diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 6a72c065..1b3538b9 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -6,7 +6,7 @@ on: - '**' push: branches: - - '**' + - 'develop' jobs: unit-tests: @@ -17,15 +17,18 @@ jobs: - uses: ./.github/actions/setup-pio with: install-unit-test-deps: 'true' - - name: Run unit tests - run: pio test -e native -v + - name: Run unit tests with coverage + if: always() + run: | + pip install gcovr + pio run -e native -t coverage - name: Publish Coverage Summary if: always() run: | echo "## Native Unit Test Coverage" >> "$GITHUB_STEP_SUMMARY" echo >> "$GITHUB_STEP_SUMMARY" - if [ -f .pio/coverage.md ]; then - cat .pio/coverage.md >> "$GITHUB_STEP_SUMMARY" + if [ -f .pio/native/coverage_report/coverage.md ]; then + cat .pio/native/coverage_report/coverage.md >> "$GITHUB_STEP_SUMMARY" else echo "Coverage report was not generated." >> "$GITHUB_STEP_SUMMARY" fi @@ -33,6 +36,7 @@ jobs: build: name: Build (${{ matrix.board }}) runs-on: ubuntu-latest + needs: unit-tests strategy: fail-fast: false matrix: @@ -47,5 +51,7 @@ jobs: - uses: ./.github/actions/setup-pio with: install-matrix-deps: 'true' + env: + PLATFORMIO_BUILD_CACHE_DIR: ${{ github.workspace }}/build_cache - name: Build ${{ matrix.board }} run: python matrix_build.py -b ${{ matrix.board }} diff --git a/matrix_build_parallel.py b/matrix_build_parallel.py index 3b7fea41..451f30b4 100644 --- a/matrix_build_parallel.py +++ b/matrix_build_parallel.py @@ -136,6 +136,12 @@ def copy_caches_to_executors(src_proj_dir: Path, dst_executors: List[Executor]): dir_names_to_copy = ['.pio', 'build_cache'] for dir_name_to_copy in dir_names_to_copy: src_path = Path(src_proj_dir, dir_name_to_copy) + # If the cache dir isn't inside the temp proj dir (e.g. when + # PLATFORMIO_BUILD_CACHE_DIR points at the repo root), try the repo root + if not src_path.exists(): + src_path = Path('.', dir_name_to_copy) + if not src_path.exists(): + continue for dst_executor in dst_executors: dst_path = Path(dst_executor.proj_dir, dir_name_to_copy) shutil.copytree(src_path, dst_path) diff --git a/platformio.ini b/platformio.ini index 03afbb86..c8ab615c 100644 --- a/platformio.ini +++ b/platformio.ini @@ -3,7 +3,6 @@ include_dir = . src_dir = ./src lib_dir = ./src/libs test_dir = ./unit_tests -build_cache_dir = ./build_cache [common] lib_deps = @@ -123,8 +122,10 @@ platform = espressif32 board = esp32dev upload_speed = 460800 monitor_filters = esp32_exception_decoder +build_unflags = -std=gnu++11 build_flags = ${env.build_flags} + -std=gnu++17 -D BOARD=BOARD_ESP32_ESP32DEV lib_deps = ${common.lib_deps} @@ -132,22 +133,31 @@ lib_deps = [env:oaeboardv1] extends = env:esp32 +build_unflags = -std=gnu++11 build_flags = ${env.build_flags} + -std=gnu++17 -D BOARD=BOARD_OAE_V1 -D ESP32BOARD [env:native] platform = native -test_ignore = test_embedded -build_flags = +test_build_src = true +build_src_filter = + +<./core> + +<./ports> + +<./adapters> +build_src_flags = + -std=gnu++17 -O0 - --coverage - -fprofile-arcs - -ftest-coverage -; Linker flag for coverage + -g + --coverage + -Wall + -Wextra + -Werror + -Wpedantic + -Wshadow +test_lib_deps = + ArduinoFake@^0.4.0 extra_scripts = scripts/test-coverage.py -test_testing_command = - /usr/bin/env - python3 - scripts/test-coverage.py - ${platformio.build_dir}/${this.__env__}/program \ No newline at end of file +test_ignore = + test_embedded diff --git a/scripts/MeadeCommandParser.py b/scripts/MeadeCommandParser.py index 40f41d9a..76875930 100644 --- a/scripts/MeadeCommandParser.py +++ b/scripts/MeadeCommandParser.py @@ -11,8 +11,8 @@ import os import re -MEADE_CPP = "..\\src\\MeadeCommandProcessor.cpp" -VERSION_FILE = "..\\Version.h" +MEADE_CPP = os.path.join("..", "src", "core", "meade", "MeadeProtocol.hpp") +VERSION_FILE = os.path.join("..", "Version.h") MODULE_PATH = os.path.dirname(os.path.realpath(__file__)) START_LINE = 0 END_LINE = 0 diff --git a/scripts/test-coverage.py b/scripts/test-coverage.py index 93330db3..22c36134 100644 --- a/scripts/test-coverage.py +++ b/scripts/test-coverage.py @@ -1,68 +1,65 @@ import os -import subprocess -from pathlib import Path import sys -from typing import TYPE_CHECKING, Any - -if TYPE_CHECKING: - def Import(*names: str) -> tuple[Any, ...]: - ... - -def _project_root(): - return Path(__file__).resolve().parent.parent - - -def _native_build_dir(): - return _project_root() / ".pio" / "build" / "native" - - -def _has_coverage_data(): - return any(_native_build_dir().rglob("*.gcda")) - - -def ensure_gcovr_installed(build_env): - """Checks if gcovr is installed, and installs it via pip if not.""" +import subprocess +Import("env") + +# Ensure the coverage flags are passed to the linker +env.Append(LINKFLAGS=["--coverage"]) + +def generate_coverage(*args, **kwargs): + print("Running tests to generate coverage data...") + # Run PlatformIO tests natively; exit(1) if any test fails + result = subprocess.run(["pio", "test", "-e", "native", "-vvv"]) + if result.returncode != 0: + print("\n❌ Tests failed — aborting coverage generation.") + sys.exit(1) + + print("\nGenerating coverage report...") + # macOS Clang uses llvm-cov, Windows/Linux use standard gcov + # gcov_tool = "llvm-cov gcov" if sys.platform == "darwin" else "gcov" + gcov_tool = "gcov" + + output_dir = os.path.join(".pio", env["PIOENV"], "coverage_report") + + # Create the output directory + os.makedirs(output_dir, exist_ok=True) + + # gcovr command to parse data and generate an HTML report + cmd = [ + "gcovr", + "--root", ".", # Ensure paths are evaluated relative to the project root + "--gcov-executable", gcov_tool, + "--html-details", os.path.join(output_dir, "index.html"), + "--markdown", os.path.join(output_dir, "coverage.md"), + + # Explicitly INCLUDE your actual source code directories + # Add "--filter", r"lib/.*" or others if you have code there too + #"--filter", r".*/core/.*", + #"--filter", r".*/src/.*", + + # Exclude the test code itself from the final metrics + "--exclude", r".pio/*", + "--exclude", r"unit_tests/*", + + # Ignore Unity testing framework errors + "--gcov-ignore-errors=no_working_dir_found", + "--gcov-ignore-errors=source_not_found", + "--print-summary" + ] + try: - import gcovr - except ImportError: - print("gcovr not found! Installing it into the PlatformIO environment...") - # $PYTHONEXE ensures we use PlatformIO's isolated Python environment, not the system OS Python - build_env.Execute("$PYTHONEXE -m pip install gcovr") - - -def generateCoverageInfo(): - if not _has_coverage_data(): - print("Skipping coverage report generation because no .gcda files were produced.") - return - - print("Generating code coverage report...") - gcovr_cmd = ["gcovr"] - report_dir = _project_root() - # Adjust this path if you are testing multiple specific folders - subprocess.run(gcovr_cmd + ["--html-details", ".pio/coverage.html", "--filter", "src/"], check=True, cwd=report_dir) - print(f"Coverage report generated at: .pio/coverage.html") - subprocess.run(gcovr_cmd + ["--markdown", ".pio/coverage.md", "--filter", "src/"], check=True, cwd=report_dir) - print(f"Coverage report generated at: .pio/coverage.md") - - -def configure_build(): - Import("env") - build_env = globals()["env"] - build_env.Append(LINKFLAGS=["--coverage"]) - ensure_gcovr_installed(build_env) - - -def main(argv): - if not argv: - print("Usage: test-coverage.py [args...]", file=sys.stderr) - return 2 - - completed = subprocess.run(argv, cwd=_project_root(), env=os.environ.copy(), check=False) - generateCoverageInfo() - return completed.returncode - - -if __name__ == "__main__": - raise SystemExit(main(sys.argv[1:])) - -configure_build() \ No newline at end of file + subprocess.run(cmd, check=True) + print("\n✅ Coverage report successfully generated: coverage_report/index.html") + except FileNotFoundError: + print("\n❌ Error: 'gcovr' not found. Please install it using 'pip install gcovr'") + except subprocess.CalledProcessError: + print("\n❌ Error: Failed to generate coverage report.") + +# Register the custom target in PlatformIO +env.AddCustomTarget( + name="coverage", + dependencies=None, + actions=[generate_coverage], + title="Coverage Report", + description="Run native tests and generate an HTML code coverage report" +) \ No newline at end of file diff --git a/specs/plan.md b/specs/plan.md index 535b969d..a095dd65 100644 --- a/specs/plan.md +++ b/specs/plan.md @@ -4,7 +4,7 @@ Refactor a ~5k-line `Mount` god-object firmware toward clean architecture for embedded: a pure **Domain Core** (no Arduino, fully unit-testable) sitting behind **Port interfaces**, with **Adapters** wrapping hardware (AccelStepper, TMC2209, EEPROM, displays, Wi-Fi, clock). -Approach: **hybrid** — extract pure logic in place first to build a regression-prevention test net (Unity + FFF on the existing `native` PIO env), then **strangler-fig** the hardware-coupled pieces (drivers, slewing loop, command executor) behind ports. Compile-time `#ifdef` axes/drivers migrate to **runtime polymorphism** so unsupported combinations no longer change the call graph. Goal endpoint: `src/core/` is buildable & 100% unit-tested on host; `src/adapters/` contains all Arduino/library coupling; `src/app/` wires them up per board. +Approach: **hybrid** — extract pure logic in place first to build a regression-prevention test net (Unity + FakeIt via ArduinoFake on the existing `native` PIO env), then **strangler-fig** the hardware-coupled pieces (drivers, slewing loop, command executor) behind ports. Compile-time `#ifdef` axes/drivers migrate to **runtime polymorphism** so unsupported combinations no longer change the call graph. Goal endpoint: `src/core/` is buildable & 100% unit-tested on host; `src/adapters/` contains all Arduino/library coupling; `src/app/` wires them up per board. --- @@ -26,8 +26,9 @@ Five layers, dependencies point inward only. The **HAL** sits between domain por | | IEeprom, IStepperMotor, ITmcDriver, IOledPanel,| | | ICharLcd, IButtonMatrix, ITimerService, | | | ISystemClock, IWifiStack. | -| | Backends: hal/arduino/, hal/esp32/, hal/avr/, | -| | hal/host/ (for native tests). | +| | Backends: hal/arduino/, hal/esp32/, hal/avr/. | +| | Host-side fakes for unit tests live under | +| | unit_tests/test_common/ (test code, not src/). | | v | | ports/ domain-level interfaces consumed by core: | | | IClock, ILogger, IPersistentStore, IStepperAxis, | @@ -39,7 +40,7 @@ Five layers, dependencies point inward only. The **HAL** sits between domain por | GuidingController, TrackingController, | | ParkingController, HomingController, | | FocusController, SiderealClock, MeadeParser, | -| MeadeExecutor, MountConfig, EventBus. | +| MountConfig, EventBus. | +----------------------------------------------------------------+ ``` @@ -57,21 +58,55 @@ Cross-cutting: --- +## Current State (after Meade parser migration) + +### ✅ Completed: Meade parser migrated to `core/` + +The Meade LX200 command parser has been fully extracted into `src/core/meade/` as a pure, host-testable, allocation-light parser with no side effects. The split is: + +| Layer | Location | Status | +|-------|----------|--------| +| **Parser** (pure) | `src/core/meade/MeadeParser.*` + 11 family-specific `.cpp` files | ✅ Done — 100% covered by 13 test files in `unit_tests/test_meade/` | +| **Protocol spec** | `src/core/meade/MeadeProtocol.hpp` | ✅ Done — comprehensive protocol documentation | +| **Handler interfaces** | `src/core/meade/MeadeParser.hpp` (12 `IMeade*Handlers` interfaces + aggregate `IMeadeHandlers`) | ✅ Done — clean typed contracts | +| **Executor/Adapter** | `src/MeadeCommandProcessor.hpp/cpp` | ✅ Done — implements `IMeadeHandlers`, delegates to `Mount`/`LcdMenu` | + +The parser directory (`src/core/meade/`) contains 16 files covering all 12 command families (Get, Set, Quit, Distance, Init, SyncControl, Home, SlewRate, GPS, Focus, Movement, Extra). Each family has: +- A typed handler interface (e.g. `IMeadeGetHandlers`, `IMeadeMovementHandlers`) +- A `handleMeade*` entry point that parses suffixes, invokes handler callbacks, and serializes `MeadeResponse` +- Value types for coordinates (e.g. `RaCoordinate`, `DecCoordinate`) + +The `MeadeCommandProcessor` adapter bridges the parser to the legacy `Mount` singleton, implementing all ~90 handler overrides. It is the **only** file in `src/` root that references the core parser. + +### Test coverage + +13 test files in `unit_tests/test_meade/` provide comprehensive wire-byte coverage for every parser family using fake handler stubs. Tests verify: +- Exact wire-byte formatting (zero-padding, sign rules, terminators) +- Suffix classification and handler dispatch routing +- Edge cases (malformed input, overflow, unknown sub-commands) +- Parser-level validation (the `parseMeadeCommand` classifier) + +### What remains + +The parser is pure and tested. The executor (`MeadeCommandProcessor`) is an adapter that still couples to `Mount*` and `LcdMenu*` directly. The `Mount` god-object still contains all domain logic (slewing, tracking, guiding, parking, homing, focus, coordinate math). No HAL, ports, or controllers exist yet beyond the meade parser. + +--- + ## Phased Plan (each phase shippable & green in CI) -### Phase 0 — Safety net & tooling (no behavior change) -*Foundation for everything else; must land first.* +### Phase 0 — Safety net & tooling (no behavior change) ✅ COMPLETE +*Foundation for everything else; must land first. Already implemented — see audit below.* + +1. ~~Add FFF as header-only dep~~ — **Superseded.** FakeIt (bundled with ArduinoFake) replaces FFF. No separate FFF needed. +2. ~~Add `native_core` PIO env~~ — **Superseded.** Only the `native` env is used. The existing `native` env already has strict warnings (`-Wall -Wextra -Werror -Wpedantic -Wshadow`). +3. ✅ gcovr-based **coverage reporting** in `native` env — **Done.** `scripts/test-coverage.py` + `--coverage` flag in `build_src_flags`. `pio run -e native -t coverage` produces HTML + markdown reports. Current: 88.3% lines, 97.0% functions, 76.5% branches. +4. ✅ CI workflow — **Done.** `.github/workflows/ci.yml` runs `pio run -e native -t coverage` (which internally executes `pio test -e native -vvv`), publishes coverage markdown to step summary. Threshold gating deferred to a later phase. +5. ✅ **ArduinoFake** as `test_lib_deps` — **Done.** Configured in `platformio.ini` `[env:native]` as `ArduinoFake@^0.4.0`. Provides stubbing/verification via FakeIt-based API for Arduino API mocking (`millis`, `String`, `pinMode`, `digitalWrite`, fake `EEPROM`, fake `Serial`, fake `Wire`, fake `SPI`). +6. ✅ Folder structure — **Done.** `src/ports/`, `src/hal/`, `src/adapters/`, `src/app/` all exist with descriptive README files. -1. Add **Fake Function Framework (FFF)** as a header-only dep in `unit_tests/test_common/fakes/`. -2. Add a new PIO env `native_core` (extends `native`) with stricter warnings (`-Wall -Wextra -Werror`) for host-only `core/` builds; keep existing `native` for compatibility. -3. Add gcovr/lcov-based **coverage reporting** to the `native` env; publish summary in CI. -4. Extend `.github/workflows/platformio_unit_tests.yml`: - - Run `pio test -e native -v`. - - Run coverage and fail if `core/` coverage drops below configured threshold (start at 0, ratchet upward). -5. Add a tiny **Arduino host shim** under `unit_tests/test_common/arduino_shim/` providing minimal stubs (`millis`, `String`, `pinMode`, `digitalWrite`, fake `EEPROM`, fake `Serial`) for files that include `` but whose logic we want to test on host. This shim will later be replaced by the proper `hal/host/` backend (Phase 3). -6. Establish folders: `src/core/`, `src/ports/`, `src/hal/`, `src/hal/host/`, `src/adapters/`, `src/app/` (empty + READMEs); leave existing files in place. +**Verify:** `pio test -e native -v` → 170 tests, 0 failures; coverage report generates; all 5 board matrix builds green via `matrix_build.py`. -**Verify:** `pio test -e native -v` green; coverage report artifact produced in CI; build for all existing boards still green via `matrix_build.py`. +**Changes from original plan (per feedback):** FFF replaced by FakeIt (in ArduinoFake); `native_core` env eliminated (use `native` only); coverage threshold gating deferred to a later phase. ### Phase 1 — Characterize existing pure logic (regression net) *All pure-logic files identified by the audit get exhaustive tests before being moved.* @@ -85,7 +120,7 @@ Steps (parallel after Phase 0): - `Mount::syncPosition` math. - `Mount::getLocalDate` calendar increment (leap years, year/month wrap). - `Mount::DECString` / `Mount::RAString` formatting. - These tests link against a stripped-down `Mount` compiled with the host shim — they fail the moment behavior shifts during extraction. + These tests link against a stripped-down `Mount` compiled with ArduinoFake — they fail the moment behavior shifts during extraction. **Verify:** All new tests green; coverage report shows non-trivial line coverage on the listed methods; CI threshold ratcheted up. @@ -97,7 +132,7 @@ Steps (parallel after Phase 0): 3. Create `core/CalendarMath` from `Mount::getLocalDate`. 4. Create `core/CoordinateFormatter` from RA/DEC string formatters. 5. Create `core/MountGeometry` value type holding steps-per-degree, calibration angles, hemisphere, backlash — replaces scattered Mount fields used by math. -6. Create `core/MeadeParser` by splitting `MeadeCommandProcessor`: pure tokenize/dispatch lookup tables in `core/`; execution stays in adapter for now. +6. ~~Create `core/MeadeParser` by splitting `MeadeCommandProcessor`: pure tokenize/dispatch lookup tables in `core/`; execution stays in adapter for now.~~ **✅ DONE** — Meade parser is already in `core/meade/` with 12 family-specific handler interfaces, 13 comprehensive test files, and `MeadeCommandProcessor` as the adapter implementing `IMeadeHandlers`. **Verify:** Phase 1 tests still green unchanged; firmware binary for each board builds identically (size diff ≈ 0); new `core/` files all covered by host tests. @@ -114,7 +149,7 @@ Steps (parallel after Phase 0): - `hal/arduino/` — generic Arduino implementation (`ArduinoGpioPin`, `ArduinoSerialPort`, `ArduinoEeprom`, `ArduinoSystemClock`, …). - `hal/avr/` — AVR-specific bits (Timer1/Timer3 interrupt service, fast pin IO). - `hal/esp32/` — ESP32-specific (hardware timers, Wi-Fi stack glue). - - `hal/host/` — pure C++ test backend (in-memory EEPROM, virtual GPIO, controllable clock); replaces and absorbs the Phase 0 ad-hoc shim. + - `unit_tests/test_common/hal_fakes/` — pure C++ test fakes (in-memory EEPROM, virtual GPIO, controllable clock, fake serial). Lives in test code, **not** in `src/`. Complements ArduinoFake (ArduinoFake handles the Arduino API layer; hal_fakes handles custom HAL interfaces). 3. Define domain **ports** in `src/ports/`: - `IClock`, `ILogger`, `IPersistentStore`, - `IStepperAxis` (position, target, speed, accel, run, stop, isRunning, `Snapshot()` for ISR safety), @@ -131,7 +166,7 @@ Steps (parallel after Phase 0): 5. Refactor `Mount` to **hold port pointers** (`IStepperAxis* _ra; IClock* _clock; ...`) injected at construction instead of owning concrete types. Composition happens in `app/` (currently `b_setup.hpp`). 6. Replace direct `millis()`, `digitalWrite()`, `EEPROMStore::` calls inside `Mount` with port calls; replace `LOG()` macro with `_logger->log(...)`. -**Verify:** All Phase 1/2 tests still green; new contract tests for each port using `hal::host` backends (e.g., `EepromPersistentStore` round-trips via in-memory `hal::host::HostEeprom`); golden-master tests on `Mount` still pass; firmware builds identical-sized binaries on at least one board (other variants ±1%). +**Verify:** All Phase 1/2 tests still green; new contract tests for each port using HAL fakes from `unit_tests/test_common/hal_fakes/` (e.g., `EepromPersistentStore` round-trips via an in-memory `FakeEeprom`); golden-master tests on `Mount` still pass; firmware builds identical-sized binaries on at least one board (other variants ±1%). ### Phase 4 — Decompose `Mount` into controllers *Strangler-fig: move responsibilities out of `Mount` into `core/` controllers, one at a time. Mount becomes a facade.* @@ -147,7 +182,7 @@ Recommended slice order (each is an independent step, parallelizable after Phase 8. `core/MountState` — single source of truth for the `_mountStatus` bitfield, with typed enum API (`Status::isSlewing()` etc.). Controllers mutate `MountState`; Mount facade reads it. 9. `core/EventBus` — controllers publish `PositionChanged`, `SlewStarted`, `Parked`, etc.; display adapter subscribes (removes Mount → display direct coupling). -Each step: extract → add focused unit tests with FFF-faked ports → remove the original code from `Mount.cpp` → ship. +Each step: extract → add focused unit tests with FakeIt-faked ports → remove the original code from `Mount.cpp` → ship. **Verify per step:** unit tests for the new controller; golden-master tests on `Mount` still green; firmware behavior on hardware unchanged (manual smoke checklist). @@ -162,15 +197,16 @@ Each step: extract → add focused unit tests with FFF-faked ports → remove th **Verify:** `core/` and `ports/` contain zero `#ifdef` for features (CI grep check); all 5 existing board matrix builds still pass; binary size delta within budget (set explicit per-board limit, e.g., +3% allowed). -### Phase 6 — Meade execution layer -*Finish what Phase 2 started: separate parser from executor.* +### Phase 6 — Meade execution layer cleanup +*The parser is already in `core/`. This phase finishes the Meade slice by refining the executor and transport layers.* -1. `core/MeadeExecutor` operating on controller interfaces (no `Mount*`). -2. `adapters/SerialTransport` + `adapters/WifiTransport` feed bytes to `MeadeParser`; parsed commands dispatch to `MeadeExecutor`. -3. Remove `Mount* _mount` from `MeadeCommandProcessor` and the legacy `Mount::delay()` blocking call. -4. Add a comprehensive Meade-protocol test suite using `scripts/MeadeCommandParser.py` traces as fixtures. +1. `MeadeCommandProcessor` (current adapter) is already in `src/` root implementing `IMeadeHandlers` → move it to `src/adapters/MeadeCommandAdapter` to match layer conventions. +2. Introduce `adapters/SerialTransport` + `adapters/WifiTransport` to feed bytes to `core/meade/MeadeParser`; parsed commands dispatch to the adapter. +3. Remove `Mount* _mount` raw pointer from `MeadeCommandProcessor` — replace with port-based interfaces from Phase 3/4 (e.g. `IMeadeHandlers` implemented over controller interfaces, not the god-object). +4. Remove the legacy `Mount::delay()` blocking call from GPS acquisition handler — replace with `IClock`-based non-blocking state machine. +5. The existing 13 test files in `unit_tests/test_meade/` already cover all parser families. Add integration tests wiring `SerialTransport` → `MeadeParser` → `MeadeCommandAdapter` with faked ports. -**Verify:** Meade test suite green; Stellarium/ASCOM round-trip smoke test (manual) recorded as a regression checklist; coverage of `core/` ≥ 80%. +**Verify:** Meade test suite green (existing 13 files + new integration tests); Stellarium/ASCOM round-trip smoke test (manual) recorded as a regression checklist; coverage of `core/meade/` ≥ 80% (already achieved). ### Phase 7 — Cleanup & documentation 1. Mount facade slimmed to a thin compat shim (or removed if no external dependents). @@ -182,18 +218,30 @@ Each step: extract → add focused unit tests with FFF-faked ports → remove th --- -## Relevant files (initial focus) +## Relevant files + +### Already migrated to `core/` +- [`src/core/meade/`](src/core/meade/) — 16 files: parser, 12 family dispatchers, helpers, protocol spec, typed handler interfaces +- [`unit_tests/test_meade/`](unit_tests/test_meade/) — 13 test files covering all parser families with fake handler stubs + +### Phase 0–1 targets +- [`src/Mount.cpp`](src/Mount.cpp), [`src/Mount.hpp`](src/Mount.hpp) — the god-object being decomposed; `loop()`, `calculateRAandDECSteppers()`, `guidePulse()`, `startSlewing()`, `readPersistentData()` are the biggest extraction targets. +- [`src/Sidereal.cpp`](src/Sidereal.cpp), [`src/DayTime.cpp`](src/DayTime.cpp), [`src/Declination.cpp`](src/Declination.cpp), [`src/Latitude.cpp`](src/Latitude.cpp), [`src/Longitude.cpp`](src/Longitude.cpp) — already pure; move into `core/` in Phase 2. +- [`src/EPROMStore.cpp`](src/EPROMStore.cpp), [`src/EPROMStore.hpp`](src/EPROMStore.hpp) — already a good seam; becomes `IPersistentStore` + adapter. + +### Phase 2–3 targets +- [`src/HallSensorHoming.cpp`](src/HallSensorHoming.cpp), [`src/EndSwitches.cpp`](src/EndSwitches.cpp), [`src/Gyro.cpp`](src/Gyro.cpp), [`src/LcdMenu.cpp`](src/LcdMenu.cpp), [`src/SSD1306_128x64_Display.cpp`](src/SSD1306_128x64_Display.cpp), [`src/WifiControl.cpp`](src/WifiControl.cpp), [`src/LcdButtons.cpp`](src/LcdButtons.cpp) — become adapters behind ports. +- [`src/Core.cpp`](src/Core.cpp), [`src/a_inits.hpp`](src/a_inits.hpp), [`src/b_setup.hpp`](src/b_setup.hpp), [`src/f_serial.hpp`](src/f_serial.hpp) — wiring code gradually migrates into `src/app/`. + +### Phase 6 targets +- [`src/MeadeCommandProcessor.cpp`](src/MeadeCommandProcessor.cpp), [`src/MeadeCommandProcessor.hpp`](src/MeadeCommandProcessor.hpp) — adapter already bridges parser to `Mount`; move to `src/adapters/` and wire through ports. +- [`src/f_serial.hpp`](src/f_serial.hpp) — serial framing code that calls `MeadeCommandProcessor::instance()->processCommand()`; becomes `SerialTransport` adapter. -- [src/Mount.cpp](../src/Mount.cpp), [src/Mount.hpp](../src/Mount.hpp) — the god-object being decomposed; `loop()`, `calculateRAandDECSteppers()`, `guidePulse()`, `startSlewing()`, `readPersistentData()` are the biggest extraction targets. -- [src/MeadeCommandProcessor.cpp](../src/MeadeCommandProcessor.cpp), [src/MeadeCommandProcessor.hpp](../src/MeadeCommandProcessor.hpp) — split into parser (`core/`) + executor (Phase 6). -- [src/EPROMStore.cpp](../src/EPROMStore.cpp), [src/EPROMStore.hpp](../src/EPROMStore.hpp) — already a good seam; becomes `IPersistentStore` + adapter. -- [src/Sidereal.cpp](../src/Sidereal.cpp), [src/DayTime.cpp](../src/DayTime.cpp), [src/Declination.cpp](../src/Declination.cpp), [src/Latitude.cpp](../src/Latitude.cpp), [src/Longitude.cpp](../src/Longitude.cpp) — already pure; move into `core/` in Phase 2. -- [src/HallSensorHoming.cpp](../src/HallSensorHoming.cpp), [src/EndSwitches.cpp](../src/EndSwitches.cpp), [src/Gyro.cpp](../src/Gyro.cpp), [src/LcdMenu.cpp](../src/LcdMenu.cpp), [src/SSD1306_128x64_Display.cpp](../src/SSD1306_128x64_Display.cpp), [src/WifiControl.cpp](../src/WifiControl.cpp), [src/LcdButtons.cpp](../src/LcdButtons.cpp) — become adapters behind ports. -- [src/Core.cpp](../src/Core.cpp), [src/a_inits.hpp](../src/a_inits.hpp), [src/b_setup.hpp](../src/b_setup.hpp), [src/f_serial.hpp](../src/f_serial.hpp) — wiring code gradually migrates into `src/app/`. -- [platformio.ini](../platformio.ini) — add `native_core` env, coverage flags, FFF include path. -- [.github/workflows/platformio_unit_tests.yml](../.github/workflows/platformio_unit_tests.yml) — coverage gating, ratchet. -- [unit_tests/test_common/](../unit_tests/test_common/test_MappedDict.cpp), [unit_tests/test_embedded/](../unit_tests/test_embedded/main.cpp) — expand with FFF-based ports tests. -- [Configuration.hpp](../Configuration.hpp), [Configuration_adv.hpp](../Configuration_adv.hpp) — read once by `MountConfig` builder in Phase 5. +### Infrastructure +- [`platformio.ini`](platformio.ini) — `native` env with coverage flags, ArduinoFake `test_lib_deps`, coverage extra script. +- [`.github/workflows/ci.yml`](.github/workflows/ci.yml) — runs `pio run -e native -t coverage` + publishes summary; builds all 5 boards. +- [`unit_tests/test_common/`](unit_tests/test_common/) — expand with FakeIt-based port fakes for Phase 3+. +- [`Configuration.hpp`](Configuration.hpp), [`Configuration_adv.hpp`](Configuration_adv.hpp) — read once by `MountConfig` builder in Phase 5. --- @@ -217,7 +265,7 @@ Manual smoke checklist (per shippable phase end): ## Decisions -- **Test stack:** Unity (already in PIO) + **FFF (Fake Function Framework)** for mocking Arduino/library calls. No GoogleTest. +- **Test stack:** Unity (already in PIO) + **FakeIt** (via ArduinoFake) for mocking Arduino/library calls. No GoogleTest. - **Migration style:** **Hybrid** — extract pure logic in place first (Phase 1–2), then strangler-fig hardware-coupled layers (Phase 3–6). - **Config flags:** Migrate to **runtime polymorphism behind interfaces**; composition root reads the `Configuration*.hpp` macros once. `core/` becomes `#ifdef`-free for features. - **Back-compat:** Meade serial protocol behavior is invariant (external interface); internal C++ APIs may change freely. @@ -225,6 +273,6 @@ Manual smoke checklist (per shippable phase end): ## Further Considerations -1. **C++ standard.** `core/` benefits from at least C++17 (`std::optional`, `std::variant`, `if constexpr`). PlatformIO defaults vary by board (some AVR ports stuck on C++11/14). *Recommendation:* set `build_flags = -std=gnu++17` for `native_core`; verify each board env supports it (likely yes on current toolchains) — fall back to `-std=gnu++14` + tagged unions if AVR pinches. +1. **C++ standard.** `core/` benefits from at least C++17 (`std::optional`, `std::variant`, `if constexpr`). PlatformIO defaults vary by board (some AVR ports stuck on C++11/14). *Recommendation:* set `build_flags = -std=gnu++17` for the `native` env; verify each board env supports it (likely yes on current toolchains) — fall back to `-std=gnu++14` + tagged unions if AVR pinches. 2. **Binary size on AVR_MEGA2560.** Polymorphism + extra indirection costs flash on AVR. *Recommendation:* keep vtables small (≤ ~12 ports), mark adapters `final`, allow link-time devirtualization. If we still bust the budget, accept template-based static dispatch for the hot path (`SlewController`) — adds complexity but keeps AVR shipping. -3. **Interrupt-driven stepping.** `InterruptAccelStepper` mutates state from ISR context. Ports for axes need explicit thread/ISR-safety contract documented; `core/` controllers must never assume single-threaded access to axis state. *Recommendation:* document this in `ports/IStepperAxis.h`; add a `Snapshot()` method returning a consistent state read.\n \ No newline at end of file +3. **Interrupt-driven stepping.** `InterruptAccelStepper` mutates state from ISR context. Ports for axes need explicit thread/ISR-safety contract documented; `core/` controllers must never assume single-threaded access to axis state. *Recommendation:* document this in `ports/IStepperAxis.h`; add a `Snapshot()` method returning a consistent state read. diff --git a/src/MeadeCommandProcessor.cpp b/src/MeadeCommandProcessor.cpp index 04b04417..1585c802 100644 --- a/src/MeadeCommandProcessor.cpp +++ b/src/MeadeCommandProcessor.cpp @@ -6,6 +6,7 @@ #include "MeadeCommandProcessor.hpp" #include "WifiControl.hpp" #include "Gyro.hpp" +#include "core/meade/MeadeParser.hpp" #include #include @@ -13,1229 +14,15 @@ #if USE_GPS == 1 bool gpsAqcuisitionComplete(int &indicator); // defined in c72_menuHA_GPS.hpp #endif -///////////////////////////////////////////////////////////////////////////////////////// -// -// Serial support -// -// The Serial protocol implemented here is the Meade LX200 Classic protocol with some extensions. -// The Meade protocol commands start with a colon and end with a hash. -// The first letter determines the family of functions (G for Get, S for Set, M for Movement, etc.) -// -// The set of Meade features implemented are: -// -//------------------------------------------------------------------ -// INITIALIZE FAMILY -// -// :I# -// Description: -// Initialize Scope -// Information: -// This puts the Arduino in Serial Control Mode and displays RA on line 1 and -// DEC on line 2 of the display. Serial Control Mode can be ended manually by -// pressing the SELECT key, or programmatically with the :Qq# command. -// Returns: -// nothing -// -//------------------------------------------------------------------ -// SYNC CONTROL FAMILY -// -// :CM# -// Description: -// Synchronize Declination and Right Ascension. -// Information: -// This tells the scope what it is currently pointing at. The scope synchronizes -// to the current target coordinates -// Remarks: -// Set with ":Sd#" and ":Sr#" -// Returns: -// "NONE#" -// -//------------------------------------------------------------------ -// DISTANCE FAMILY -// -// :D# -// Description: -// Query Mount Status -// Information: -// This queries the mount for its slewing status -// Returns: -// "|#" if slewing -// " #" if not -// -//------------------------------------------------------------------ -// GPS FAMILY -// -// :gT# -// Description: -// Set Mount Time -// Information: -// Attempts to set the mount time and location from the GPS for 2 minutes. This is essentially a -// blocking call, no other activities take place (except tracking, but only if interrupt-driven). -// Remarks: -// Use ":Gt#" and ":Gg#" to retrieve Lat and Long, -// Returns: -// "1" if the data was set -// "0" if not (timedout) -// -// :gTnnn# -// Description: -// Set Mount Time w/ timeout -// Information: -// Attempts to set the mount time and location from the GPS with a custom timeout. This is also blocking -// but by using a low timeout, you can avoid long pauses and let the user know that it's not ready yet. -// Returns: -// "1" if the data was set -// "0" if not (timedout) -// Parameters: -// "nnn" is an integer defining the number of milliseconds to wait for the GPS to get a bearing -// -//------------------------------------------------------------------ -// GET FAMILY -// -// :GVP# -// Description: -// Get the Product Name -// Returns: -// "OpenAstroTracker#" if the firmware was compiled for OAT -// "OpenAstroMount#" if the firmware was compiled for OAM -// -// :GVN# -// Description: -// Get the Firmware Version Number -// Returns: -// "V1.major.minor#" from version.h -// -// :Gd# -// Description: -// Get Target Declination -// Returns: -// "sDD*MM'SS#" -// Parameters: -// "s" is + or - -// "DD" is degrees -// "MM" is minutes -// "SS" is seconds -// -// :GD# -// Description: -// Get Current Declination -// Returns: -// "sDD*MM'SS#" -// Parameters: -// "s" is + or - -// "DD" is degrees -// "MM" is minutes -// "SS" is seconds. -// -// :Gr# -// Description: -// Get Target Right Ascension -// Returns: -// HH:MM:SS# -// Parameters: -// "HH" is hour -// "MM" is minutes -// "SS" is seconds -// -// :GR# -// Description: -// Get Current Right Ascension -// Returns: -// "HH:MM:SS#" -// Parameters: -// "HH" is hour -// "MM" is minutes -// "SS" is seconds -// -// :Gt# -// Description: -// Get Site Latitude -// Returns: -// "sDD*MM#" -// Parameters: -// "s" is + or - -// "DD" is the latitude in degrees -// "MM" the minutes -// -// :Gg# -// Description: -// Get Site Longitude -// Returns: -// "sDDD*MM#" -// Parameters: -// "s" is the sign of the longitude -// "DDD" is the degrees -// "MM" is the minutes -// Remarks: -// Note that this is the actual longitude, but east coordinates are negative (opposite of normal cartographic coordinates) -// -// :Gc# -// Description: -// Get current Clock format -// Returns: -// "24#" -// -// :GG# -// Description: -// Get offset to UTC time -// Returns: -// "sHH#" -// Parameters: -// "s" is the sign -// "HH" is the number of hours -// Remarks: -// Note that this is NOT simply the timezone offset you are in (like -8 for Pacific Standard Time), it is the negative of it. So how many hours need to be added to your local time to get to UTC. -// -// :Ga# -// Description: -// Get local time in 12h format -// Returns: -// "HH:MM:SS#" -// Parameters: -// "HH" are hours (modulo 12) -// "MM" are minutes -// "SS" are seconds of the local time -// -// :GL# -// Description: -// Get local time in 24h format -// Returns: -// "HH:MM:SS#" -// Parameters: -// "HH" are hours -// "MM" are minutes -// "SS" are seconds of the local time -// -// :GC# -// Description: -// Get current date -// Returns: -// "MM/DD/YY#" -// Parameters: -// "MM" is the month (1-12) -// "day" is the day (1-31) -// "year" is the lower two digits of the year -// -// :GM# -// Description: -// Get Site Name 1 -// Returns: -// "OAT1#" -// -// :GN# -// Description: -// Get Site Name 2 -// Returns: -// "OAT2#" -// -// :GO# -// Description: -// Get Site Name 3 -// Returns: -// OAT2# -// -// :GP# -// Description: -// Get Site Name 4 -// Returns: -// OAT4# -// -// :GT# -// Description: -// Get tracking rate -// Returns: -// 60.0# -// -//------------------------------------------------------------------ -// GET EXTENSIONS -// -// :GIS# -// Description: -// Get DEC or RA Slewing -// Returns: -// "1#" if either RA or DEC is slewing -// "0#" if not -// -// :GIT# -// Description: -// Get Tracking -// Returns: -// "1#" if tracking is on -// "0#" if not -// -// :GIG# -// Description: -// Get Guiding -// Returns: -// "1#" if currently guiding -// "0#" if not -// -// :GX# -// Description: -// Get Mount Status -// Information: -// String reflecting the mounts' status. The string is a comma-delimited list of statuses. -// Returns: -// "Idle,--T--,11219,0,927,071906,+900000,,#" -// Parameters: -// [0] The mount status. One of 'Idle', 'Parked', 'Parking', 'Guiding', 'SlewToTarget', 'FreeSlew', 'ManualSlew', 'Tracking', 'Homing' -// [1] The motion state (see Remarks below). -// [2] The RA stepper position -// [3] The DEC stepper position -// [4] The Tracking stepper position -// [5] The current RA coordinate -// [6] The current DEC coordinate -// [7] The FOC stepper position (if FOC enabled, else empty) -// Remarks: -// The motion state consists of 6 characters. If the character is a '-', the corresponding axis is not moving. -// First character is RA slewing state ('R' is East, 'r' is West, '-' is stopped). -// Second character is DEC slewing state ('d' is North, 'D' is South, '-' is stopped). -// Third character is TRK slewing state ('T' is Tracking, '-' is stopped). -// Fourth character is AZ slewing state ('Z' and 'z' is adjusting, '-' is stopped). -// Fifth character is ALT slewing state ('A' and 'a' is adjusting, '-' is stopped). -// Sixth character is FOC slewing state ('F' and 'f' is adjusting, '-' is stopped). -// AZ, ALT, and FOC are only set if the corresponding axis is enabled. If not, the character is always '-'. -// Since AZ/ALT rarely move, their positions are not returned here. To get the AZ and ALT stepper positions, use the ":XGAA#" command. -// -//------------------------------------------------------------------ -// SET FAMILY -// -// :SdsDD*MM:SS# -// Description: -// Set Target Declination -// Information: -// This sets the target DEC. Use a Movement command to slew there. -// Parameters: -// "s" is + or - -// "DD" is degrees -// "MM" is minutes -// "SS" is seconds -// Returns: -// "1" if successfully set -// "0" otherwise -// -// :SrHH:MM:SS# -// Description: -// Set Right Ascension -// Information: -// This sets the target RA. Use a Movement command to slew there. -// Returns: -// "1" if successfully set -// "0" otherwise -// Parameters: -// "HH" is hours -// "MM" is minutes -// "SS" is seconds -// -// :StsDD*MM# -// Description: -// Set Site Latitude -// Information: -// This sets the latitude of the location of the mount. -// Returns: -// "1" if successfully set -// "0" otherwise -// Parameters: -// "s" is the sign ('+' or '-') -// "DD" is the degree (90 or less) -// "MM" is minutes -// -// :SgsDDD*MM# -// Description: -// Set Site Longitude -// Information: -// This sets the longitude of the location of the mount. -// Returns: -// "1" if successfully set -// "0" otherwise -// Parameters: -// "s" (optional) is the sign of the longitude (see Remarks) -// "DDD" is the number of degrees -// "MM" is the minutes -// Remarks: -// When a sign is provided, longitudes are interpreted as given, with zero at Greenwich but negative coordinates going east (opposite of normal cartographic coordinates) -// When a sign is not provided, longitudes are from 0 to 360 going WEST with 180 at Greenwich. So 369 is 179W and 1 is 179E. 190 would be 10W and 170 would be 10E. -// -// :SGsHH# -// Description: -// Set Site UTC Offset -// Information: -// This sets the offset of the timezone in which the mount is in hours from UTC. -// Returns: -// "1" -// Parameters: -// "s" is the sign -// "HH" is the number of hours -// -// :SLHH:MM:SS# -// Description: -// Set Site Local Time -// Information: -// This sets the local time of the timezone in which the mount is located. -// Returns: -// "1" -// Parameters: -// "HH" is hours -// "MM" is minutes -// "SS" is seconds -// -// :SCMM/DD/YY# -// Description: -// Set Site Date -// Information: -// This sets the date -// Returns: -// "1Updating Planetary Data# #" -// Parameters: -// "MM" is the month -// "DD" is the day -// "YY" is the year since 2000 -// -//------------------------------------------------------------------ -// SET Extensions -// -// :SHHH:MM# -// Description: -// Set HA (Hour Angle of Polaris) -// Information: -// This sets the scopes HA, which should be that of Polaris. -// Returns: -// "1" if successfully set -// "0" otherwise -// Parameters: -// "HH" is hours -// "MM" is minutes -// -// :SHP# -// Description: -// Set Home Point -// Information: -// This sets the current orientation of the scope as its home point. -// Returns: -// "1" -// -// :SHLHH:MM# -// Description: -// Set LST Time -// Information: -// This sets the scopes LST (and HA). -// Returns: -// "1" if successfully set -// "0" otherwise -// Parameters: -// "HH" is hours -// "MM" is minutes -// -// :SYsDD*MM:SS.HH:MM:SS# -// Description: -// Synchronize Declination and Right Ascension. -// Information: -// This tells the scope what exact coordinates it is currently pointing at. These coordinates become the new current RA/DEC coordinates of the mount. -// Returns: -// "1" if successfully set -// "0" otherwise -// Parameters: -// "s" is + or - -// "DD" is degrees -// "HH" is hours -// "MM" is minutes -// "SS" is seconds -// -//------------------------------------------------------------------ -// RATE CONTROL FAMILY -// -// :Rs# -// Description: -// Set Slew rate -// Parameters: -// "s" is one of 'S', 'M', 'C', or 'G' in order of decreasing speed -// Returns: -// nothing -// -//------------------------------------------------------------------ -// MOVEMENT FAMILY -// -// :MS# -// Description: -// Start Slew to Target (Asynchronously) -// Information: -// This starts slewing the scope to the target RA and DEC coordinates and returns immediately. -// Returns: -// "0" -// -//------------------------------------------------------------------ -// MOVEMENT EXTENSIONS -// -// :MGdnnnn# -// Description: -// Run a Guide pulse -// Information: -// This runs the RA or DEC steppers at an increased or decreased speed (in the case of RA) or a constant speed (in the case of DEC) for a short period of time. It is used for guiding. -// Parameters: -// "d" is one of 'N', 'E', 'W', or 'S' -// "nnnn" is the duration in ms -// Returns: -// "1" -// -// :MTs# -// Description: -// Set Tracking mode -// Information: -// This turns the scopes tracking mode on or off. -// Parameters: -// "s" is "1" to turn on Tracking and "0" to turn it off -// Returns: -// "1" -// -// :Mc# -// Description: -// Start slewing -// Information: -// This starts slewing the mount in the given direction. You must issue a stop command (such as the corresponding ":Qc#", -// where 'c' is the same direction as passed to this command) or ":Q#" (stops all steppers) to stop it. -// Parameters: -// "c" is one of 'n', 'e', 'w', or 's' -// Returns: -// nothing -// -// :MXxnnnnn# -// Description: -// Move stepper -// Information: -// This starts moving one of the steppers by the given amount of steps and returns immediately. Steps can be positive or negative. -// Parameters: -// "x" is the stepper to move (r for RA, d for DEC, f for FOC, z for AZ, l for ALT) -// "nnnn" is the number of steps -// Returns: -// "1" if successfully scheduled, else "0" -// -// :MHRxn# -// Description: -// Home RA stepper via Hall sensor -// Information: -// This attempts to find the hall sensor and to home the RA ring accordingly. -// Parameters: -// "x" is either 'R' or 'L' and determines the direction in which the search starts (L is CW, R is CCW). -// "n" (Optional) is the maximum number of degrees to move while searching for the sensor location. Defaults to 30degs. Limited to the range 5degs - 75degs. -// Remarks: -// The ring is first moved 30 degrees (or the given amount) in the initial direction. If no hall sensor is encountered, -// it will move twice the amount (60 degrees by default) in the opposite direction. -// If a hall sensor is not encountered during that slew, the homing exits with a failure. -// If the sensor is found, it will slew to the middle position of the Hall sensor trigger range and then to the offset -// specified in the Home offset position (set with the ":XSHRnnnn#" command). -// If the RA ring is positioned such that the Hall sensor is already triggered when the command is received, the mount will move -// the RA ring off the trigger in the opposite direction specified for a max of 15 degrees before searching 30 degrees in the -// specified direction. -// Returns: -// "1" if search is started -// "0" if homing has not been enabled in the local configuration file -// -// :MHDxn# -// Description: -// Home DEC stepper via Hall sensor -// Information: -// This attempts to find the hall sensor and to home the DEC axis accordingly. -// Parameters: -// "x" is either 'U' or 'D' and determines the direction in which the search starts (U is up, D is down). -// "n" (Optional) is the maximum number of degrees to move while searching for the sensor location. Defaults to 30degs. Limited to the range 5degs - 75degs. -// Remarks: -// The ring is first moved 30 degrees (or the given amount) in the initial direction. If no hall sensor is encountered, -// it will move twice the amount (60 degrees by default) in the opposite direction. -// If a hall sensor is not encountered during that slew, the homing exits with a failure. -// If the sensor is found, it will slew to the middle position of the Hall sensor trigger range and then to the offset -// specified in the Home offset position (set with the ":XSHDnnnn#" command). -// If the DEC ring is positioned such that the Hall sensor is already triggered when the command is received, the mount will move -// the DEC ring off the trigger in the opposite direction specified for a max of 15 degrees before searching 30 degrees in the -// specified direction. -// Returns: -// "1" if search is started -// "0" if homing has not been enabled in the local configuration file -// -// :MAAH# -// Description: -// Move Azimuth and Altitude to home -// Information: -// If the scope supports automated azimuth and altitude operations, move AZ and ALT axis to their zero positions. -// Returns: -// "1" -// -// :MAZn.nn# -// Description: -// Move Azimuth -// Information: -// If the scope supports automated azimuth operation, move azimuth by n.nn arcminutes -// Parameters: -// "n.nn" is a signed floating point number representing the number of arcminutes to move the mount left or right -// Returns: -// nothing -// -// :MALn.nn# -// Description: -// Move Altitude -// Information: -// If the scope supports automated altitude operation, move altitude by n.nn arcminutes -// Parameters: -// "n.nn" is a signed floating point number representing the number of arcminutes to raise or lower the mount. -// Returns: -// nothing -// -//------------------------------------------------------------------ -// HOME FAMILY -// -// :hP# -// Description: -// Park Scope and stop motors -// Information: -// This slews the scope back to it's home position (RA ring centered, DEC at 90, basically -// pointing at celestial pole), then advances to the parking position (defined by the Homing offsets) -// and stops all movement (including tracking). -// Returns: -// nothing -// -// :hF# -// Description: -// Move Scope to Home position -// Information: -// This slews the scope back to its home position (RA ring centered, DEC -// at 90, basically pointing at celestial pole). Mount will keep tracking. -// Returns: -// nothing -// -//------------------------------------------------------------------ -// HOME/PARK Extensions -// -// :hU# -// Description: -// Unpark Scope -// Information: -// This currently simply turns on tracking. -// Returns: -// "1" -// -// :hZ# -// Description: -// Set home position for AZ and ALT axes -// Information: -// If the mount supports AZ and ALT axes, this call sets their positions to 0 and stores this in persistent storage. -// Returns: -// "1" -// -//------------------------------------------------------------------ -// QUIT MOVEMENT FAMILY -// -// :Q# -// Description: -// Stop all motors -// Information: -// This stops all motors, including tracking. Note that deceleration curves are still followed. -// Returns: -// nothing -// -// :Qd# -// Description: -// Stop Slewing -// Information: -// Stops slew in specified direction where d is n, s, e, w, a (the first four are the cardinal directions, a stands for All). -// Returns: -// nothing -// -//------------------------------------------------------------------ -// QUIT MOVEMENT Extensions -// -// :Qq# -// Description: -// Disconnect, Quit Control mode -// Information: -// This quits Serial Control mode and starts tracking. -// Returns: -// nothing -// -//------------------------------------------------------------------ -// EXTRA OAT FAMILY - These are used by the PC control application OATControl -// -// :XFR# -// Description: -// Perform a Factory Reset -// Information: -// Clears all the EEPROM settings -// Returns: -// "1#" -// -// :XDnnn# -// Description: -// Run drift alignment (only supported if SUPPORT_DRIFT_ALIGNMENT is enabled) -// Information: -// This runs a drift alignment procedure where the mounts slews east, pauses, slews west and pauses. -// Where nnn is the number of seconds the entire alignment should take. The call is blocking and will -// only return once the drift alignment is complete. -// Returns: -// nothing -// -// :XL0# -// Description: -// Turn off the Digital level -// Returns: -// "1#" if successful -// "0#" if there is no Digital Level -// -// :XL1# -// Description: -// Turn on the Digital level -// Returns: -// "1#" if successful -// "0#" if there is no Digital Level -// -// :XLGR# -// Description: -// Digital Level - Get Reference -// Information: -// Gets the reference pitch and roll values of the mount (Digital Level addon). These -// values are the values of the pitch and roll when the mount is level. -// Returns: -// ",#" -// "0#" if there is no Digital Level -// -// :XLGC# -// Description: -// Digital Level - Get Values -// Information: -// Gets the current pitch and roll values of the mount (Digital Level addon). -// Returns: -// ",#" -// "0#" if there is no Digital Level -// -// :XLGT# -// Description: -// Digital Level - Get Temperature -// Information: -// Get the current temperature in Celsius of the mount (Digital Level addon). -// Returns: -// "#" -// "0#" if there is no Digital Level -// -// :XLSR# -// Description: -// Digital Level - Set Reference Roll -// Information: -// Sets the reference roll value of the mount (Digital Level addon). This is the value -// at which the mount is level. -// Returns: -// "1#" if successful -// "0#" if there is no Digital Level -// -// :XLSP# -// Description: -// Digital Level - Set Reference Pitch -// Information: -// Sets the reference pitch value of the mount (Digital Level addon). This is the value -// at which the mount is level. -// Returns: -// "1#" if successful -// "0#" if there is no Digital Level -// -// :XGAA# -// Description: -// Get position of AZ and ALT axes -// Information: -// Get the current position in steps of the AZ and ALT axes if they are enabled. -// If an axis is not enabled, this always returns zero as the axis's value. -// Returns: -// "azpos|altpos#" if either axis is enabled -// -// :XGAH# -// Description: -// Get auto homing state -// Information: -// Get the current state of RA and DEC Autohoming status. Only valid when at least -// one Hall sensor based autohoming axis is enabled. -// Returns: -// "rastate|decstate#" if either axis is enabled -// "|#" if no autohoming is enabled -// Remarks: -// While the mount status (:GX#) is 'Homing', the command returns one of these: -// MOVE_OFF -// MOVING_OFF -// STOP_AT_TIME -// WAIT_FOR_STOP -// START_FIND_START -// FINDING_START -// FINDING_START_REVERSE -// FINDING_END -// RANGE_FOUND -// -// If the mount status (:GX#) is not 'Homing' the command returns one of these: -// SUCCEEDED -// NEVER RUN -// IN PROGRESS -// CANT MOVE OFF SENSOR -// CANT FIND SENSOR BEGIN -// CANT FIND SENSOR END -// -// :XGB# -// Description: -// Get Backlash correction steps -// Information: -// Get the number of steps the RA stepper motor needs to overshoot and backtrack when slewing east. -// Returns: -// "integer#" -// -// :XGCn.nn*m.mm# -// Description: -// Get stepper motor positions for target -// Information: -// Get the positions of stepper motors when pointed at the given coordinates. -// Parameters: -// "n.nn" is the RA coordinate (0.0 - 23.999) -// "m.mm" is the DEC coordinate (-90.00 - +90.00) -// "ralong" is the stepper position of the RA stepper -// "declong" is the stepper position of the DEC stepper -// Returns: -// "ralong,declong#" -// -// :XGR# -// Description: -// Get RA steps -// Information: -// Get the number of steps the RA stepper motor needs to take to rotate RA by one degree -// Returns: -// "float#" -// -// :XGD# -// Description: -// Get DEC steps -// Information: -// Get the number of steps the DEC stepper motor needs to take to rotate DEC by one degree -// Returns: -// "float#" -// -// :XGZ# -// Description: -// Get AZ steps -// Information: -// Get the number of steps the AZ stepper motor needs to take to rotate AZ by one degree -// Returns: -// "float#" if AZ motor is present -// "0#" if AZ is not configured -// -// :XGA# -// Description: -// Get ALT steps -// Information: -// Get the number of steps the ALT stepper motor needs to take to rotate ALT by one degree -// Returns: -// "float#" if ALT motor is present -// "0#" if ALT is not configured -// -// :XGDLx# -// Description: -// Get DEC limits -// Information: -// Get either lower, upper or both limits for the DEC stepper motor in degrees. -// Parameters: -// 'x' is optional or can be 'U' or 'L'. If it is 'U' only the upper bound is returned, -// if it is 'L' only the lower bound is returned and if it is missing, both are returned. -// Returns: -// "float#" or "float|float#" -// -// :XGDP# (obsolete, disabled) -// Description: -// Get DEC parking position -// Information: -// Gets the number of steps from the home position to the parking position for DEC -// Returns: -// "0#" -// -// :XGS# -// Description: -// Get Tracking speed adjustment -// Information: -// Get the adjustment factor used to speed up (>1.0) or slow down (<1.0) the tracking speed of the mount. -// Returns: -// "float#" -// -// :XGST# -// Description: -// Get Remaining Safe Time -// Information: -// Get the number of hours before the RA ring reaches its end. -// Returns: -// "float#" -// -// :XGT# -// Description: -// Get Tracking speed -// Information: -// Get the absolute tracking speed of the mount. -// Returns: -// "float#" -// -// :XGH# -// Description: -// Get HA (Hour Angle of Polaris) -// Information: -// Get the current HA of Polaris that the mount thinks it is. -// Returns: -// "HHMMSS#" -// -// :XGHR# -// Description: -// Get RA Homing offset -// Information: -// Get the RA ring homing offset. -// If a Hall sensor is present this is the number of steps from the center of the sensor range to -// where the actual center position is located. -// If no Hall sensor is present this is the number of steps from the power on position of the RA axis to -// where the actual center position is located. -// Returns: -// "n#" - the number of steps -// -// :XGHD# -// Description: -// Get DEC Homing offset -// Information: -// Get the DEC ring homing offset. -// If a Hall sensor is present this is the number of steps from the center of the sensor range to -// where the actual center position is located. -// If no Hall sensor is present this is the number of steps from the power on position of the DEC axis to -// where the actual center position is located. -// Returns: -// "n#" - the number of steps -// -// :XGHS# -// Description: -// Get Hemisphere -// Information: -// Get the hemisphere that the OAT currently assumes it is operating in. This is set via setting Latitude (see ":St" command) -// Returns: -// "N#" - for northern hemisphere -// "S#" - for southern hemisphere -// -// :XGM# -// Description: -// Get Mount configuration settings -// Returns: -// ",,,,,,,(more features...)#" -// Parameters: -// "" is one of the supported boards (currently Mega, ESP32, MKS) -// "" is a pipe-delimited string of Motor type (NEMA or 28BYJ), Pulley Teeth, Steps per revolution) -// "" is either NO_GPS or GPS, depending on whether a GPS module is present -// "" is either NO_AZ_ALT, AUTO_AZ_ALT, AUTO_AZ, or AUTO_ALT, depending on which AutoPA stepper motors are present -// "" is either NO_GYRO or GYRO depending on whether the Digital level is present -// "" is either NO_LCD or LCD_display_type depending on whether LCD is present and if so, which one -// "" is either NO_FOC or FOC depending on whether the focuser motor is enabled -// "" is either NO_HSAH or HSAH depending on whether the Hall sensor based auto homing for RA is enabled -// "" is either NO_ENDSW or ENDS_RA, ENDSW_DEC, or ENDSW_RA_DEC depending on which axis have end switches installed -// Remarks: -// As OAT/OAM firmware supports more features, these may be appended, separated by a comma. Any further features will -// have a 'NO_xxxxx' if the feature is not supported. -// To differentiate between OAT and OAM, use the Get Product Name (#GVP) command. -// Example: -// "ESP32,28BYJ|16|4096.00,28BYJ|16|4096.00,NO_GPS,NO_AZ_ALT,NO_GYRO,NO_LCD,NO_FOC,NO_ENDSW#" -// -// :XGMS# -// Description: -// Get Mount driver configuration -// Returns: -// ",,|,,|#" -// Parameters: -// "" is one of the supported drivers: TU=TMC2209UART, TS=TMC2209STANDALONE, A=A4983 -// "" is the microstepping divider (1, 2, 4, 8, 15, 21, 64, 128, 256) used when slewing -// "" is the microstepping divider (1, 2, 4, 8, 15, 21, 64, 128, 256) used when tracking RA -// "" is the microstepping divider (1, 2, 4, 8, 15, 21, 64, 128, 256) used when guiding DEC -// Example: -// "TU,8,64|TU,16,64|#" -// -// :XGN# -// Description: -// Get network settings -// Information: -// Gets the current status of the Wifi connection. Reply only available when running on ESP boards. -// Returns: -// "1,,,,:,,#" if Wifi is enabled -// "0,#" if Wifi is not enabled -// -// :XGL# -// Description: -// Get LST -// Information: -// Get the current LST of the mount. -// Returns: -// "HHMMSS#" -// -// :XSBn# -// Description: -// Set Backlash correction steps -// Information: -// Sets the number of steps the RA stepper motor needs to overshoot and backtrack when slewing east. -// Returns: -// nothing -// -// :XSHRnnn# -// Description: -// Set homing offset for RA ring from Hall sensor center -// Information: -// This offset is added to the position of the RA ring when it is centered on the hall sensor triggered range after running. -// the RA homing command (:MHRx#) -// Parameters: -// "n" is the (positive or negative) number of steps that are needed from the center of the Hall sensor trigger range to the actual home position. -// Returns: -// nothing -// -// :XSHDnnn# -// Description: -// Set homing offset for DEC ring from Hall sensor center -// Information: -// This offset is added to the position of the DEC ring when it is centered on the hall sensor triggered range after running. -// the DEC homing command (:MHDx#) -// Parameters: -// "n" is the (positive or negative) number of steps that are needed from the center of the Hall sensor trigger range to the actual home position. -// Returns: -// nothing -// -// :XSRn.n# -// Description: -// Set RA steps -// Information: -// Set the number of steps the RA stepper motor needs to take to rotate by one degree. -// Parameters: -// "n.n" is the number of steps (only one decimal point is supported, must be positive) -// Returns: -// nothing -// -// :XSDn.n# -// Description: -// Set DEC steps -// Information: -// Set the number of steps the DEC stepper motor needs to take to rotate by one degree. -// Parameters: -// "n.n" is the number of steps (only one decimal point is supported, must be positive) -// Returns: -// nothing -// -// :XSAn.n# -// Description: -// Set AZ steps -// Information: -// Set the number of steps the AZ stepper motor needs to take to rotate by one degree. -// Parameters: -// "n.n" is the number of steps (only one decimal point is supported, must be positive) -// Returns: -// nothing -// -// :XSLn.n# -// Description: -// Set ALT steps -// Information: -// Set the number of steps the ALT stepper motor needs to take to rotate by one degree. -// Parameters: -// "n.n" is the number of steps (only one decimal point is supported, must be positive) -// Returns: -// nothing -// -// :XSDLUnnnnn# -// Description: -// Set DEC upper limit -// Information: -// Set the upper limit for the DEC axis to the current position if no parameter is given, -// otherwise to the given angle (in degrees from the home position). -// Parameters: -// "nnnnn" is the number of steps from home that the DEC ring can travel upwards. Passing 0 will reset it to the -// limits defined in your configuration file. Omitting this parameter sets it to the current DEC position. -// Returns: -// nothing -// -// :XSDLu# -// Description: -// Clear DEC upper limit -// Information: -// Resets the upper limit for the DEC axis to the configuration-defined position. -// If not configured, the limit is cleared. -// Returns: -// nothing -// -// :XSDLLnnnnn# -// Description: -// Set DEC lower limit -// Information: -// Set the lower limit for the DEC axis to the current position if no parameter is given, -// otherwise to the given angle (in degrees from the home position). -// Parameters: -// "nnnnn" is the number of steps from home that the DEC ring can travel downwards. Passing 0 will reset it to the -// limits defined in your configuration file. Omitting this parameter sets it to the current DEC position. -// Returns: -// nothing -// -// :XSDLl# -// Description: -// Clear DEC lower limit -// Information: -// Resets the lower limit for the DEC axis to the configuration-defined position. -// If not configured, the limit is cleared. -// Returns: -// nothing -// -// :XSDPnnnn# (obsolete, disabled) -// Description: -// Set DEC parking position offset -// Information: -// This stores the number of steps needed to move from home to the parking position. -// Returns: -// nothing -// -// :XSSn.nnn# -// Description: -// Set Tracking speed adjustment -// Information: -// Set the adjustment factor used to speed up "(>1.0)" or slow down "(<1.0)" the tracking speed of the mount -// Parameters: -// "n.nnn" is the factor to multiply the theoretical speed by -// Returns: -// nothing -// -// :XSTnnnn# -// Description: -// Set Tracking motor position (no movement) -// Information: -// This is purely a debugging aid. It is not recommended to call this unless you know what you are doing. It simply sets the internal tracking steps to the given value. -// Parameters: -// "nnn" is the stepper steps to set -// Returns: -// nothing -// -// :XSMn# -// Description: -// Set Manual Slewing Mode -// Information: -// Toggle the manual slewing mode state where the RA and DEC motors run at a constant speed -// Parameters: -// "n" is '1' to turn it on, otherwise turn it off -// Returns: -// nothing -// -// :XSXn.nnn# -// Description: -// Set RA Speed -// Information: -// Set RA manual slewing speed in degrees/sec immediately. Max is around 2.5 degs/s -// Returns: -// nothing -// Remarks: -// Must be in manual slewing mode. -// -// :XSYn.nnn# -// Description: -// Set DEC Speed -// Information: -// Set DEC manual slewing speed in degrees/sec immediately. Max is around 2.5 degs/s -// Returns: -// nothing -// Remarks: -// Must be in manual slewing mode. -// -//------------------------------------------------------------------ -// FOCUS FAMILY -// -// :F+# -// Description: -// Start Focuser moving inward (toward objective) -// Information: -// Continues pull in until stopped -// Returns: -// nothing -// -// :F-# -// Description: -// Pull out -// Information: -// Continues pull out until stopped -// Returns: -// nothing -// -// :Fn# -// Description: -// Set speed factor -// Information: -// Set focuser speed to where is an ASCII digit 1..4. 1 is slowest, 4 is fastest -// Returns: -// nothing -// -// :FS# -// Description: -// Set slowest speed factor -// Information: -// Set focuser to the slowest speed it can use -// Returns: -// nothing -// -// :FF# -// Description: -// Set fastest speed factor -// Information: -// Set focuser speed to the fastest speed it can use -// Returns: -// nothing -// -// :Fp# -// Description: -// Get position -// Information: -// Get the current position of the focus stepper motor -// Returns: -// "nnn#" "nnn" is the current position of the stepper -// -// :FPnnn# -// Description: -// Set position -// Information: -// Sets the current position of the focus stepper motor -// Returns: -// "1" -// Parameters: -// "nnn" is the new position of the stepper. The stepper is not moved. -// -// :FB# -// Description: -// Get focuser state -// Information: -// Gets the state of the focuser stepper. -// Returns: -// "0" if the focuser is idle -// "1" if the focuser is moving -// -// :FQ# -// Description: -// Stop focuser -// Information: -// Stops the stepper motor of the focuser. -// Returns: -// nothing -// -//------------------------------------------------------------------ -///////////////////////////////////////////////////////////////////////////////////////// -MeadeCommandProcessor *MeadeCommandProcessor::_instance = nullptr; -char MeadeCommandProcessor::_responseBuffer[200] = {}; - -const char *MeadeCommandProcessor::copyToResponse(const char *src) -{ - strlcpy(_responseBuffer, src, sizeof(_responseBuffer)); - return _responseBuffer; -} +namespace meade = oat::core::meade; -const char *MeadeCommandProcessor::formatResponse(const char *fmt, ...) -{ - va_list args; - va_start(args, fmt); - vsnprintf(_responseBuffer, sizeof(_responseBuffer), fmt, args); - va_end(args); - return _responseBuffer; -} +MeadeCommandProcessor *MeadeCommandProcessor::_instance = nullptr; -const char *MeadeCommandProcessor::copyToResponse_P(const char *pgmSrc) +const char *MeadeCommandProcessor::store(oat::core::meade::MeadeResponse response) { - strncpy_P(_responseBuffer, pgmSrc, sizeof(_responseBuffer) - 1); - _responseBuffer[sizeof(_responseBuffer) - 1] = '\0'; - return _responseBuffer; + _response = response; + return _response.c_str(); } ///////////////////////////// @@ -1269,1106 +56,903 @@ MeadeCommandProcessor::MeadeCommandProcessor(Mount *mount, LcdMenu *lcdMenu) ///////////////////////////// // INIT ///////////////////////////// -const char *MeadeCommandProcessor::handleMeadeInit(const String &inCmd) +void MeadeCommandProcessor::onEnterSerialControl() { inSerialControl = true; _lcdMenu->setCursor(0, 0); _lcdMenu->printMenu("Remote control"); _lcdMenu->setCursor(0, 1); _lcdMenu->printMenu(">SELECT to quit"); - return ""; } ///////////////////////////// // GET INFO ///////////////////////////// -const char *MeadeCommandProcessor::handleMeadeGetInfo(const String &inCmd) +// ---- IMeadeGetHandlers callbacks --------------------------------------- + +const char *MeadeCommandProcessor::onFirmwareVersion() { - if (inCmd.length() < 1) - { - return ""; - } - char cmdOne = inCmd[0]; - char cmdTwo = (inCmd.length() > 1) ? inCmd[1] : '\0'; - char achBuffer[20]; + return VERSION; +} - switch (cmdOne) - { - case 'V': - if (cmdTwo == 'N') // :GVN - { - return formatResponse("%s#", VERSION); - } - else if (cmdTwo == 'P') // :GVP - { +const char *MeadeCommandProcessor::onProductName() +{ #ifdef OAM - return "OpenAstroMount#"; + return "OpenAstroMount"; #elif defined(OAE) - return "OpenAstroExplorer#"; + return "OpenAstroExplorer"; #else - return "OpenAstroTracker#"; + return "OpenAstroTracker"; #endif - } - break; +} - case 'r': // :Gr - return copyToResponse(_mount->RAString(MEADE_STRING | TARGET_STRING).c_str()); // returns trailing # - - case 'd': // :Gd - return copyToResponse(_mount->DECString(MEADE_STRING | TARGET_STRING).c_str()); // returns trailing # - - case 'R': // :GR - return copyToResponse(_mount->RAString(MEADE_STRING | CURRENT_STRING).c_str()); // returns trailing # - - case 'D': // :GD - return copyToResponse(_mount->DECString(MEADE_STRING | CURRENT_STRING).c_str()); // returns trailing # - - case 'X': // :GX - return formatResponse("%s#", _mount->getStatusString().c_str()); - - case 'I': - { - const char *val = ""; - if (cmdTwo == 'S') // :GIS - { - val = _mount->isSlewingRAorDEC() ? "1" : "0"; - } - else if (cmdTwo == 'T') // :GIT - { - val = _mount->isSlewingTRK() ? "1" : "0"; - } - else if (cmdTwo == 'G') // :GIG - { - val = _mount->isGuiding() ? "1" : "0"; - } - return formatResponse("%s#", val); - } - case 't': // :Gt - { - _mount->latitude().formatString(achBuffer, "{d}*{m}#"); - return copyToResponse(achBuffer); - } - case 'g': // :Gg - { - _mount->longitude().formatStringForMeade(achBuffer); - return formatResponse("%s#", achBuffer); - } - case 'c': // :Gc - { - return "24#"; - } - case 'G': // :GG - { - int offset = _mount->getLocalUtcOffset(); - snprintf(achBuffer, sizeof(achBuffer), "%+03d#", -offset); - return copyToResponse(achBuffer); - } - case 'a': // :Ga - { - DayTime time = _mount->getLocalTime(); - if (time.getHours() > 12) - { - time.addHours(-12); - } - time.formatString(achBuffer, "{d}:{m}:{s}#"); - return copyToResponse(achBuffer + 1); - } - case 'L': // :GL - { - DayTime time = _mount->getLocalTime(); - time.formatString(achBuffer, "{d}:{m}:{s}#"); - return copyToResponse(achBuffer + 1); - } - case 'C': // :GC - { - LocalDate date = _mount->getLocalDate(); - snprintf(achBuffer, sizeof(achBuffer), "%02d/%02d/%02d#", date.month, date.day, date.year % 100); - return copyToResponse(achBuffer); - } - case 'M': // :GM - { - return "OAT1#"; - } - case 'N': // :GN - { - return "OAT2#"; - } - case 'O': // :GO - { - return "OAT3#"; - } - case 'P': // :GP - { - return "OAT4#"; - } - case 'T': // :GT - { - return "60.0#"; //default MEADE Tracking Frequency - } - } +namespace +{ +meade::RaCoordinate raFrom(const DayTime &t) +{ + return meade::RaCoordinate { + static_cast(t.getHours()), + static_cast(t.getMinutes()), + static_cast(t.getSeconds()), + }; +} + +meade::DecCoordinate decFrom(const Declination &d) +{ + return meade::DecCoordinate { + static_cast(d.getHours()), + static_cast(d.getMinutes()), + static_cast(d.getSeconds()), + }; +} +} // namespace + +meade::RaCoordinate MeadeCommandProcessor::onCurrentRa() +{ + return raFrom(_mount->currentRA()); +} + +meade::RaCoordinate MeadeCommandProcessor::onTargetRa() +{ + return raFrom(_mount->targetRA()); +} + +meade::DecCoordinate MeadeCommandProcessor::onCurrentDec() +{ + return decFrom(_mount->currentDEC()); +} + +meade::DecCoordinate MeadeCommandProcessor::onTargetDec() +{ + return decFrom(_mount->targetDEC()); +} + +const char *MeadeCommandProcessor::onMountStatus() +{ + _mountStatusScratch = _mount->getStatusString(); + return _mountStatusScratch.c_str(); +} + +bool MeadeCommandProcessor::onIsSlewing() +{ + return _mount->isSlewingRAorDEC(); +} + +bool MeadeCommandProcessor::onIsTracking() +{ + return _mount->isSlewingTRK(); +} + +bool MeadeCommandProcessor::onIsGuiding() +{ + return _mount->isGuiding(); +} + +meade::MeadeLatitude MeadeCommandProcessor::onSiteLatitude() +{ + const Latitude lat = _mount->latitude(); + return meade::MeadeLatitude { + static_cast(lat.getHours()), + static_cast(lat.getMinutes()), + }; +} + +meade::MeadeLongitude MeadeCommandProcessor::onSiteLongitude() +{ + const Longitude lon = _mount->longitude(); + return meade::MeadeLongitude { + static_cast(lon.getHours()), + static_cast(lon.getMinutes()), + }; +} + +int MeadeCommandProcessor::onUtcOffset() +{ + return -_mount->getLocalUtcOffset(); +} + +meade::MeadeLocalTime MeadeCommandProcessor::onLocalTime() +{ + DayTime time = _mount->getLocalTime(); + return meade::MeadeLocalTime { + static_cast(time.getHours()), + static_cast(time.getMinutes()), + static_cast(time.getSeconds()), + }; +} + +meade::MeadeLocalDate MeadeCommandProcessor::onLocalDate() +{ + ::LocalDate d = _mount->getLocalDate(); + return meade::MeadeLocalDate { + static_cast(d.month), + static_cast(d.day), + static_cast(d.year), + }; +} + +meade::MeadeClockFormat MeadeCommandProcessor::onClockFormat() +{ + return meade::MeadeClockFormat::Hours24; +} - return ""; +meade::MeadeTrackingRate MeadeCommandProcessor::onTrackingRate() +{ + return meade::MeadeTrackingRate::Sidereal; +} + +const char *MeadeCommandProcessor::onSiteName(uint8_t index) +{ + snprintf(_siteNameScratch, sizeof(_siteNameScratch), "OAT%u", static_cast(index)); + return _siteNameScratch; } ///////////////////////////// // GPS CONTROL ///////////////////////////// -const char *MeadeCommandProcessor::handleMeadeGPSCommands(const String &inCmd) +bool MeadeCommandProcessor::onStartGpsAcquisition(const char *timeoutPayload) { - if (inCmd.length() < 1) +#if USE_GPS == 1 + unsigned long timeoutLen = 2UL * 60UL * 1000UL; + if (timeoutPayload != nullptr && timeoutPayload[0] != '\0') { - return "0"; + timeoutLen = String(timeoutPayload).toInt(); } -#if USE_GPS == 1 - if (inCmd[0] == 'T') + unsigned long timeoutTime = millis() + timeoutLen; + int indicator = 0; + while (millis() < timeoutTime) { - unsigned long timeoutLen = 2UL * 60UL * 1000UL; - if (inCmd.length() > 1) - { - timeoutLen = inCmd.substring(1).toInt(); - } - // Wait at most 2 minutes - unsigned long timeoutTime = millis() + timeoutLen; - int indicator = 0; - while (millis() < timeoutTime) + if (gpsAqcuisitionComplete(indicator)) { - if (gpsAqcuisitionComplete(indicator)) - { - LOG(DEBUG_MEADE, "[MEADE]: GPS startup, GPS acquired"); - return "1"; - } + LOG(DEBUG_MEADE, "[MEADE]: GPS startup, GPS acquired"); + return true; } } +#else + (void) timeoutPayload; #endif LOG(DEBUG_MEADE, "[MEADE]: GPS startup, no GPS signal"); - return "0"; + return false; } ///////////////////////////// // SYNC CONTROL ///////////////////////////// -const char *MeadeCommandProcessor::handleMeadeSyncControl(const String &inCmd) +void MeadeCommandProcessor::onSyncToTarget() { - if (inCmd.length() < 1) - { - return "FAIL#"; - } - if (inCmd[0] == 'M') // :CM - { - _mount->syncPosition(_mount->targetRA(), _mount->targetDEC()); - return "NONE#"; - } - - return "FAIL#"; + _mount->syncPosition(_mount->targetRA(), _mount->targetDEC()); } ///////////////////////////// // SET INFO ///////////////////////////// -const char *MeadeCommandProcessor::handleMeadeSetInfo(const String &inCmd) +bool MeadeCommandProcessor::onSetTargetDec(meade::DecCoordinate dec) { - if (inCmd.length() < 1) - { - return "0"; - } - if ((inCmd[0] == 'd') && (inCmd.length() == 10)) - { - // Set DEC - // 0123456789 - // :Sd+84*03:02 - if (((inCmd[4] == '*') || (inCmd[4] == ':')) && (inCmd[7] == ':')) - { - Declination dec = Declination::ParseFromMeade(inCmd.substring(1)); - _mount->targetDEC() = dec; - LOG(DEBUG_MEADE, "[MEADE]: SetInfo: Received Target DEC: %s", _mount->targetDEC().ToString()); - return "1"; - } - else - { - // Did not understand the coordinate - return "0"; - } - } - else if (inCmd[0] == 'r' && (inCmd.length() == 9)) - { - // :Sr11:04:57# - // Set RA - // 012345678 - // :Sr04:03:02 - if ((inCmd[3] == ':') && (inCmd[6] == ':')) - { - _mount->targetRA().set(inCmd.substring(1, 3).toInt(), inCmd.substring(4, 6).toInt(), inCmd.substring(7, 9).toInt()); - LOG(DEBUG_MEADE, "[MEADE]: SetInfo: Received Target RA: %s", _mount->targetRA().ToString()); - return "1"; - } - else - { - // Did not understand the coordinate - return "0"; - } - } - else if (inCmd[0] == 'H') - { - if (inCmd[1] == 'L') - { - // Set LST - int hLST = inCmd.substring(2, 4).toInt(); - int minLST = inCmd.substring(4, 6).toInt(); - int secLST = 0; - if (inCmd.length() > 7) - { - secLST = inCmd.substring(6, 8).toInt(); - } - - DayTime lst(hLST, minLST, secLST); - LOG(DEBUG_MEADE, "[MEADE]: SetInfo: Received LST: %d:%d:%d", hLST, minLST, secLST); - _mount->setLST(lst); - } - else if (inCmd[1] == 'P') - { - // Set home point :SHP# - _mount->setHome(false); - } - else - { - // Set HA - int hHA = inCmd.substring(1, 3).toInt(); - int minHA = inCmd.substring(4, 6).toInt(); - LOG(DEBUG_MEADE, "[MEADE]: SetInfo: Received HA: %d:%d:%d", hHA, minHA, 0); - _mount->setHA(DayTime(hHA, minHA, 0)); - } + _mount->targetDEC() = Declination(static_cast(dec.degrees), static_cast(dec.minutes), static_cast(dec.seconds)); + LOG(DEBUG_MEADE, "[MEADE]: SetInfo: Received Target DEC: %s", _mount->targetDEC().ToString()); + return true; +} - return "1"; - } - else if ((inCmd[0] == 'Y') && inCmd.length() == 19) - { - // Sync RA, DEC - current position is the given coordinate - // 0123456789012345678 - // :SY+84*03:02.18:34:12 - if (((inCmd[4] == '*') || (inCmd[4] == ':')) && (inCmd[7] == ':') && (inCmd[10] == '.') && (inCmd[13] == ':') && (inCmd[16] == ':')) - { - Declination dec = Declination::ParseFromMeade(inCmd.substring(1, 9)); - DayTime ra = DayTime::ParseFromMeade(inCmd.substring(11)); +bool MeadeCommandProcessor::onSetTargetRa(meade::RaCoordinate ra) +{ + _mount->targetRA().set(static_cast(ra.hours), static_cast(ra.minutes), static_cast(ra.seconds)); + LOG(DEBUG_MEADE, "[MEADE]: SetInfo: Received Target RA: %s", _mount->targetRA().ToString()); + return true; +} - _mount->syncPosition(ra, dec); - return "1"; - } - return "0"; - } - else if ((inCmd[0] == 't')) // latitude: :St+30*29# - { - Latitude lat = Latitude::ParseFromMeade(inCmd.substring(1)); - _mount->setLatitude(lat); - return "1"; - } - else if (inCmd[0] == 'g') // longitude :Sg097*34# or :Sg-122*54# - { - Longitude lon = Longitude::ParseFromMeade(inCmd.substring(1)); - _mount->setLongitude(lon); - return "1"; - } - else if (inCmd[0] == 'G') // utc offset :SG+05# - { - int offset = inCmd.substring(1, 4).toInt(); - _mount->setLocalUtcOffset(-offset); - return "1"; - } - else if (inCmd[0] == 'L') // Local time :SL19:33:03# - { - _mount->setLocalStartTime(DayTime::ParseFromMeade(inCmd.substring(1))); - return "1"; - } - else if (inCmd[0] == 'C') - { // Set Date (MM/DD/YY) :SC04/30/20# - int month = inCmd.substring(1, 3).toInt(); - int day = inCmd.substring(4, 6).toInt(); - int year = 2000 + inCmd.substring(7, 9).toInt(); - _mount->setLocalStartDate(year, month, day); - - /* +bool MeadeCommandProcessor::onSetLocalSiderealTime(meade::MeadeLocalTime lst) +{ + LOG(DEBUG_MEADE, "[MEADE]: SetInfo: Received LST: %u:%u:%u", lst.hours, lst.minutes, lst.seconds); + _mount->setLST(DayTime(static_cast(lst.hours), static_cast(lst.minutes), static_cast(lst.seconds))); + return true; +} + +bool MeadeCommandProcessor::onSetHomePoint() +{ + _mount->setHome(false); + return true; +} + +bool MeadeCommandProcessor::onSetHourAngle(uint8_t hours, uint8_t minutes) +{ + LOG(DEBUG_MEADE, "[MEADE]: SetInfo: Received HA: %u:%u:0", hours, minutes); + _mount->setHA(DayTime(static_cast(hours), static_cast(minutes), 0)); + return true; +} + +bool MeadeCommandProcessor::onSyncCoordinates(meade::DecCoordinate dec, meade::RaCoordinate ra) +{ + Declination decValue(static_cast(dec.degrees), static_cast(dec.minutes), static_cast(dec.seconds)); + DayTime raValue(static_cast(ra.hours), static_cast(ra.minutes), static_cast(ra.seconds)); + _mount->syncPosition(raValue, decValue); + return true; +} + +bool MeadeCommandProcessor::onSetSiteLatitude(meade::MeadeLatitude lat) +{ + _mount->setLatitude(Latitude(static_cast(lat.degrees), static_cast(lat.minutes), 0)); + return true; +} + +bool MeadeCommandProcessor::onSetSiteLongitude(meade::MeadeLongitude lon) +{ + _mount->setLongitude(Longitude(static_cast(lon.degrees), static_cast(lon.minutes), 0)); + return true; +} + +bool MeadeCommandProcessor::onSetUtcOffset(int hours) +{ + // Wire value is the local-time offset from UTC; the mount stores the + // inverse so that "local + offset = UTC". + _mount->setLocalUtcOffset(-hours); + return true; +} + +bool MeadeCommandProcessor::onSetLocalTime(meade::MeadeLocalTime t) +{ + _mount->setLocalStartTime(DayTime(static_cast(t.hours), static_cast(t.minutes), static_cast(t.seconds))); + return true; +} + +bool MeadeCommandProcessor::onSetLocalDate(meade::MeadeLocalDate d) +{ + _mount->setLocalStartDate(static_cast(d.year), static_cast(d.month), static_cast(d.day)); + /* From https://www.astro.louisville.edu/software/xmtel/archive/xmtel-indi-6.0/xmtel-6.0l/support/lx200/CommandSet.html : SC: Calendar: If the date is valid 2 s are returned, each string is 31 bytes long. The first is: "Updating planetary data#" followed by a second string of 30 spaces terminated by '#' */ - return copyToResponse_P(PSTR("1Updating Planetary Data# #")); - } - else - { - return "0"; - } + return true; } ///////////////////////////// // MOVEMENT ///////////////////////////// -const char *MeadeCommandProcessor::handleMeadeMovement(const String &inCmd) +///////////////////////////// +// HOME +///////////////////////////// +void MeadeCommandProcessor::onPark() { - if (inCmd.length() < 1) - { - return ""; - } - LOG(DEBUG_MEADE, "[MEADE]: Process Move command: [%s]", inCmd.c_str()); - if (inCmd[0] == 'S') // :MS# - { - _mount->startSlewingToTarget(); - return "0"; - } - else if (inCmd[0] == 'T') // :MT1 - { - if (inCmd.length() > 1) - { - if (inCmd[1] == '1') - { - _mount->startSlewing(TRACKING); - return "1"; - } - else if (inCmd[1] == '0') - { - _mount->stopSlewing(TRACKING); - return "1"; - } - } - else - { - return "0"; - } - } - else if ((inCmd[0] == 'G') || (inCmd[0] == 'g')) // MG - { - // The spec calls for lowercase, but ASCOM Drivers prior to 0.3.1.0 sends uppercase, so we allow both for now. - // Guide pulse - // 012345678901 - // :MGd0403 - if (inCmd.length() == 6 && isdigit(inCmd[2]) && isdigit(inCmd[3]) && isdigit(inCmd[4]) && isdigit(inCmd[5])) - { - byte direction = EAST; - char dirChar = tolower(inCmd[1]); - if (dirChar == 'n') - direction = NORTH; - else if (dirChar == 's') - direction = SOUTH; - else if (dirChar == 'e') - direction = EAST; - else if (dirChar == 'w') - direction = WEST; - int duration = (inCmd[2] - '0') * 1000 + (inCmd[3] - '0') * 100 + (inCmd[4] - '0') * 10 + (inCmd[5] - '0'); - _mount->guidePulse(direction, duration); - return ""; - } - } - else if (inCmd[0] == 'A' && inCmd.length() > 1) - { - LOG(DEBUG_MEADE, "[MEADE]: Move Az/Alt"); - - if (inCmd[1] == 'A') // :MAA - { - LOG(DEBUG_MEADE, "[MEADE]: Move AZ and ALT to home"); - _mount->moveAZALTToHome(); - return "1"; - } - - // Move Azimuth or Altitude by given arcminutes - // :MAZ+32.1# or :MAL-32.1# -#if (AZ_STEPPER_TYPE != STEPPER_TYPE_NONE) - if (inCmd[1] == 'Z') // :MAZ - { - float arcMinute = inCmd.substring(2).toFloat(); - LOG(DEBUG_MEADE, "[MEADE]: Move AZ by %f arcmins", arcMinute); - _mount->moveBy(AZIMUTH_STEPS, arcMinute); - } -#endif -#if (ALT_STEPPER_TYPE != STEPPER_TYPE_NONE) - if (inCmd[1] == 'L') // :MAL - { - float arcMinute = inCmd.substring(2).toFloat(); - LOG(DEBUG_MEADE, "[MEADE]: Move ALT by %f arcmins", arcMinute); - _mount->moveBy(ALTITUDE_STEPS, arcMinute); - } -#endif - return ""; - } - else if (inCmd[0] == 'e') // :Me - { - _mount->startSlewing(EAST); - return ""; - } - else if (inCmd[0] == 'w') // :Mw - { - _mount->startSlewing(WEST); - return ""; - } - else if (inCmd[0] == 'n') // :Mn - { - _mount->startSlewing(NORTH); - return ""; - } - else if (inCmd[0] == 's') // :Ms - { - _mount->startSlewing(SOUTH); - return ""; - } - else if (inCmd[0] == 'X') // :MX - { - long steps = inCmd.substring(2).toInt(); - LOG(DEBUG_MEADE, "[MEADE]: Move: %l in %c", steps, inCmd[1]); - if (inCmd[1] == 'r') - _mount->moveStepperBy(RA_STEPS, steps); - else if (inCmd[1] == 'd') - _mount->moveStepperBy(DEC_STEPS, steps); - else if (inCmd[1] == 'z') - _mount->moveStepperBy(AZIMUTH_STEPS, steps); - else if (inCmd[1] == 'l') - _mount->moveStepperBy(ALTITUDE_STEPS, steps); - else if (inCmd[1] == 'f') - _mount->moveStepperBy(FOCUS_STEPS, steps); - else - return "0"; - return "1"; - } - else if ((inCmd[0] == 'H') && (inCmd.length() > 2) && inCmd[1] == 'R') - { -#if USE_HALL_SENSOR_RA_AUTOHOME == 1 - int distance = RA_HOMING_SENSOR_SEARCH_DEGREES; - if (inCmd.length() > 3) - { - distance = clamp((int) inCmd.substring(3).toInt(), 5, 75); - LOG(DEBUG_MEADE, "[MEADE]: RA AutoHome by %dh", distance); - } + _mount->park(); +} - if (inCmd[2] == 'R') // :MHRR - { - return _mount->findHomeByHallSensor(StepperAxis::RA_STEPS, -1, distance) ? "1" : "0"; - } - else if (inCmd[2] == 'L') // :MHRL - { - return _mount->findHomeByHallSensor(StepperAxis::RA_STEPS, 1, distance) ? "1" : "0"; - } - return "0"; -#endif - } - else if ((inCmd[0] == 'H') && (inCmd.length() > 2) && inCmd[1] == 'D') - { -#if USE_HALL_SENSOR_DEC_AUTOHOME == 1 - int decDistance = DEC_HOMING_SENSOR_SEARCH_DEGREES; - if (inCmd.length() > 3) - { - decDistance = clamp((int) inCmd.substring(3).toInt(), 5, 75); - LOG(DEBUG_MEADE, "[MEADE]: DEC AutoHome by %dh", decDistance); - } +void MeadeCommandProcessor::onSlewToHome() +{ + _mount->startSlewingToHome(); +} - if (inCmd[2] == 'U') // :MHDU - { - return _mount->findHomeByHallSensor(StepperAxis::DEC_STEPS, 1, decDistance) ? "1" : "0"; - } - else if (inCmd[2] == 'D') // :MHDD - { - return _mount->findHomeByHallSensor(StepperAxis::DEC_STEPS, -1, decDistance) ? "1" : "0"; - } -#endif - return "0"; - } +void MeadeCommandProcessor::onUnpark() +{ + _mount->startSlewing(TRACKING); +} - return "0"; +void MeadeCommandProcessor::onSetAzAltHome() +{ + _mount->setAZALTHome(); } -///////////////////////////// -// HOME -///////////////////////////// -const char *MeadeCommandProcessor::handleMeadeHome(const String &inCmd) +void MeadeCommandProcessor::onSetSlewRate(uint8_t rate) { - if (inCmd.length() < 1) - { - return ""; - } - if (inCmd[0] == 'P') // :hP - { // Park - _mount->park(); - } - else if (inCmd[0] == 'F') // :hF - { // Home - _mount->startSlewingToHome(); - } - else if (inCmd[0] == 'U') // :hU - { // Unpark - _mount->startSlewing(TRACKING); - return "1"; - } - else if (inCmd[0] == 'Z') // :hZ - { // Set AZ/ALT home - _mount->setAZALTHome(); - return "1"; - } - return ""; + _mount->setSlewRate(static_cast(rate)); } -const char *MeadeCommandProcessor::handleMeadeDistance(const String &inCmd) +bool MeadeCommandProcessor::onIsSlewingRaOrDec() { - if (_mount->isSlewingRAorDEC()) - { - return "|#"; - } - return " #"; + return _mount->isSlewingRAorDEC(); } ///////////////////////////// // EXTRA COMMANDS ///////////////////////////// -const char *MeadeCommandProcessor::handleMeadeExtraCommands(const String &inCmd) +// ---- IMeadeExtraHandlers overrides ---------------------------------------- + +void MeadeCommandProcessor::onFactoryReset() +{ + _mount->clearConfiguration(); +} + +void MeadeCommandProcessor::onDriftAlignment(int duration) { - if (inCmd.length() < 1) - { - return ""; - } #if SUPPORT_DRIFT_ALIGNMENT == 1 - // :XDmmm - if (inCmd[0] == 'D') // :XD - { // Drift Alignemnt - int duration = inCmd.substring(1, 4).toInt() - 3; - _lcdMenu->setCursor(0, 0); - _lcdMenu->printMenu(">Drift Alignment"); - _lcdMenu->setCursor(0, 1); - _lcdMenu->printMenu("Pause 1.5s...."); - _mount->stopSlewing(ALL_DIRECTIONS | TRACKING); - _mount->waitUntilStopped(ALL_DIRECTIONS); - _mount->delay(1500); - _lcdMenu->setCursor(0, 1); - _lcdMenu->printMenu("Eastward pass..."); - _mount->runDriftAlignmentPhase(EAST, duration); - _lcdMenu->setCursor(0, 1); - _lcdMenu->printMenu("Pause 1.5s...."); - _mount->delay(1500); - _lcdMenu->printMenu("Westward pass..."); - _mount->runDriftAlignmentPhase(WEST, duration); - _lcdMenu->setCursor(0, 1); - _lcdMenu->printMenu("Pause 1.5s...."); - _mount->delay(1500); - _lcdMenu->printMenu("Reset _mount->.."); - _mount->runDriftAlignmentPhase(0, duration); - _lcdMenu->setCursor(0, 1); - _mount->startSlewing(TRACKING); - } - else + _lcdMenu->setCursor(0, 0); + _lcdMenu->printMenu(">Drift Alignment"); + _lcdMenu->setCursor(0, 1); + _lcdMenu->printMenu("Pause 1.5s...."); + _mount->stopSlewing(ALL_DIRECTIONS | TRACKING); + _mount->waitUntilStopped(ALL_DIRECTIONS); + _mount->delay(1500); + _lcdMenu->setCursor(0, 1); + _lcdMenu->printMenu("Eastward pass..."); + _mount->runDriftAlignmentPhase(EAST, duration); + _lcdMenu->setCursor(0, 1); + _lcdMenu->printMenu("Pause 1.5s...."); + _mount->delay(1500); + _lcdMenu->printMenu("Westward pass..."); + _mount->runDriftAlignmentPhase(WEST, duration); + _lcdMenu->setCursor(0, 1); + _lcdMenu->printMenu("Pause 1.5s...."); + _mount->delay(1500); + _lcdMenu->printMenu("Reset _mount->.."); + _mount->runDriftAlignmentPhase(0, duration); + _lcdMenu->setCursor(0, 1); + _mount->startSlewing(TRACKING); +#else + (void) duration; #endif - if (inCmd[0] == 'G') - { // Get RA/DEC steps/deg, speedfactor - if (inCmd[1] == 'R') // :XGR# - { - return formatResponse("%s#", String(_mount->getStepsPerDegree(RA_STEPS), 1).c_str()); - } - else if (inCmd[1] == 'D') - { - if (inCmd.length() > 2) - { - if (inCmd[2] == 'L') // :XGDLx# - { - float loLimit, hiLimit; - _mount->getDecLimitPositions(loLimit, hiLimit); - if (inCmd.length() > 3) - { - if (inCmd[3] == 'L') // :XGDLL# - { - return formatResponse("%s#", String(loLimit, 1).c_str()); - } - else if (inCmd[3] == 'U') // :XGDLU# - { - return formatResponse("%s#", String(hiLimit, 1).c_str()); - } - else - { - return "0#"; - } - } - else // :XGDL# - { - return formatResponse("%s|%s#", String(loLimit, 1).c_str(), String(hiLimit, 1).c_str()); - } - } - if (inCmd[2] == 'P') // :XGDP# - { - return "0#"; - } - } - else // :XGD# - { - return formatResponse("%s#", String(_mount->getStepsPerDegree(DEC_STEPS), 1).c_str()); - } - } - else if (inCmd[1] == 'S') - { - if (inCmd.length() == 2) // :XGS# - { - return formatResponse("%s#", String(_mount->getSpeedCalibration(), 5).c_str()); - } - else if ((inCmd.length() == 3) && (inCmd[2] == 'T')) // :XGST# - { - return formatResponse("%s#", String(_mount->checkRALimit(), 7).c_str()); - } - } - else if (inCmd[1] == 'T') // :XGT# - { - return formatResponse("%s#", String(_mount->getSpeed(TRACKING), 7).c_str()); - } - else if (inCmd[1] == 'B') // :XGB# - { - return formatResponse("%s#", String(_mount->getBacklashCorrection()).c_str()); - } - else if ((inCmd[1] == 'A') && (inCmd.length() == 2)) // :XGA# - { - return formatResponse("%s#", String(_mount->getStepsPerDegree(ALTITUDE_STEPS), 1).c_str()); - } - else if ((inCmd[1] == 'Z') && (inCmd.length() == 2)) // :XGZ# - { - return formatResponse("%s#", String(_mount->getStepsPerDegree(AZIMUTH_STEPS), 1).c_str()); - } - else if ((inCmd[1] == 'A') && (inCmd.length() > 2) && (inCmd[2] == 'H')) // :XGAH# - { - return formatResponse("%s#", _mount->getAutoHomingStates().c_str()); - } - else if ((inCmd[1] == 'A') && (inCmd.length() > 2) && (inCmd[2] == 'A')) // :XGAA# - { - long azPos, altPos; - _mount->getAZALTPositions(azPos, altPos); - return formatResponse("%ld|%ld#", azPos, altPos); - } - else if (inCmd[1] == 'C') // :XGCn.nn*m.mm# - { - String coords = inCmd.substring(2); - int star = coords.indexOf('*'); - if (star > 0) - { - long raPos, decPos; - float raCoord = coords.substring(0, star).toFloat(); - float decCoord = coords.substring(star + 1).toFloat(); - _mount->calculateStepperPositions(raCoord, decCoord, raPos, decPos); - return formatResponse("%ld|%ld#", raPos, decPos); - } - } - else if (inCmd[1] == 'M') - { - if ((inCmd.length() > 2) && (inCmd[2] == 'S')) // :XGMS# - { - return formatResponse("%s#", _mount->getStepperInfo().c_str()); - } - return formatResponse("%s#", _mount->getMountHardwareInfo().c_str()); // :XGM# - } - else if (inCmd[1] == 'O') // :XGO# - { - return copyToResponse(getLogBuffer().c_str()); - } - else if (inCmd[1] == 'H') // :XGH# - { - if (inCmd.length() > 2) - { - LOG(DEBUG_MEADE, "[MEADE]: XGH -> %s", inCmd.c_str()); - if (inCmd[2] == 'R') // :XGHR# - { - LOG(DEBUG_MEADE, "[MEADE]: XGHR -> %s", inCmd.c_str()); - return formatResponse("%ld#", _mount->getHomingOffset(StepperAxis::RA_STEPS)); - } - else if (inCmd[2] == 'D') // :XGHD# - { - LOG(DEBUG_MEADE, "[MEADE]: XGHD -> %s", inCmd.c_str()); - return formatResponse("%ld#", _mount->getHomingOffset(StepperAxis::DEC_STEPS)); - } - else if (inCmd[2] == 'S') // :XGHS# - { - LOG(DEBUG_MEADE, "[MEADE]: XGHS -> %s", inCmd.c_str()); - return inNorthernHemisphere ? "N#" : "S#"; - } - LOG(DEBUG_MEADE, "[MEADE]: XGH? -> %s", inCmd.c_str()); - - return "0#"; - } - else - { - DayTime ha = _mount->calculateHa(); - return formatResponse("%02d%02d%02d#", ha.getHours(), ha.getMinutes(), ha.getSeconds()); - } - } - else if (inCmd[1] == 'L') // :XGL# - { - DayTime lst = _mount->calculateLst(); - return formatResponse("%02d%02d%02d#", lst.getHours(), lst.getMinutes(), lst.getSeconds()); - } - else if (inCmd[1] == 'N') // :XGN# - { +} + +float MeadeCommandProcessor::onGetRaStepsPerDegree() +{ + return _mount->getStepsPerDegree(RA_STEPS); +} +float MeadeCommandProcessor::onGetDecStepsPerDegree() +{ + return _mount->getStepsPerDegree(DEC_STEPS); +} +float MeadeCommandProcessor::onGetAltStepsPerDegree() +{ + return _mount->getStepsPerDegree(ALTITUDE_STEPS); +} +float MeadeCommandProcessor::onGetAzStepsPerDegree() +{ + return _mount->getStepsPerDegree(AZIMUTH_STEPS); +} + +oat::core::meade::ExtraDecLimits MeadeCommandProcessor::onGetDecLimits() +{ + oat::core::meade::ExtraDecLimits lim; + _mount->getDecLimitPositions(lim.lo, lim.hi); + return lim; +} + +float MeadeCommandProcessor::onGetTrackingSpeedCalibration() +{ + return _mount->getSpeedCalibration(); +} +float MeadeCommandProcessor::onGetRemainingSafeTime() +{ + return _mount->checkRALimit(); +} +float MeadeCommandProcessor::onGetTrackingSpeed() +{ + return _mount->getSpeed(TRACKING); +} +int MeadeCommandProcessor::onGetBacklashSteps() +{ + return _mount->getBacklashCorrection(); +} +const char *MeadeCommandProcessor::onGetAutoHomingStates() +{ + _mountStatusScratch = _mount->getAutoHomingStates(); + return _mountStatusScratch.c_str(); +} + +oat::core::meade::ExtraAzAltPositions MeadeCommandProcessor::onGetAzAltPositions() +{ + oat::core::meade::ExtraAzAltPositions p; + _mount->getAZALTPositions(p.az, p.alt); + return p; +} + +oat::core::meade::ExtraStepperCoords MeadeCommandProcessor::onGetTargetCoordinatePositions(float raCoord, float decCoord) +{ + oat::core::meade::ExtraStepperCoords pos; + _mount->calculateStepperPositions(raCoord, decCoord, pos.raPos, pos.decPos); + return pos; +} + +const char *MeadeCommandProcessor::onGetStepperInfo() +{ + _mountStatusScratch = _mount->getStepperInfo(); + return _mountStatusScratch.c_str(); +} +const char *MeadeCommandProcessor::onGetMountHardwareInfo() +{ + _mountStatusScratch = _mount->getMountHardwareInfo(); + return _mountStatusScratch.c_str(); +} +const char *MeadeCommandProcessor::onGetLogBuffer() +{ + _mountStatusScratch = getLogBuffer(); + return _mountStatusScratch.c_str(); +} +long MeadeCommandProcessor::onGetRaHomingOffset() +{ + return _mount->getHomingOffset(StepperAxis::RA_STEPS); +} +long MeadeCommandProcessor::onGetDecHomingOffset() +{ + return _mount->getHomingOffset(StepperAxis::DEC_STEPS); +} +bool MeadeCommandProcessor::onGetHemisphere() +{ + return inNorthernHemisphere; +} + +oat::core::meade::ExtraHms MeadeCommandProcessor::onGetHourAngle() +{ + DayTime ha = _mount->calculateHa(); + oat::core::meade::ExtraHms t; + t.hours = ha.getHours(); + t.minutes = ha.getMinutes(); + t.seconds = ha.getSeconds(); + return t; +} + +oat::core::meade::ExtraHms MeadeCommandProcessor::onGetLocalSiderealTime() +{ + DayTime lst = _mount->calculateLst(); + oat::core::meade::ExtraHms t; + t.hours = lst.getHours(); + t.minutes = lst.getMinutes(); + t.seconds = lst.getSeconds(); + return t; +} + +const char *MeadeCommandProcessor::onGetNetworkStatus() +{ #if (WIFI_ENABLED == 1) - return formatResponse("%s#", wifiControl.getStatus().c_str()); + _mountStatusScratch = wifiControl.getStatus(); + return _mountStatusScratch.c_str(); +#else + return "0,"; #endif +} - return "0,#"; - } +void MeadeCommandProcessor::onSetRaStepsPerDegree(float v) +{ + _mount->setStepsPerDegree(RA_STEPS, v); +} +void MeadeCommandProcessor::onSetDecStepsPerDegree(float v) +{ + _mount->setStepsPerDegree(DEC_STEPS, v); +} +void MeadeCommandProcessor::onSetAzStepsPerDegree(float v) +{ + _mount->setStepsPerDegree(AZIMUTH_STEPS, v); +} +void MeadeCommandProcessor::onSetAltStepsPerDegree(float v) +{ + _mount->setStepsPerDegree(ALTITUDE_STEPS, v); +} + +void MeadeCommandProcessor::onSetDecLimitLower(bool havePayload, float value) +{ + if (havePayload) + { + _mount->setDecLimitPosition(false, value); } - else if (inCmd[0] == 'S') - { // Set RA/DEC steps/deg, speedfactor - if (inCmd[1] == 'R') // :XSR# - { - _mount->setStepsPerDegree(RA_STEPS, inCmd.substring(2).toFloat()); - } - else if (inCmd[1] == 'A') // :XSA# - { - _mount->setStepsPerDegree(AZIMUTH_STEPS, inCmd.substring(2).toFloat()); - } - else if (inCmd[1] == 'L') // :XSL# - { - _mount->setStepsPerDegree(ALTITUDE_STEPS, inCmd.substring(2).toFloat()); - } - else if (inCmd[1] == 'D') // :XSD - { - if ((inCmd.length() > 2) && (inCmd[2] == 'L')) // :XSDL - { - if (inCmd.length() > 3) - { - if (inCmd[3] == 'L') // :XSDLL - { - if (inCmd.length() > 4) - { - _mount->setDecLimitPosition(false, inCmd.substring(4).toFloat()); - } - else - { - _mount->setDecLimitPosition(false); - } - } - else if (inCmd[3] == 'U') // :XSDLU - { - if (inCmd.length() > 4) - { - _mount->setDecLimitPosition(true, inCmd.substring(4).toFloat()); - } - else - { - _mount->setDecLimitPosition(true); - } - } - else if (inCmd[3] == 'l') // :XSDLl - { - _mount->clearDecLimitPosition(false); - } - else if (inCmd[3] == 'u') // :XSDLU - { - _mount->clearDecLimitPosition(true); - } - } - } - else if ((inCmd.length() > 3) && (inCmd[2] == 'P')) // :XSDP - { - } - else - { - float stepsPerDegree = inCmd.substring(2).toFloat(); - if (stepsPerDegree > 0) - { - _mount->setStepsPerDegree(DEC_STEPS, stepsPerDegree); - } - } - } - else if (inCmd[1] == 'S') // :XSS - { - _mount->setSpeedCalibration(inCmd.substring(2).toFloat(), true); - } - else if (inCmd[1] == 'T') // :XST - { - _mount->setTrackingStepperPos(inCmd.substring(2).toInt()); - } - else if (inCmd[1] == 'M') // :XSM - { - _mount->setManualSlewMode(inCmd[2] == '1'); - } - else if (inCmd[1] == 'X') // :XSX - { - _mount->setSpeed(RA_STEPS, inCmd.substring(2).toFloat()); - } - else if (inCmd[1] == 'Y') // :XSY - { - _mount->setSpeed(DEC_STEPS, inCmd.substring(2).toFloat()); - } - else if (inCmd[1] == 'B') // :XSB - { - _mount->setBacklashCorrection(inCmd.substring(2).toInt()); - } - else if (inCmd[1] == 'H') // :XSH - { - if (inCmd.length() > 2) - { - if (inCmd[2] == 'R') // :XSHR - { - _mount->setHomingOffset(StepperAxis::RA_STEPS, inCmd.substring(3).toInt()); - } - else if (inCmd[2] == 'D') // :XSHD - { - _mount->setHomingOffset(StepperAxis::DEC_STEPS, inCmd.substring(3).toInt()); - } - } - } + else + { + _mount->setDecLimitPosition(false); } - else if (inCmd[0] == 'L') - { // Digital Level -#if USE_GYRO_LEVEL == 1 - if (inCmd[1] == 'G') - { // get values - if (inCmd[2] == 'R') // :XLGR - { // get Calibration/Reference values - return formatResponse( - "%s,%s#", String(_mount->getPitchCalibrationAngle(), 4).c_str(), String(_mount->getRollCalibrationAngle(), 4).c_str()); - } - else if (inCmd[2] == 'C') // :XLGC - { // Get current values - auto angles = Gyro::getCurrentAngles(); - return formatResponse("%s,%s#", String(angles.pitchAngle, 4).c_str(), String(angles.rollAngle, 4).c_str()); - } - else if (inCmd[2] == 'T') // :XLGT - { // Get current temp - float temp = Gyro::getCurrentTemperature(); - return formatResponse("%s#", String(temp, 1).c_str()); - } - } - else if (inCmd[1] == 'S') - { // set values - if (inCmd[2] == 'P') // :XLSP - { // get Calibration/Reference values - _mount->setPitchCalibrationAngle(inCmd.substring(3).toFloat()); - return "1#"; - } - else if (inCmd[2] == 'R') // :XLSR - { - _mount->setRollCalibrationAngle(inCmd.substring(3).toFloat()); - return "1#"; - } - } - else if (inCmd[1] == '1') // :XL1 - { // Turn on Gyro - Gyro::startup(); - return "1#"; - } - else if (inCmd[1] == '0') // :XL0 - { // Turn off Gyro - Gyro::shutdown(); - return "1#"; - } - else - { - return formatResponse("Unknown Level command: X%s", inCmd.c_str()); - } -#endif - return "0#"; +} +void MeadeCommandProcessor::onSetDecLimitUpper(bool havePayload, float value) +{ + if (havePayload) + { + _mount->setDecLimitPosition(true, value); } - else if ((inCmd[0] == 'F') && (inCmd[1] == 'R')) + else { - _mount->clearConfiguration(); // :XFR - return "1#"; + _mount->setDecLimitPosition(true); } +} +void MeadeCommandProcessor::onClearDecLimitLower() +{ + _mount->clearDecLimitPosition(false); +} +void MeadeCommandProcessor::onClearDecLimitUpper() +{ + _mount->clearDecLimitPosition(true); +} +void MeadeCommandProcessor::onSetTrackingSpeedCalibration(float v) +{ + _mount->setSpeedCalibration(v, true); +} +void MeadeCommandProcessor::onSetTrackingStepperPosition(long v) +{ + _mount->setTrackingStepperPos(v); +} +void MeadeCommandProcessor::onSetManualSlewMode(bool enable) +{ + _mount->setManualSlewMode(enable); +} +void MeadeCommandProcessor::onSetRaManualSpeed(float v) +{ + _mount->setSpeed(RA_STEPS, v); +} +void MeadeCommandProcessor::onSetDecManualSpeed(float v) +{ + _mount->setSpeed(DEC_STEPS, v); +} +void MeadeCommandProcessor::onSetBacklashCorrection(int v) +{ + _mount->setBacklashCorrection(v); +} +void MeadeCommandProcessor::onSetRaHomingOffset(long v) +{ + _mount->setHomingOffset(StepperAxis::RA_STEPS, static_cast(v)); +} +void MeadeCommandProcessor::onSetDecHomingOffset(long v) +{ + _mount->setHomingOffset(StepperAxis::DEC_STEPS, static_cast(v)); +} + +bool MeadeCommandProcessor::onLevelIsAvailable() +{ +#if USE_GYRO_LEVEL == 1 + return true; +#else + return false; +#endif +} - return ""; +oat::core::meade::ExtraPitchRoll MeadeCommandProcessor::onLevelGetReferenceAngles() +{ + oat::core::meade::ExtraPitchRoll pr; +#if USE_GYRO_LEVEL == 1 + pr.pitch = _mount->getPitchCalibrationAngle(); + pr.roll = _mount->getRollCalibrationAngle(); +#endif + return pr; +} + +oat::core::meade::ExtraPitchRoll MeadeCommandProcessor::onLevelGetCurrentAngles() +{ + oat::core::meade::ExtraPitchRoll pr; +#if USE_GYRO_LEVEL == 1 + auto angles = Gyro::getCurrentAngles(); + pr.pitch = angles.pitchAngle; + pr.roll = angles.rollAngle; +#endif + return pr; +} + +float MeadeCommandProcessor::onLevelGetTemperature() +{ +#if USE_GYRO_LEVEL == 1 + return Gyro::getCurrentTemperature(); +#else + return 0.0f; +#endif +} + +void MeadeCommandProcessor::onLevelSetReferencePitch(float v) +{ +#if USE_GYRO_LEVEL == 1 + _mount->setPitchCalibrationAngle(v); +#else + (void) v; +#endif +} +void MeadeCommandProcessor::onLevelSetReferenceRoll(float v) +{ +#if USE_GYRO_LEVEL == 1 + _mount->setRollCalibrationAngle(v); +#else + (void) v; +#endif +} +void MeadeCommandProcessor::onLevelStartup() +{ +#if USE_GYRO_LEVEL == 1 + Gyro::startup(); +#endif +} +void MeadeCommandProcessor::onLevelShutdown() +{ +#if USE_GYRO_LEVEL == 1 + Gyro::shutdown(); +#endif } ///////////////////////////// // QUIT ///////////////////////////// -const char *MeadeCommandProcessor::handleMeadeQuit(const String &inCmd) +void MeadeCommandProcessor::onStopAll() { - // :Q# stops a motors - remains in Control mode - // :Qq# command does not stop motors, but quits Control mode - if (inCmd.length() == 0) - { - _mount->stopSlewing(ALL_DIRECTIONS | TRACKING); - _mount->stopSlewing(AZIMUTH_STEPS); - _mount->stopSlewing(ALTITUDE_STEPS); - _mount->stopSlewing(FOCUS_STEPS); - _mount->waitUntilAllStopped(); - return ""; - } + // :Q# stops all motors but remains in Control mode. + _mount->stopSlewing(ALL_DIRECTIONS | TRACKING); + _mount->stopSlewing(AZIMUTH_STEPS); + _mount->stopSlewing(ALTITUDE_STEPS); + _mount->stopSlewing(FOCUS_STEPS); + _mount->waitUntilAllStopped(); +} - switch (inCmd[0]) - { - case 'a': - _mount->stopSlewing(ALL_DIRECTIONS); - break; - case 'e': - _mount->stopSlewing(EAST); - break; - case 'w': - _mount->stopSlewing(WEST); - break; - case 'n': - _mount->stopSlewing(NORTH); - break; - case 's': - _mount->stopSlewing(SOUTH); - break; - case 'q': - inSerialControl = false; - _lcdMenu->setCursor(0, 0); - _lcdMenu->updateDisplay(); - break; - } +void MeadeCommandProcessor::onStopDirectionalAll() +{ + _mount->stopSlewing(ALL_DIRECTIONS); +} - return ""; +void MeadeCommandProcessor::onStopEast() +{ + _mount->stopSlewing(EAST); } -///////////////////////////// -// Set Slew Rates -///////////////////////////// -const char *MeadeCommandProcessor::handleMeadeSetSlewRate(const String &inCmd) +void MeadeCommandProcessor::onStopWest() { - if (inCmd.length() < 1) - { - return ""; - } - switch (inCmd[0]) - { - case 'S': - _mount->setSlewRate(4); - break; // Slew - Fastest - case 'M': - _mount->setSlewRate(3); - break; // Find - 2nd Fastest - case 'C': - _mount->setSlewRate(2); - break; // Center - 2nd Slowest - case 'G': - _mount->setSlewRate(1); - break; // Guide - Slowest - default: - break; - } - return ""; + _mount->stopSlewing(WEST); +} + +void MeadeCommandProcessor::onStopNorth() +{ + _mount->stopSlewing(NORTH); +} + +void MeadeCommandProcessor::onStopSouth() +{ + _mount->stopSlewing(SOUTH); +} + +void MeadeCommandProcessor::onQuitControlMode() +{ + // :Qq# does not stop motors, just leaves Control mode. + inSerialControl = false; + _lcdMenu->setCursor(0, 0); + _lcdMenu->updateDisplay(); } +///////////////////////////// +// Set Slew Rates +///////////////////////////// ///////////////////////////// // FOCUS COMMANDS ///////////////////////////// -const char *MeadeCommandProcessor::handleMeadeFocusCommands(const String &inCmd) +void MeadeCommandProcessor::onFocusContinuousIn() { - if (inCmd.length() < 1) - { - return ""; - } #if (FOCUS_STEPPER_TYPE != STEPPER_TYPE_NONE) - if (inCmd[0] == '+') // :F+ - { - LOG(DEBUG_MEADE, "[MEADE]: Focus focusContinuousMove IN"); - _mount->focusContinuousMove(FOCUS_BACKWARD); - } - else if (inCmd[0] == '-') // :F- - { - LOG(DEBUG_MEADE, "[MEADE]: Focus focusContinuousMove OUT"); - _mount->focusContinuousMove(FOCUS_FORWARD); - } - else if (inCmd[0] == 'M') // :FMnnnn - { - long steps = inCmd.substring(1).toInt(); - LOG(DEBUG_MEADE, "[MEADE]: Focus move by %l steps", steps); - _mount->focusMoveBy(steps); - } - else if ((inCmd[0] >= '1') && (inCmd[0] <= '4')) // :F1 - Slowest, F4 fastest - { - int speed = inCmd[0] - '0'; - LOG(DEBUG_MEADE, "[MEADE]: Focus setSpeed %d", speed); - _mount->focusSetSpeedByRate(speed); - } - else if (inCmd[0] == 'F') // :FF - { - LOG(DEBUG_MEADE, "[MEADE]: Focus setSpeed fastest"); - _mount->focusSetSpeedByRate(4); - } - else if (inCmd[0] == 'S') // :FS - { - LOG(DEBUG_MEADE, "[MEADE]: Focus setSpeed slowest"); - _mount->focusSetSpeedByRate(1); - } - else if (inCmd[0] == 'p') // :Fp - { - LOG(DEBUG_MEADE, "[MEADE]: Focus get stepperPosition"); - long focusPos = _mount->focusGetStepperPosition(); - return formatResponse("%ld#", focusPos); - } - else if (inCmd[0] == 'P') // :FPnnn - { - long steps = inCmd.substring(1).toInt(); - LOG(DEBUG_MEADE, "[MEADE]: Focus set stepperPosition %d", steps); - _mount->focusSetStepperPosition(steps); - return "1"; - } - else if (inCmd[0] == 'B') // :FB - { - LOG(DEBUG_MEADE, "[MEADE]: Focus isRunningFocus"); - return _mount->isRunningFocus() ? "1" : "0"; - } - else if (inCmd[0] == 'Q') // :FQ - { - LOG(DEBUG_MEADE, "[MEADE]: Focus stop"); - _mount->focusStop(); + LOG(DEBUG_MEADE, "[MEADE]: Focus focusContinuousMove IN"); + _mount->focusContinuousMove(FOCUS_BACKWARD); +#endif +} + +void MeadeCommandProcessor::onFocusContinuousOut() +{ +#if (FOCUS_STEPPER_TYPE != STEPPER_TYPE_NONE) + LOG(DEBUG_MEADE, "[MEADE]: Focus focusContinuousMove OUT"); + _mount->focusContinuousMove(FOCUS_FORWARD); +#endif +} + +void MeadeCommandProcessor::onFocusMoveBy(long steps) +{ +#if (FOCUS_STEPPER_TYPE != STEPPER_TYPE_NONE) + LOG(DEBUG_MEADE, "[MEADE]: Focus move by %l steps", steps); + _mount->focusMoveBy(steps); +#else + (void) steps; +#endif +} + +void MeadeCommandProcessor::onFocusSetSpeedByRate(int rate) +{ +#if (FOCUS_STEPPER_TYPE != STEPPER_TYPE_NONE) + LOG(DEBUG_MEADE, "[MEADE]: Focus setSpeed %d", rate); + _mount->focusSetSpeedByRate(rate); +#else + (void) rate; +#endif +} + +void MeadeCommandProcessor::onFocusStop() +{ +#if (FOCUS_STEPPER_TYPE != STEPPER_TYPE_NONE) + LOG(DEBUG_MEADE, "[MEADE]: Focus stop"); + _mount->focusStop(); +#endif +} + +long MeadeCommandProcessor::onFocusGetPosition() +{ +#if (FOCUS_STEPPER_TYPE != STEPPER_TYPE_NONE) + LOG(DEBUG_MEADE, "[MEADE]: Focus get stepperPosition"); + return _mount->focusGetStepperPosition(); +#else + return 0L; +#endif +} + +bool MeadeCommandProcessor::onFocusIsAvailable() +{ +#if (FOCUS_STEPPER_TYPE != STEPPER_TYPE_NONE) + return true; +#else + return false; +#endif +} + +void MeadeCommandProcessor::onFocusSetPosition(long steps) +{ +#if (FOCUS_STEPPER_TYPE != STEPPER_TYPE_NONE) + LOG(DEBUG_MEADE, "[MEADE]: Focus set stepperPosition %d", steps); + _mount->focusSetStepperPosition(steps); +#else + (void) steps; +#endif +} + +bool MeadeCommandProcessor::onFocusGetState() +{ +#if (FOCUS_STEPPER_TYPE != STEPPER_TYPE_NONE) + LOG(DEBUG_MEADE, "[MEADE]: Focus isRunningFocus"); + return _mount->isRunningFocus(); +#else + return false; +#endif +} + +// --------------------------------------------------------------------------- +// IMeadeMovementHandlers overrides — bridge the parser-side callbacks to +// `_mount`. Hardware-feature guards (AZ/ALT stepper presence, Hall-sensor +// auto-home) live here so the dispatcher stays hardware-agnostic. +// --------------------------------------------------------------------------- + +namespace +{ +byte toMountDirection(oat::core::meade::MoveDirection dir) +{ + switch (dir) + { + case oat::core::meade::MoveDirection::North: + return NORTH; + case oat::core::meade::MoveDirection::South: + return SOUTH; + case oat::core::meade::MoveDirection::West: + return WEST; + case oat::core::meade::MoveDirection::East: + default: + return EAST; } +} +} // namespace + +void MeadeCommandProcessor::onStartSlewToTarget() +{ + _mount->startSlewingToTarget(); +} + +void MeadeCommandProcessor::onTrackingOn() +{ + _mount->startSlewing(TRACKING); +} + +void MeadeCommandProcessor::onTrackingOff() +{ + _mount->stopSlewing(TRACKING); +} + +void MeadeCommandProcessor::onGuidePulse(oat::core::meade::MoveDirection dir, int durationMs) +{ + _mount->guidePulse(toMountDirection(dir), durationMs); +} + +void MeadeCommandProcessor::onMoveAzAltHome() +{ + LOG(DEBUG_MEADE, "[MEADE]: Move AZ and ALT to home"); + _mount->moveAZALTToHome(); +} + +void MeadeCommandProcessor::onMoveAzimuth(float arcMinutes) +{ +#if (AZ_STEPPER_TYPE != STEPPER_TYPE_NONE) + LOG(DEBUG_MEADE, "[MEADE]: Move AZ by %f arcmins", arcMinutes); + _mount->moveBy(AZIMUTH_STEPS, arcMinutes); #else - if (inCmd[0] == 'p') // :Fp + (void) arcMinutes; +#endif +} + +void MeadeCommandProcessor::onMoveAltitude(float arcMinutes) +{ +#if (ALT_STEPPER_TYPE != STEPPER_TYPE_NONE) + LOG(DEBUG_MEADE, "[MEADE]: Move ALT by %f arcmins", arcMinutes); + _mount->moveBy(ALTITUDE_STEPS, arcMinutes); +#else + (void) arcMinutes; +#endif +} + +void MeadeCommandProcessor::onSlewEast() +{ + _mount->startSlewing(EAST); +} + +void MeadeCommandProcessor::onSlewWest() +{ + _mount->startSlewing(WEST); +} + +void MeadeCommandProcessor::onSlewNorth() +{ + _mount->startSlewing(NORTH); +} + +void MeadeCommandProcessor::onSlewSouth() +{ + _mount->startSlewing(SOUTH); +} + +void MeadeCommandProcessor::onMoveStepper(oat::core::meade::MovementAxis axis, long steps) +{ + LOG(DEBUG_MEADE, "[MEADE]: MoveStepper: %l steps on axis %d", steps, static_cast(axis)); + switch (axis) { - return "0#"; + case oat::core::meade::MovementAxis::Ra: + _mount->moveStepperBy(RA_STEPS, steps); + break; + case oat::core::meade::MovementAxis::Dec: + _mount->moveStepperBy(DEC_STEPS, steps); + break; + case oat::core::meade::MovementAxis::Azimuth: + _mount->moveStepperBy(AZIMUTH_STEPS, steps); + break; + case oat::core::meade::MovementAxis::Altitude: + _mount->moveStepperBy(ALTITUDE_STEPS, steps); + break; + case oat::core::meade::MovementAxis::Focus: + _mount->moveStepperBy(FOCUS_STEPS, steps); + break; } - else if (inCmd[0] == 'B') // :FB +} + +bool MeadeCommandProcessor::onHomeRa(int direction, const char *distancePayload) +{ +#if USE_HALL_SENSOR_RA_AUTOHOME == 1 + int distance = RA_HOMING_SENSOR_SEARCH_DEGREES; + if (distancePayload != nullptr && distancePayload[0] != '\0') { - return "0"; + distance = clamp(static_cast(strtol(distancePayload, nullptr, 10)), 5, 75); + LOG(DEBUG_MEADE, "[MEADE]: RA AutoHome by %dh", distance); } - + return _mount->findHomeByHallSensor(StepperAxis::RA_STEPS, direction, distance); +#else + (void) direction; + (void) distancePayload; + return false; #endif - return ""; } -const char *MeadeCommandProcessor::processCommand(String inCmd) +bool MeadeCommandProcessor::onHomeDec(int direction, const char *distancePayload) { - if (inCmd.length() < 2) +#if USE_HALL_SENSOR_DEC_AUTOHOME == 1 + int distance = DEC_HOMING_SENSOR_SEARCH_DEGREES; + if (distancePayload != nullptr && distancePayload[0] != '\0') { - return ""; + distance = clamp(static_cast(strtol(distancePayload, nullptr, 10)), 5, 75); + LOG(DEBUG_MEADE, "[MEADE]: DEC AutoHome by %dh", distance); } - if (inCmd[0] == ':') - { - LOG(DEBUG_MEADE, "[MEADE]: Received command '%s'", inCmd.c_str()); - - // Apparently some LX200 implementations put spaces in their commands..... remove them with impunity. - int spacePos; - while ((spacePos = inCmd.indexOf(' ')) != -1) - { - inCmd.remove(spacePos, 1); - } + return _mount->findHomeByHallSensor(StepperAxis::DEC_STEPS, direction, distance); +#else + (void) direction; + (void) distancePayload; + return false; +#endif +} - if (inCmd.length() < 2) - { - return ""; - } - LOG(DEBUG_MEADE, "[MEADE]: Processing command '%s'", inCmd.c_str()); - char command = inCmd[1]; - inCmd = inCmd.substring(2); - _mount->commandReceived(); - switch (command) - { - case 'S': - return handleMeadeSetInfo(inCmd); - case 'M': - return handleMeadeMovement(inCmd); - case 'G': - return handleMeadeGetInfo(inCmd); - case 'g': - return handleMeadeGPSCommands(inCmd); - case 'C': - return handleMeadeSyncControl(inCmd); - case 'h': - return handleMeadeHome(inCmd); - case 'I': - return handleMeadeInit(inCmd); - case 'Q': - return handleMeadeQuit(inCmd); - case 'R': - return handleMeadeSetSlewRate(inCmd); - case 'D': - return handleMeadeDistance(inCmd); - case 'X': - return handleMeadeExtraCommands(inCmd); - case 'F': - return handleMeadeFocusCommands(inCmd); - default: - LOG(DEBUG_MEADE, "[MEADE]: Received unknown command '%s'", inCmd.c_str()); - break; - } - } - return ""; +const char *MeadeCommandProcessor::processCommand(String inCmd) +{ + LOG(DEBUG_MEADE, "[MEADE]: Received command '%s'", inCmd.c_str()); + _mount->commandReceived(); + return store(meade::dispatchMeadeCommand(inCmd.c_str(), *this)); } diff --git a/src/MeadeCommandProcessor.hpp b/src/MeadeCommandProcessor.hpp index e50653d1..8c42b8e2 100644 --- a/src/MeadeCommandProcessor.hpp +++ b/src/MeadeCommandProcessor.hpp @@ -1,10 +1,12 @@ #pragma once +#include "core/meade/MeadeParser.hpp" + // Forward declarations class Mount; class LcdMenu; -class MeadeCommandProcessor +class MeadeCommandProcessor : private oat::core::meade::IMeadeHandlers { public: static MeadeCommandProcessor *createProcessor(Mount *mount, LcdMenu *lcdMenu); @@ -13,25 +15,160 @@ class MeadeCommandProcessor private: MeadeCommandProcessor(Mount *mount, LcdMenu *lcdMenu); - const char *handleMeadeSetInfo(const String &inCmd); - const char *handleMeadeMovement(const String &inCmd); - const char *handleMeadeGetInfo(const String &inCmd); - const char *handleMeadeGPSCommands(const String &inCmd); - const char *handleMeadeSyncControl(const String &inCmd); - const char *handleMeadeHome(const String &inCmd); - const char *handleMeadeInit(const String &inCmd); - const char *handleMeadeQuit(const String &inCmd); - const char *handleMeadeDistance(const String &inCmd); - const char *handleMeadeSetSlewRate(const String &inCmd); - const char *handleMeadeExtraCommands(const String &inCmd); - const char *handleMeadeFocusCommands(const String &inCmd); - - static const char *copyToResponse(const char *src); - static const char *formatResponse(const char *fmt, ...); - static const char *copyToResponse_P(const char *pgmSrc); + + // Persist a freshly-built response across the handler return. + // The returned pointer is valid until the next call to `store`. + const char *store(oat::core::meade::MeadeResponse response); + + // IMeadeGetHandlers overrides. Each method returns a typed domain value; + // the parser layer handles all Meade wire formatting. + const char *onFirmwareVersion() override; + const char *onProductName() override; + oat::core::meade::RaCoordinate onCurrentRa() override; + oat::core::meade::RaCoordinate onTargetRa() override; + oat::core::meade::DecCoordinate onCurrentDec() override; + oat::core::meade::DecCoordinate onTargetDec() override; + const char *onMountStatus() override; + bool onIsSlewing() override; + bool onIsTracking() override; + bool onIsGuiding() override; + oat::core::meade::MeadeLatitude onSiteLatitude() override; + oat::core::meade::MeadeLongitude onSiteLongitude() override; + int onUtcOffset() override; + oat::core::meade::MeadeLocalTime onLocalTime() override; + oat::core::meade::MeadeLocalDate onLocalDate() override; + oat::core::meade::MeadeClockFormat onClockFormat() override; + oat::core::meade::MeadeTrackingRate onTrackingRate() override; + const char *onSiteName(uint8_t index) override; + + // IMeadeSetHandlers overrides. Each method receives a parser-validated + // typed value and returns whether the mount accepted it. + bool onSetTargetDec(oat::core::meade::DecCoordinate dec) override; + bool onSetTargetRa(oat::core::meade::RaCoordinate ra) override; + bool onSetLocalSiderealTime(oat::core::meade::MeadeLocalTime lst) override; + bool onSetHomePoint() override; + bool onSetHourAngle(uint8_t hours, uint8_t minutes) override; + bool onSyncCoordinates(oat::core::meade::DecCoordinate dec, oat::core::meade::RaCoordinate ra) override; + bool onSetSiteLatitude(oat::core::meade::MeadeLatitude lat) override; + bool onSetSiteLongitude(oat::core::meade::MeadeLongitude lon) override; + bool onSetUtcOffset(int hours) override; + bool onSetLocalTime(oat::core::meade::MeadeLocalTime t) override; + bool onSetLocalDate(oat::core::meade::MeadeLocalDate d) override; + + // IMeadeQuitHandlers overrides. All callbacks are side-effect only; the + // dispatcher emits an empty wire response regardless. + void onStopAll() override; + void onStopDirectionalAll() override; + void onStopEast() override; + void onStopWest() override; + void onStopNorth() override; + void onStopSouth() override; + void onQuitControlMode() override; + + // IMeadeDistanceHandlers overrides. + bool onIsSlewingRaOrDec() override; + + // IMeadeInitHandlers overrides. + void onEnterSerialControl() override; + + // IMeadeSyncControlHandlers overrides. + void onSyncToTarget() override; + + // IMeadeHomeHandlers overrides. + void onPark() override; + void onSlewToHome() override; + void onUnpark() override; + void onSetAzAltHome() override; + + // IMeadeSlewRateHandlers overrides. + void onSetSlewRate(uint8_t rate) override; + + // IMeadeGpsHandlers overrides. + bool onStartGpsAcquisition(const char *timeoutPayload) override; + + // IMeadeFocusHandlers overrides. + void onFocusContinuousIn() override; + void onFocusContinuousOut() override; + void onFocusMoveBy(long steps) override; + void onFocusSetSpeedByRate(int rate) override; + void onFocusStop() override; + long onFocusGetPosition() override; + bool onFocusIsAvailable() override; + void onFocusSetPosition(long steps) override; + bool onFocusGetState() override; + + // IMeadeMovementHandlers overrides. + void onStartSlewToTarget() override; + void onTrackingOn() override; + void onTrackingOff() override; + void onGuidePulse(oat::core::meade::MoveDirection dir, int durationMs) override; + void onMoveAzAltHome() override; + void onMoveAzimuth(float arcMinutes) override; + void onMoveAltitude(float arcMinutes) override; + void onSlewEast() override; + void onSlewWest() override; + void onSlewNorth() override; + void onSlewSouth() override; + void onMoveStepper(oat::core::meade::MovementAxis axis, long steps) override; + bool onHomeRa(int direction, const char *distancePayload) override; + bool onHomeDec(int direction, const char *distancePayload) override; + + // IMeadeExtraHandlers overrides. + void onFactoryReset() override; + void onDriftAlignment(int duration) override; + float onGetRaStepsPerDegree() override; + float onGetDecStepsPerDegree() override; + float onGetAltStepsPerDegree() override; + float onGetAzStepsPerDegree() override; + oat::core::meade::ExtraDecLimits onGetDecLimits() override; + float onGetTrackingSpeedCalibration() override; + float onGetRemainingSafeTime() override; + float onGetTrackingSpeed() override; + int onGetBacklashSteps() override; + const char *onGetAutoHomingStates() override; + oat::core::meade::ExtraAzAltPositions onGetAzAltPositions() override; + oat::core::meade::ExtraStepperCoords onGetTargetCoordinatePositions(float raCoord, float decCoord) override; + const char *onGetStepperInfo() override; + const char *onGetMountHardwareInfo() override; + const char *onGetLogBuffer() override; + long onGetRaHomingOffset() override; + long onGetDecHomingOffset() override; + bool onGetHemisphere() override; + oat::core::meade::ExtraHms onGetHourAngle() override; + oat::core::meade::ExtraHms onGetLocalSiderealTime() override; + const char *onGetNetworkStatus() override; + void onSetRaStepsPerDegree(float v) override; + void onSetDecStepsPerDegree(float v) override; + void onSetAzStepsPerDegree(float v) override; + void onSetAltStepsPerDegree(float v) override; + void onSetDecLimitLower(bool havePayload, float value) override; + void onSetDecLimitUpper(bool havePayload, float value) override; + void onClearDecLimitLower() override; + void onClearDecLimitUpper() override; + void onSetTrackingSpeedCalibration(float v) override; + void onSetTrackingStepperPosition(long v) override; + void onSetManualSlewMode(bool enable) override; + void onSetRaManualSpeed(float v) override; + void onSetDecManualSpeed(float v) override; + void onSetBacklashCorrection(int v) override; + void onSetRaHomingOffset(long v) override; + void onSetDecHomingOffset(long v) override; + bool onLevelIsAvailable() override; + oat::core::meade::ExtraPitchRoll onLevelGetReferenceAngles() override; + oat::core::meade::ExtraPitchRoll onLevelGetCurrentAngles() override; + float onLevelGetTemperature() override; + void onLevelSetReferencePitch(float v) override; + void onLevelSetReferenceRoll(float v) override; + void onLevelStartup() override; + void onLevelShutdown() override; Mount *_mount; LcdMenu *_lcdMenu; static MeadeCommandProcessor *_instance; - static char _responseBuffer[200]; + oat::core::meade::MeadeResponse _response; + + // Storage backing the pointer-returning Get callbacks (firmware/product + // names use string literals; mount status / site name use these buffers). + String _mountStatusScratch; + char _siteNameScratch[8]; }; diff --git a/src/adapters/README.md b/src/adapters/README.md new file mode 100644 index 00000000..341ee052 --- /dev/null +++ b/src/adapters/README.md @@ -0,0 +1,92 @@ +# adapters/ + +Thin glue binding domain [`../ports/`](../ports/) to [`../hal/`](../hal/) backends +(and to non-HAL libraries such as TinyGPS data structs). + +Examples (planned): `AccelStepperAxis`, `Tmc2209Driver`, `EepromPersistentStore`, +`SerialLogger`, `LcdMenuDisplay`, `Ssd1306InfoDisplay`, `SerialTransport`, +`WifiTransport`, `TinyGpsAdapter`. + +No domain logic lives here — adapters translate, they don't decide. + +Note: the snippets below are illustrative only. They demonstrate layer responsibilities and dependency direction, not the final refactored code shape; actual code can and will differ. + +Minimal go-to example: + +```cpp +class StepperAxis { +public: + explicit StepperAxis(int32_t stepsPerArcSecondX1000) + : _stepsPerArcSecondX1000(stepsPerArcSecondX1000) + { + } + + virtual ~StepperAxis() = default; + + virtual long currentSteps() const = 0; + virtual bool isBusy() const = 0; + virtual void stop() = 0; + +protected: + long stepsFromMilliArcSeconds(int32_t targetMilliArcSeconds) const + { + return static_cast((static_cast(targetMilliArcSeconds) * _stepsPerArcSecondX1000) / 1000000); + } + + static int32_t milliArcSecondsFromRa(const RA &target) + { + return target.milliArcSeconds(); + } + +private: + int32_t _stepsPerArcSecondX1000; +}; + +class AccelStepperAxis : public StepperAxis { +public: + AccelStepperAxis(hal::IStepperMotor &motor, int32_t stepsPerArcSecondX1000) + : StepperAxis(stepsPerArcSecondX1000), _motor(motor) + { + } + + void moveToSteps(long targetSteps) + { + _motor.setTargetSteps(targetSteps); + _motor.startMotion(); + } + + long currentSteps() const override { return _motor.currentSteps(); } + bool isBusy() const { return _motor.isRunning(); } + void stop() { _motor.stopMotion(); } + +protected: + void moveToMilliArcSeconds(int32_t targetMilliArcSeconds) + { + moveToSteps(stepsFromMilliArcSeconds(targetMilliArcSeconds)); + } + +private: + hal::IStepperMotor &_motor; +}; + +class RaAxis : public IRaAxis, private AccelStepperAxis { +public: + RaAxis(hal::IStepperMotor &motor, int32_t stepsPerArcSecondX1000) + : AccelStepperAxis(motor, stepsPerArcSecondX1000) + { + } + + void moveTo(const RA &target) override + { + moveToMilliArcSeconds(milliArcSecondsFromRa(target)); + } + + bool isBusy() const override { return AccelStepperAxis::isBusy(); } + void stop() override { AccelStepperAxis::stop(); } +}; +``` + +Responsibility: keep step-based/transmission-aware behavior in a generic base, implement the concrete motor backend in `AccelStepperAxis`, then add RA-specific translation in `RaAxis`. +Dependency rule: adapters depend on both [`../ports/`](../ports/) and [`../hal/`](../hal/), but they do not decide go-to targets or mount behavior. + +See [specs/plan.md](../../specs/plan.md) for the target architecture. diff --git a/src/app/README.md b/src/app/README.md new file mode 100644 index 00000000..44e65943 --- /dev/null +++ b/src/app/README.md @@ -0,0 +1,30 @@ +# app/ + +Per-board composition root. The only place that: +- reads `Configuration*.hpp` macros and builds a runtime `MountConfig`, +- selects HAL backends, +- constructs adapters and wires them into [`../core/`](../core/) controllers, +- owns the program entry point (eventually replacing the legacy `.ino`). + +Feature `#ifdef`s survive here and in [`../hal/`](../hal/) backend selection only. + +Note: the snippets below are illustrative only. They demonstrate layer responsibilities and dependency direction, not the final refactored code shape; actual code can and will differ. + +Minimal go-to example: + +```cpp +std::unique_ptr raMotor = makeRaStepperMotor(config); +std::unique_ptr decMotor = makeDecStepperMotor(config); + +RaAxis raAxis(*raMotor, config.raStepsPerArcSecondX1000); +DecAxis decAxis(*decMotor, config.decStepsPerArcSecondX1000); + +GoToController goToController(raAxis, decAxis); + +MeadeCommandAdapter meade(goToController); +``` + +Responsibility: choose concrete implementations and wire the go-to slice together for the selected board. +Dependency rule: app may depend on every inner layer because it is the composition root; the inner layers never depend back on app. + +See [specs/plan.md](../../specs/plan.md) for the target architecture. diff --git a/src/core/README.md b/src/core/README.md new file mode 100644 index 00000000..bc24b413 --- /dev/null +++ b/src/core/README.md @@ -0,0 +1,52 @@ +# core/ + +Pure domain logic. **No Arduino, no hardware libraries, no `#ifdef` feature flags.** +Everything here must be buildable and unit-testable on the host (`native_core` PIO env). + +Depends only on the C++ standard library and on interfaces in [`../ports/`](../ports/). + +Note: the snippets below are illustrative only. They demonstrate layer responsibilities and dependency direction, not the final refactored code shape; actual code can and will differ. + +Minimal go-to example: + +```cpp +struct EquatorialTarget { + RA ra; + int32_t decMilliArcSeconds; +}; + +class IRaAxis { +public: + virtual ~IRaAxis() = default; + virtual void moveTo(const RA &target) = 0; +}; + +class IDecAxis { +public: + virtual ~IDecAxis() = default; + virtual void moveToMilliArcSeconds(int32_t targetMilliArcSeconds) = 0; +}; + +class GoToController { +public: + GoToController(IRaAxis &raAxis, IDecAxis &decAxis) + : _raAxis(raAxis), _decAxis(decAxis) + { + } + + void goTo(const EquatorialTarget &target) + { + _raAxis.moveTo(target.ra); + _decAxis.moveToMilliArcSeconds(target.decMilliArcSeconds); + } + +private: + IRaAxis &_raAxis; + IDecAxis &_decAxis; +}; +``` + +Responsibility: decide what each axis should do for a go-to in domain units such as RA and DEC. +Dependency rule: core depends only on [`../ports/`](../ports/)-style interfaces, never on adapters, HAL, or Arduino APIs. + +See [specs/plan.md](../../specs/plan.md) for the target architecture. diff --git a/src/core/meade/MeadeParser.cpp b/src/core/meade/MeadeParser.cpp new file mode 100644 index 00000000..d9ff938f --- /dev/null +++ b/src/core/meade/MeadeParser.cpp @@ -0,0 +1,131 @@ +/** + * @file MeadeParser.cpp + * @brief Top-level entry points for the Meade LX200 command parser. + * + * Contains `parseMeadeCommand` (classifier) and `dispatchMeadeCommand` + * (unified parse + dispatch). Family-specific handlers live in their own + * files (MeadeParserGet.cpp, MeadeParserSet.cpp, etc.). + */ + +#include "MeadeParser.hpp" +#include "MeadeParserHelpers.hpp" + +#include + +namespace oat +{ +namespace core +{ +namespace meade +{ + +// --------------------------------------------------------------------------- +// Top-level parser +// --------------------------------------------------------------------------- +MeadeParseResult parseMeadeCommand(const char *input) +{ + MeadeParseResult result; + if (input == nullptr || input[0] != ':') + { + return result; + } + + // Copy the input into a stack buffer with whitespace stripped and the + // optional trailing `#` removed. Using a fixed-capacity char buffer keeps + // the parser usable on bare AVR builds that lack libstdc++ (`std::string`). + char normalized[MeadeResponse::Capacity]; + size_t nlen = 0; + for (const char *cursor = input; *cursor != '\0' && nlen + 1 < sizeof(normalized); ++cursor) + { + if (*cursor != ' ') + { + normalized[nlen++] = *cursor; + } + } + normalized[nlen] = '\0'; + + if (nlen < 2) + { + return result; + } + + if (normalized[nlen - 1] == '#') + { + --nlen; + normalized[nlen] = '\0'; + } + + if (nlen < 2) + { + return result; + } + + const char family = normalized[1]; + switch (family) + { + case 'S': + case 'M': + case 'G': + case 'g': + case 'C': + case 'h': + case 'I': + case 'Q': + case 'R': + case 'D': + case 'X': + case 'F': + result.valid = true; + result.family = family; + result.payload.assign(normalized + 2); + return result; + default: + return result; + } +} + +// --------------------------------------------------------------------------- +// Unified dispatch — parse + classify + dispatch in one call +// --------------------------------------------------------------------------- +MeadeResponse dispatchMeadeCommand(const char *input, IMeadeHandlers &h) +{ + MeadeParseResult parsed = parseMeadeCommand(input); + if (!parsed.valid) + { + return MeadeResponse {}; + } + + switch (parsed.family) + { + case 'S': + return handleMeadeSet(parsed.payload.c_str(), h); + case 'M': + return handleMeadeMovement(parsed.payload.c_str(), h); + case 'G': + return handleMeadeGet(parsed.payload.c_str(), h); + case 'g': + return handleMeadeGps(parsed.payload.c_str(), h); + case 'C': + return handleMeadeSyncControl(parsed.payload.c_str(), h); + case 'h': + return handleMeadeHome(parsed.payload.c_str(), h); + case 'I': + return handleMeadeInit(parsed.payload.c_str(), h); + case 'Q': + return handleMeadeQuit(parsed.payload.c_str(), h); + case 'R': + return handleMeadeSetSlewRate(parsed.payload.c_str(), h); + case 'D': + return handleMeadeDistance(parsed.payload.c_str(), h); + case 'X': + return handleMeadeExtra(parsed.payload.c_str(), h); + case 'F': + return handleMeadeFocus(parsed.payload.c_str(), h); + default: + return MeadeResponse {}; + } +} + +} // namespace meade +} // namespace core +} // namespace oat diff --git a/src/core/meade/MeadeParser.hpp b/src/core/meade/MeadeParser.hpp new file mode 100644 index 00000000..0e5c2901 --- /dev/null +++ b/src/core/meade/MeadeParser.hpp @@ -0,0 +1,810 @@ +#pragma once + +/** + * @file MeadeParser.hpp + * @brief Pure parser for the Meade LX200 command protocol used by + * OpenAstroTracker. + * + * The parser is allocation-light (the captured payload is held in a small + * fixed-capacity inline buffer) and has no side effects on the mount. It + * classifies the top-level family, retains the remaining payload bytes, and + * either exposes a small parse result or dispatches the family directly via + * typed handler interfaces that return a `MeadeResponse`. + * + * The framing characters (`:` prefix and `#` terminator) are handled by + * the caller and are not part of the inputs to these functions. + * + * ### Hierarchy + * - `parseMeadeCommand` classifies the top-level command family. + * - Most families then dispatch directly via `handleMeade*` entry points. + * - The `Extra` family also dispatches directly, but still parses nested + * leaf keys inside its `handleMeadeExtra` implementation. + */ + +#include +#include + +namespace oat +{ +namespace core +{ +namespace meade +{ + +/** + * @brief Fixed-capacity NUL-terminated Meade buffer value type. + * + * Used for both parser payload capture and final wire responses. + */ +class MeadeResponse +{ + public: + static constexpr size_t Capacity = 200; + + MeadeResponse() : _length(0) + { + _data[0] = '\0'; + } + + const char *c_str() const + { + return _data; + } + + size_t length() const + { + return _length; + } + + bool empty() const + { + return _length == 0; + } + + char operator[](size_t i) const + { + return _data[i]; + } + + operator const char *() const + { + return _data; + } + + void assign(const char *s) + { + if (s == nullptr) + { + _data[0] = '\0'; + _length = 0; + return; + } + + size_t i = 0; + while ((s[i] != '\0') && (i + 1 < Capacity)) + { + _data[i] = s[i]; + ++i; + } + _data[i] = '\0'; + _length = i; + } + + char *buffer() + { + return _data; + } + + static constexpr size_t capacity() + { + return Capacity; + } + + void setLength(size_t n) + { + _length = n; + } + + private: + char _data[Capacity]; + size_t _length; +}; + +/** @brief Result of `parseMeadeCommand`. */ +struct MeadeParseResult { + /** @brief `true` if the input was recognised. */ + bool valid = false; + /** @brief The family character (e.g. 'G', 'M', 'X'); '\0' for unrecognised. */ + char family = '\0'; + /** @brief Remaining bytes after the family prefix. */ + MeadeResponse payload; +}; + +/** + * @brief Parse functions consume the bytes between the framing `:` prefix + * and the `#` terminator (neither is part of the input) and return a result + * whose `valid` flag indicates whether the command was recognised. + */ + +/** + * @brief Classify a top-level Meade command. + * @param input NUL-terminated bytes after the leading `:`. + */ +MeadeParseResult parseMeadeCommand(const char *input); + +// --------------------------------------------------------------------------- +// Get-family dispatch +// +// The Get pipeline is collapsed into a single entry point: `handleMeadeGet` +// parses the sub-command character(s), invokes the matching typed callback +// on `IMeadeGetHandlers`, and serialises the returned value directly into a +// `MeadeResponse`. There is no intermediate kind enum, parse-result, or +// tag-binding indirection for the Get family. +// +// All Meade reply formatting (zero-padding, sign rules, terminator) lives on +// the parser side; handlers return plain typed values. +// --------------------------------------------------------------------------- + +/** @brief Right-ascension coordinate (hours/minutes/seconds, all non-negative). */ +struct RaCoordinate { + uint8_t hours; + uint8_t minutes; + uint8_t seconds; +}; + +/** @brief Declination coordinate; `degrees` carries the sign (-180..180). */ +struct DecCoordinate { + int16_t degrees; + uint8_t minutes; + uint8_t seconds; +}; + +/** @brief Site latitude; `degrees` is signed (-90..90). */ +struct MeadeLatitude { + int16_t degrees; + uint8_t minutes; +}; + +/** @brief Site longitude; `degrees` is signed (-180..180). */ +struct MeadeLongitude { + int16_t degrees; + uint8_t minutes; +}; + +/** @brief Wall-clock time (24h). The parser handles 12h conversion for `:Ga#`. */ +struct MeadeLocalTime { + uint8_t hours; + uint8_t minutes; + uint8_t seconds; +}; + +/** @brief Calendar date. `year` is the full 4-digit year; parser truncates to 2 digits. */ +struct MeadeLocalDate { + uint8_t month; + uint8_t day; + uint16_t year; +}; + +/** @brief Clock-format selector; controls wire bytes for `:Gc#`. */ +enum class MeadeClockFormat +{ + Hours12, + Hours24, +}; + +/** @brief Tracking rate selector; controls wire bytes for `:GT#`. */ +enum class MeadeTrackingRate +{ + Sidereal, + Lunar, + Solar, +}; + +/** + * @brief Pure callback interface for the Meade `:G...` (Get) command family. + * + * Each method returns a typed value or pointer to static storage. Returned + * `const char *` values must outlive the call (use `static const char[]` or + * compile-time literals). + */ +class IMeadeGetHandlers +{ + public: + virtual ~IMeadeGetHandlers() = default; + + virtual const char *onFirmwareVersion() = 0; + virtual const char *onProductName() = 0; + + virtual RaCoordinate onCurrentRa() = 0; + virtual RaCoordinate onTargetRa() = 0; + + virtual DecCoordinate onCurrentDec() = 0; + virtual DecCoordinate onTargetDec() = 0; + + virtual const char *onMountStatus() = 0; + + virtual bool onIsSlewing() = 0; + virtual bool onIsTracking() = 0; + virtual bool onIsGuiding() = 0; + + virtual MeadeLatitude onSiteLatitude() = 0; + virtual MeadeLongitude onSiteLongitude() = 0; + + virtual int onUtcOffset() = 0; + + virtual MeadeLocalTime onLocalTime() = 0; + virtual MeadeLocalDate onLocalDate() = 0; + + virtual MeadeClockFormat onClockFormat() = 0; + virtual MeadeTrackingRate onTrackingRate() = 0; + + /** @param index Site name slot, 1..4. */ + virtual const char *onSiteName(uint8_t index) = 0; +}; + +/** + * @brief Parse + dispatch + serialise a Meade Get sub-command in one step. + * + * @param suffix The bytes that follow the family `:G` prefix, with the + * trailing `#` already stripped (e.g. `"R"`, `"VN"`, `"IS"`). + * @param handlers Implementation providing the runtime values. + * @return Framed wire response, or an empty response for unknown sub-commands. + */ +MeadeResponse handleMeadeGet(const char *suffix, IMeadeGetHandlers &handlers); + +// --------------------------------------------------------------------------- +// Set-family dispatch +// +// Mirrors the Get pipeline: `handleMeadeSet` parses the sub-command key and +// its payload, invokes the matching typed callback on `IMeadeSetHandlers`, +// and serialises the boolean acknowledgement (`"1"`/`"0"`, or the special +// `:SC#` planetary-data ack) into a `MeadeResponse`. +// +// All wire-format parsing lives in the parser; handlers receive validated +// typed values and report success/failure as a bool. Unrecognised or +// malformed sub-commands produce `"0"` without invoking a handler. +// --------------------------------------------------------------------------- + +/** + * @brief Pure callback interface for the Meade `:S...` (Set) command family. + * + * Each method returns a bool indicating whether the mount accepted the + * value. The parser maps this to the wire bytes `"1"` (success) / `"0"` + * (failure). `:SC#` uses a dedicated ack format implemented by the parser. + */ +class IMeadeSetHandlers +{ + public: + virtual ~IMeadeSetHandlers() = default; + + virtual bool onSetTargetDec(DecCoordinate dec) = 0; + virtual bool onSetTargetRa(RaCoordinate ra) = 0; + + virtual bool onSetLocalSiderealTime(MeadeLocalTime lst) = 0; + virtual bool onSetHomePoint() = 0; + + /** @param hours 0..23 @param minutes 0..59 */ + virtual bool onSetHourAngle(uint8_t hours, uint8_t minutes) = 0; + + virtual bool onSyncCoordinates(DecCoordinate dec, RaCoordinate ra) = 0; + + virtual bool onSetSiteLatitude(MeadeLatitude lat) = 0; + virtual bool onSetSiteLongitude(MeadeLongitude lon) = 0; + + /** @param hours Signed wire value (-12..+14). */ + virtual bool onSetUtcOffset(int hours) = 0; + + virtual bool onSetLocalTime(MeadeLocalTime t) = 0; + virtual bool onSetLocalDate(MeadeLocalDate d) = 0; +}; + +/** + * @brief Parse + dispatch + serialise a Meade Set sub-command in one step. + * + * @param suffix The bytes that follow the family `:S` prefix, with the + * trailing `#` already stripped (e.g. `"d+12*34:56"`). + * @param handlers Implementation providing the mount-side side effects. + * @return Framed wire response, or `"0"` for unknown / malformed input. + */ +MeadeResponse handleMeadeSet(const char *suffix, IMeadeSetHandlers &handlers); + +// --------------------------------------------------------------------------- +// Quit-family dispatch +// --------------------------------------------------------------------------- +// Mirrors the Get/Set pipelines for the `:Q...` family. All quit commands +// emit an empty wire response on the protocol; the handler interface only +// reports side effects. + +/** + * @brief Pure callback interface for the Meade `:Q...` (Quit / stop) family. + * + * Every callback is a side-effect-only operation; the wire response is + * always empty regardless of which callback fires. Unknown sub-commands + * produce an empty response without invoking any handler. + */ +class IMeadeQuitHandlers +{ + public: + virtual ~IMeadeQuitHandlers() = default; + + /** @brief `:Q#` — stop all axes (slew, tracking, az/alt, focus). */ + virtual void onStopAll() = 0; + /** @brief `:Qa#` — stop slew on all directional axes; leaves tracking on. */ + virtual void onStopDirectionalAll() = 0; + /** @brief `:Qe#` — stop eastward slew. */ + virtual void onStopEast() = 0; + /** @brief `:Qw#` — stop westward slew. */ + virtual void onStopWest() = 0; + /** @brief `:Qn#` — stop northward slew. */ + virtual void onStopNorth() = 0; + /** @brief `:Qs#` — stop southward slew. */ + virtual void onStopSouth() = 0; + /** @brief `:Qq#` — leave serial control mode without stopping motors. */ + virtual void onQuitControlMode() = 0; +}; + +/** + * @brief Parse + dispatch a Meade Quit sub-command in one step. + * + * @param suffix The bytes that follow the family `:Q` prefix, with the + * trailing `#` already stripped. The empty string is the + * StopAll variant. + * @param handlers Implementation providing the mount-side side effects. + * @return Empty wire response (`""`) for every outcome including unknown. + */ +MeadeResponse handleMeadeQuit(const char *suffix, IMeadeQuitHandlers &handlers); + +// --------------------------------------------------------------------------- +// Distance family dispatch (:D...) +// --------------------------------------------------------------------------- +// The `:D#` distance bars command reports motion status as a single wire byte +// ('|' while slewing, ' ' when idle) followed by the standard terminator. +// All sub-commands (including the bare `:D#`) collapse to one boolean query. + +/** + * @brief Pure callback interface for the Meade `:D...` (Distance bars) family. + */ +class IMeadeDistanceHandlers +{ + public: + virtual ~IMeadeDistanceHandlers() = default; + + /** @brief True while either RA or DEC is actively slewing toward target. */ + virtual bool onIsSlewingRaOrDec() = 0; +}; + +/** + * @brief Parse + dispatch a Meade Distance sub-command in one step. + * + * @param suffix Bytes following `:D`, trailing `#` already stripped. The + * classic command is the empty suffix; any suffix is treated + * as the same query (legacy lenient behaviour). + * @param handlers Implementation providing the slewing-state query. + * @return Wire bytes: `"|#"` while slewing, `" #"` otherwise. + */ +MeadeResponse handleMeadeDistance(const char *suffix, IMeadeDistanceHandlers &handlers); + +// ---- Init family dispatch (:I...) ------------------------------------- +// +// The `:I#` command hands the mount UI over to serial control. It emits +// an empty response on the wire; the only behaviour is the side effect. + +class IMeadeInitHandlers +{ + public: + virtual ~IMeadeInitHandlers() = default; + + /** @brief Enter serial-control mode (suppress LCD menu, show banner). */ + virtual void onEnterSerialControl() = 0; +}; + +/** + * @brief Parse + dispatch a Meade Init sub-command in one step. + * + * @param suffix Bytes following `:I`, trailing `#` already stripped. Any + * suffix is accepted (legacy lenient behaviour). + * @param handlers Implementation performing the mode switch. + * @return Empty wire response. + */ +MeadeResponse handleMeadeInit(const char *suffix, IMeadeInitHandlers &handlers); + +// ---- SyncControl family dispatch (:C...) ------------------------------ +// +// The only currently supported variant is `:CM#` (sync to target). All +// other suffixes elicit `"FAIL#"`. Successful sync emits `"NONE#"` +// (preserved legacy wire byte). + +class IMeadeSyncControlHandlers +{ + public: + virtual ~IMeadeSyncControlHandlers() = default; + + /** @brief Sync current mount position to the previously-set target. */ + virtual void onSyncToTarget() = 0; +}; + +/** + * @brief Parse + dispatch a Meade SyncControl sub-command in one step. + * + * @param suffix Bytes following `:C`, trailing `#` already stripped. + * @param handlers Implementation performing the sync. + * @return Wire bytes: `"NONE#"` on success, `"FAIL#"` on unknown suffix. + */ +MeadeResponse handleMeadeSyncControl(const char *suffix, IMeadeSyncControlHandlers &handlers); + +// ---- Home family dispatch (:h...) ------------------------------------- +// +// Supported suffixes: +// "P" - park (side effect, empty response) +// "F" - slew home (side effect, empty response) +// "U" - unpark (side effect, "1" response) +// "Z" - set Az/Alt home (side effect, "1" response) +// All other suffixes elicit an empty response. + +class IMeadeHomeHandlers +{ + public: + virtual ~IMeadeHomeHandlers() = default; + + /** @brief Park the mount. */ + virtual void onPark() = 0; + /** @brief Slew to the home position. */ + virtual void onSlewToHome() = 0; + /** @brief Resume tracking after unparking. */ + virtual void onUnpark() = 0; + /** @brief Persist the current Az/Alt position as the home reference. */ + virtual void onSetAzAltHome() = 0; +}; + +/** + * @brief Parse + dispatch a Meade Home sub-command in one step. + * + * @param suffix Bytes following `:h`, trailing `#` already stripped. + * @param handlers Implementation of the four home operations. + * @return Wire bytes per suffix table above; empty for unknown suffix. + */ +MeadeResponse handleMeadeHome(const char *suffix, IMeadeHomeHandlers &handlers); + +// --------------------------------------------------------------------------- +// SetSlewRate-family dispatch +// +// `:R...` selects one of four mount slew rates. Each suffix sets a numeric +// rate value (1..4) and produces an empty wire response: +// "G" -> 1 (guide) +// "C" -> 2 (center) +// "M" -> 3 (find) +// "S" -> 4 (slew) +// All other suffixes elicit an empty response. + +class IMeadeSlewRateHandlers +{ + public: + virtual ~IMeadeSlewRateHandlers() = default; + + /** @brief Apply the given mount slew rate (1..4). */ + virtual void onSetSlewRate(uint8_t rate) = 0; +}; + +/** + * @brief Parse + dispatch a Meade SetSlewRate sub-command in one step. + * + * @param suffix Bytes following `:R`, trailing `#` already stripped. + * @param handlers Slew-rate setter callback. + * @return Empty response on success or unknown suffix. + */ +MeadeResponse handleMeadeSetSlewRate(const char *suffix, IMeadeSlewRateHandlers &handlers); + +// --------------------------------------------------------------------------- +// GPSCommands-family dispatch +// +// `:gT` initiates a blocking GPS acquisition attempt. The handler is +// responsible for the millis()-based wait loop. Returns SetSuccess("1")/("0"). +// All other suffixes return SetSuccess("0") without invoking the handler. + +class IMeadeGpsHandlers +{ + public: + virtual ~IMeadeGpsHandlers() = default; + + /** + * @brief Attempt a GPS acquisition. + * @param timeoutPayload Bytes after `T` (NUL-terminated). May be empty + * (the handler decides the default). + * @return `true` on successful fix within the timeout, `false` otherwise. + */ + virtual bool onStartGpsAcquisition(const char *timeoutPayload) = 0; +}; + +/** + * @brief Parse + dispatch a Meade GPS sub-command in one step. + * + * @param suffix Bytes following `:g`, trailing `#` already stripped. + * @param handlers GPS acquisition callback. + * @return SetSuccess wire bytes ("1" or "0"). + */ +MeadeResponse handleMeadeGps(const char *suffix, IMeadeGpsHandlers &handlers); + +// --------------------------------------------------------------------------- +// Focus-family dispatch +// +// `:F...` sub-commands control an optional focus stepper. When the hardware is +// not available, handler overrides should be no-ops; `onFocusGetPosition` +// returns 0 and `onFocusGetState` returns false. `onFocusIsAvailable` gates +// the `:FP` SetPosition response: when false the dispatcher emits empty +// wire bytes (preserving legacy behaviour) instead of `SetSuccess("1")`. + +class IMeadeFocusHandlers +{ + public: + virtual ~IMeadeFocusHandlers() = default; + + /** @brief `:F+#` — start continuous focus-in. */ + virtual void onFocusContinuousIn() = 0; + /** @brief `:F-#` — start continuous focus-out. */ + virtual void onFocusContinuousOut() = 0; + /** @brief `:FM#` — move focus by `steps` (signed). */ + virtual void onFocusMoveBy(long steps) = 0; + /** @brief `:F<1..4>#`, `:FS#` (rate=1), `:FF#` (rate=4) — set focus speed. */ + virtual void onFocusSetSpeedByRate(int rate) = 0; + /** @brief `:FQ#` — stop focus motion. */ + virtual void onFocusStop() = 0; + /** @brief `:Fp#` — return current focus stepper position (0 when disabled). */ + virtual long onFocusGetPosition() = 0; + /** @brief Whether the focus stepper is compiled in / available. */ + virtual bool onFocusIsAvailable() = 0; + /** @brief `:FP#` — set the focus stepper position. */ + virtual void onFocusSetPosition(long steps) = 0; + /** @brief `:FB#` — return `true` if focus is running, `false` otherwise (or when disabled). */ + virtual bool onFocusGetState() = 0; +}; + +/** + * @brief Parse + dispatch a Meade `:F...` Focus sub-command in one step. + * + * @param suffix Bytes following `:F`, trailing `#` already stripped. + * @param handlers Focus stepper callbacks. + * @return Wire bytes per sub-command (Empty, Long, or SetSuccess). + */ +MeadeResponse handleMeadeFocus(const char *suffix, IMeadeFocusHandlers &handlers); + +// --------------------------------------------------------------------------- +// Movement-family dispatch +// +// `:M...` sub-commands cover slewing, tracking toggle, guide pulses, direct +// axis nudges, stepper-by-steps movement, and Hall-sensor auto-homing. The +// dispatcher classifies the suffix shape, parses payload bytes, and invokes +// the matching handler. Compile-time hardware guards (e.g. AZ_STEPPER_TYPE, +// USE_HALL_SENSOR_RA_AUTOHOME) live in the override implementations; the +// dispatcher remains hardware-agnostic. + +/** @brief Movement axes addressable via `:MX#`. */ +enum class MovementAxis +{ + Ra, + Dec, + Azimuth, + Altitude, + Focus, +}; + +/** @brief Guide pulse / direct slew directions. */ +enum class MoveDirection +{ + North, + South, + East, + West, +}; + +class IMeadeMovementHandlers +{ + public: + virtual ~IMeadeMovementHandlers() = default; + + /** @brief `:MS#` — start slew to current target coordinates. */ + virtual void onStartSlewToTarget() = 0; + /** @brief `:MT1#` — engage sidereal tracking. */ + virtual void onTrackingOn() = 0; + /** @brief `:MT0#` — disengage sidereal tracking. */ + virtual void onTrackingOff() = 0; + /** @brief `:MG#` — fire a guide pulse for `durationMs` milliseconds. */ + virtual void onGuidePulse(MoveDirection dir, int durationMs) = 0; + /** @brief `:MAA#` — move AZ/ALT axes back to their home positions. */ + virtual void onMoveAzAltHome() = 0; + /** @brief `:MAZ#` — nudge the azimuth axis by `arcMinutes`. */ + virtual void onMoveAzimuth(float arcMinutes) = 0; + /** @brief `:MAL#` — nudge the altitude axis by `arcMinutes`. */ + virtual void onMoveAltitude(float arcMinutes) = 0; + /** @brief `:Me#` — begin continuous slew east. */ + virtual void onSlewEast() = 0; + /** @brief `:Mw#` — begin continuous slew west. */ + virtual void onSlewWest() = 0; + /** @brief `:Mn#` — begin continuous slew north. */ + virtual void onSlewNorth() = 0; + /** @brief `:Ms#` — begin continuous slew south. */ + virtual void onSlewSouth() = 0; + /** @brief `:MX#` — move a stepper by raw step count. */ + virtual void onMoveStepper(MovementAxis axis, long steps) = 0; + /** + * @brief `:MHR[degrees]#` — search for the RA Hall-sensor home. + * @param direction `+1` for L, `-1` for R. + * @param distancePayload Bytes after the direction char (may be empty; + * the handler decides the default and clamping policy). + * @return `true` on success, `false` otherwise (incl. when feature is disabled). + */ + virtual bool onHomeRa(int direction, const char *distancePayload) = 0; + /** + * @brief `:MHD[degrees]#` — search for the DEC Hall-sensor home. + * @param direction `+1` for U, `-1` for D. + * @param distancePayload Bytes after the direction char. + */ + virtual bool onHomeDec(int direction, const char *distancePayload) = 0; +}; + +/** + * @brief Parse + dispatch a Meade `:M...` Movement sub-command in one step. + * + * @param suffix Bytes following `:M`, trailing `#` already stripped. + * @param handlers Movement callbacks. + * @return Wire bytes per sub-command. + */ +MeadeResponse handleMeadeMovement(const char *suffix, IMeadeMovementHandlers &handlers); + +// --------------------------------------------------------------------------- +// Extra-family (`:X...`) dispatch +// +// The Extra family is a two-level tree: `:X` where +// `` is one of FR (factory reset), D (drift alignment), G (Get-leaves), +// S (Set-leaves), or L (Level-leaves). `handleMeadeExtra` parses both levels +// directly and dispatches every leaf via a small but wide handler interface. +// Compile-time guards for `USE_GYRO_LEVEL`, `WIFI_ENABLED`, etc. live in the +// override impls. + +/** @brief Output of `IMeadeExtraHandlers::onGetTargetCoordinatePositions`. */ +struct ExtraStepperCoords { + long raPos = 0; + long decPos = 0; +}; + +/** @brief Output of the Level-family angle queries. */ +struct ExtraPitchRoll { + float pitch = 0.0f; + float roll = 0.0f; +}; + +/** @brief Output of `IMeadeExtraHandlers::onGetHourAngle` / `onGetLocalSiderealTime`. */ +struct ExtraHms { + int hours = 0; + int minutes = 0; + int seconds = 0; +}; + +/** @brief Output of `IMeadeExtraHandlers::onGetAzAltPositions`. */ +struct ExtraAzAltPositions { + long az = 0; + long alt = 0; +}; + +/** @brief Output of `IMeadeExtraHandlers::onGetDecLimits` (both lo & hi). */ +struct ExtraDecLimits { + float lo = 0.0f; + float hi = 0.0f; +}; + +class IMeadeExtraHandlers +{ + public: + virtual ~IMeadeExtraHandlers() = default; + + /** @brief `:XFR#` — full configuration wipe. */ + virtual void onFactoryReset() = 0; + + /** @brief `:XD#` — drift-alignment sequence (duration in seconds). */ + virtual void onDriftAlignment(int duration) = 0; + + // ---- Get-leaves ----------------------------------------------------- + virtual float onGetRaStepsPerDegree() = 0; + virtual float onGetDecStepsPerDegree() = 0; + virtual float onGetAltStepsPerDegree() = 0; + virtual float onGetAzStepsPerDegree() = 0; + virtual ExtraDecLimits onGetDecLimits() = 0; + virtual float onGetTrackingSpeedCalibration() = 0; + virtual float onGetRemainingSafeTime() = 0; + virtual float onGetTrackingSpeed() = 0; + virtual int onGetBacklashSteps() = 0; + virtual const char *onGetAutoHomingStates() = 0; + virtual ExtraAzAltPositions onGetAzAltPositions() = 0; + virtual ExtraStepperCoords onGetTargetCoordinatePositions(float raCoord, float decCoord) = 0; + virtual const char *onGetStepperInfo() = 0; + virtual const char *onGetMountHardwareInfo() = 0; + virtual const char *onGetLogBuffer() = 0; + virtual long onGetRaHomingOffset() = 0; + virtual long onGetDecHomingOffset() = 0; + virtual bool onGetHemisphere() = 0; + virtual ExtraHms onGetHourAngle() = 0; + virtual ExtraHms onGetLocalSiderealTime() = 0; + virtual const char *onGetNetworkStatus() = 0; + + // ---- Set-leaves ----------------------------------------------------- + virtual void onSetRaStepsPerDegree(float v) = 0; + virtual void onSetDecStepsPerDegree(float v) = 0; + virtual void onSetAzStepsPerDegree(float v) = 0; + virtual void onSetAltStepsPerDegree(float v) = 0; + /** @brief `:XSDLL[]#` — set lower DEC limit; payload may be empty. */ + virtual void onSetDecLimitLower(bool havePayload, float value) = 0; + virtual void onSetDecLimitUpper(bool havePayload, float value) = 0; + virtual void onClearDecLimitLower() = 0; + virtual void onClearDecLimitUpper() = 0; + virtual void onSetTrackingSpeedCalibration(float v) = 0; + virtual void onSetTrackingStepperPosition(long v) = 0; + virtual void onSetManualSlewMode(bool enable) = 0; + virtual void onSetRaManualSpeed(float v) = 0; + virtual void onSetDecManualSpeed(float v) = 0; + virtual void onSetBacklashCorrection(int v) = 0; + virtual void onSetRaHomingOffset(long v) = 0; + virtual void onSetDecHomingOffset(long v) = 0; + + // ---- Level-leaves --------------------------------------------------- + /** @brief Whether USE_GYRO_LEVEL is compiled in. */ + virtual bool onLevelIsAvailable() = 0; + virtual ExtraPitchRoll onLevelGetReferenceAngles() = 0; + virtual ExtraPitchRoll onLevelGetCurrentAngles() = 0; + virtual float onLevelGetTemperature() = 0; + virtual void onLevelSetReferencePitch(float v) = 0; + virtual void onLevelSetReferenceRoll(float v) = 0; + virtual void onLevelStartup() = 0; + virtual void onLevelShutdown() = 0; +}; + +/** + * @brief Parse + dispatch a Meade `:X...` Extra sub-command in one step. + * + * @param suffix Bytes following `:X`, trailing `#` already stripped. + * @param handlers Extra-family callbacks. + * @return Wire bytes per sub-command. + */ +MeadeResponse handleMeadeExtra(const char *suffix, IMeadeExtraHandlers &handlers); + +// --------------------------------------------------------------------------- +// Aggregate handler interface +// +// Unifies all 12 family-specific handler interfaces into a single type. +// `dispatchMeadeCommand` takes this aggregate and handles the top-level +// family switch internally — callers pass the raw command (after `:`, before +// `#`) and receive a complete `MeadeResponse`. +// --------------------------------------------------------------------------- + +class IMeadeHandlers : public IMeadeGetHandlers, + public IMeadeSetHandlers, + public IMeadeQuitHandlers, + public IMeadeDistanceHandlers, + public IMeadeInitHandlers, + public IMeadeSyncControlHandlers, + public IMeadeHomeHandlers, + public IMeadeSlewRateHandlers, + public IMeadeGpsHandlers, + public IMeadeFocusHandlers, + public IMeadeMovementHandlers, + public IMeadeExtraHandlers +{ + public: + virtual ~IMeadeHandlers() = default; +}; + +/** + * @brief Parse + classify + dispatch a complete Meade command in one call. + * + * Accepts the raw bytes between the framing `:` prefix and `#` terminator. + * Strips whitespace, validates the family character, and dispatches to the + * correct family handler. Returns a fully-formed `MeadeResponse` ready for + * transmission. + * + * @param input NUL-terminated bytes (may include leading `:` and trailing `#`). + * @param handlers Implementation of all family callback interfaces. + * @return Wire response (may be empty for unknown or unrecognised commands). + */ +MeadeResponse dispatchMeadeCommand(const char *input, IMeadeHandlers &handlers); + +} // namespace meade +} // namespace core +} // namespace oat \ No newline at end of file diff --git a/src/core/meade/MeadeParserDistance.cpp b/src/core/meade/MeadeParserDistance.cpp new file mode 100644 index 00000000..6d1d5b26 --- /dev/null +++ b/src/core/meade/MeadeParserDistance.cpp @@ -0,0 +1,26 @@ +/** + * @file MeadeParserDistance.cpp + * @brief Distance-family (`:D...`) dispatcher for the Meade LX200 parser. + */ + +#include "MeadeParser.hpp" +#include "MeadeParserHelpers.hpp" + +namespace oat +{ +namespace core +{ +namespace meade +{ + +MeadeResponse handleMeadeDistance(const char *, IMeadeDistanceHandlers &h) +{ + MeadeResponse r; + writeChar(r, h.onIsSlewingRaOrDec() ? '|' : ' '); + writeTerminator(r); + return r; +} + +} // namespace meade +} // namespace core +} // namespace oat diff --git a/src/core/meade/MeadeParserExtra.cpp b/src/core/meade/MeadeParserExtra.cpp new file mode 100644 index 00000000..2c522b4b --- /dev/null +++ b/src/core/meade/MeadeParserExtra.cpp @@ -0,0 +1,374 @@ +/** + * @file MeadeParserExtra.cpp + * @brief Extra-family (`:X...`) dispatcher for the Meade LX200 parser. + * + * Two-level dispatch: :X where family is one of + * FR (factory reset), D (drift alignment), G (Get-leaves), S (Set-leaves), + * or L (Level-leaves). + */ + +#include "MeadeParser.hpp" +#include "MeadeParserHelpers.hpp" + +#include +#include + +namespace oat +{ +namespace core +{ +namespace meade +{ + +namespace +{ + +MeadeResponse handleExtraGetLeaf(const char *leafInput, IMeadeExtraHandlers &h) +{ + MeadeResponse r; + + if (leafInput == nullptr || leafInput[0] == '\0') + { + return r; + } + + if (isExact(leafInput, "R")) + { + return makeNumericFloatResponse(h.onGetRaStepsPerDegree(), 1); + } + if (isExact(leafInput, "D")) + { + return makeNumericFloatResponse(h.onGetDecStepsPerDegree(), 1); + } + if (isExact(leafInput, "DL")) + { + ExtraDecLimits lim = h.onGetDecLimits(); + return makeDecLimitsPairResponse(lim.lo, lim.hi); + } + if (isExact(leafInput, "DLL")) + { + return makeNumericFloatResponse(h.onGetDecLimits().lo, 1); + } + if (isExact(leafInput, "DLU")) + { + return makeNumericFloatResponse(h.onGetDecLimits().hi, 1); + } + if (startsWith(leafInput, "DL")) + { + return makeBooleanResponse(false); + } + if (isExact(leafInput, "DP")) + { + return makeBooleanResponse(false); + } + if (isExact(leafInput, "S")) + { + return makeNumericFloatResponse(h.onGetTrackingSpeedCalibration(), 5); + } + if (isExact(leafInput, "ST")) + { + return makeNumericFloatResponse(h.onGetRemainingSafeTime(), 7); + } + if (isExact(leafInput, "T")) + { + return makeNumericFloatResponse(h.onGetTrackingSpeed(), 7); + } + if (isExact(leafInput, "B")) + { + return makeIntResponse(h.onGetBacklashSteps()); + } + if (isExact(leafInput, "A")) + { + return makeNumericFloatResponse(h.onGetAltStepsPerDegree(), 1); + } + if (isExact(leafInput, "AH")) + { + return makeFramedTextResponse(h.onGetAutoHomingStates()); + } + if (isExact(leafInput, "AA")) + { + ExtraAzAltPositions p = h.onGetAzAltPositions(); + return makeLongPairPipeResponse(p.az, p.alt); + } + if (isExact(leafInput, "Z")) + { + return makeNumericFloatResponse(h.onGetAzStepsPerDegree(), 1); + } + if (startsWith(leafInput, "C")) + { + // Payload format: "*" — float pair separated by '*'. + const char *payload = leafInput + 1; + const char *star = strchr(payload, '*'); + if (star == nullptr || star == payload) + { + return r; + } + const float raCoord = static_cast(strtod(payload, nullptr)); + const float decCoord = static_cast(strtod(star + 1, nullptr)); + ExtraStepperCoords pos = h.onGetTargetCoordinatePositions(raCoord, decCoord); + return makeLongPairPipeResponse(pos.raPos, pos.decPos); + } + if (isExact(leafInput, "MS")) + { + return makeFramedTextResponse(h.onGetStepperInfo()); + } + if (startsWith(leafInput, "M")) + { + return makeFramedTextResponse(h.onGetMountHardwareInfo()); + } + if (isExact(leafInput, "O")) + { + return makeLiteralResponse(h.onGetLogBuffer()); + } + if (isExact(leafInput, "HR")) + { + return makeLongResponse(h.onGetRaHomingOffset()); + } + if (isExact(leafInput, "HD")) + { + return makeLongResponse(h.onGetDecHomingOffset()); + } + if (isExact(leafInput, "HS")) + { + return makeHemisphereResponse(h.onGetHemisphere()); + } + if (isExact(leafInput, "H")) + { + ExtraHms t = h.onGetHourAngle(); + return makeCompactHmsResponse(t.hours, t.minutes, t.seconds); + } + if (startsWith(leafInput, "H")) + { + return makeBooleanResponse(false); + } + if (isExact(leafInput, "L")) + { + ExtraHms t = h.onGetLocalSiderealTime(); + return makeCompactHmsResponse(t.hours, t.minutes, t.seconds); + } + if (isExact(leafInput, "N")) + { + return makeFramedTextResponse(h.onGetNetworkStatus()); + } + return r; +} + +MeadeResponse handleExtraSetLeaf(const char *leafInput, IMeadeExtraHandlers &h) +{ + MeadeResponse r; + if (leafInput == nullptr || leafInput[0] == '\0') + { + return r; + } + + if (isExact(leafInput, "DLl")) + { + h.onClearDecLimitLower(); + return r; + } + if (isExact(leafInput, "DLu")) + { + h.onClearDecLimitUpper(); + return r; + } + if (startsWith(leafInput, "DLL")) + { + const char *payload = leafInput + 3; + const bool havePayload = payload[0] != '\0'; + const float value = havePayload ? static_cast(strtod(payload, nullptr)) : 0.0f; + h.onSetDecLimitLower(havePayload, value); + return r; + } + if (startsWith(leafInput, "DLU")) + { + const char *payload = leafInput + 3; + const bool havePayload = payload[0] != '\0'; + const float value = havePayload ? static_cast(strtod(payload, nullptr)) : 0.0f; + h.onSetDecLimitUpper(havePayload, value); + return r; + } + if (startsWith(leafInput, "DP")) + { + return r; + } + if (startsWith(leafInput, "HR")) + { + h.onSetRaHomingOffset(strtol(leafInput + 2, nullptr, 10)); + return r; + } + if (startsWith(leafInput, "HD")) + { + h.onSetDecHomingOffset(strtol(leafInput + 2, nullptr, 10)); + return r; + } + if (startsWith(leafInput, "D") && leafInput[1] != '\0') + { + const float v = static_cast(strtod(leafInput + 1, nullptr)); + if (v > 0.0f) + { + h.onSetDecStepsPerDegree(v); + } + return r; + } + if (startsWith(leafInput, "R")) + { + h.onSetRaStepsPerDegree(static_cast(strtod(leafInput + 1, nullptr))); + return r; + } + if (startsWith(leafInput, "A")) + { + h.onSetAzStepsPerDegree(static_cast(strtod(leafInput + 1, nullptr))); + return r; + } + if (startsWith(leafInput, "L")) + { + h.onSetAltStepsPerDegree(static_cast(strtod(leafInput + 1, nullptr))); + return r; + } + if (startsWith(leafInput, "S")) + { + h.onSetTrackingSpeedCalibration(static_cast(strtod(leafInput + 1, nullptr))); + return r; + } + if (startsWith(leafInput, "T")) + { + h.onSetTrackingStepperPosition(strtol(leafInput + 1, nullptr, 10)); + return r; + } + if (startsWith(leafInput, "M")) + { + h.onSetManualSlewMode(leafInput[1] == '1'); + return r; + } + if (startsWith(leafInput, "X")) + { + h.onSetRaManualSpeed(static_cast(strtod(leafInput + 1, nullptr))); + return r; + } + if (startsWith(leafInput, "Y")) + { + h.onSetDecManualSpeed(static_cast(strtod(leafInput + 1, nullptr))); + return r; + } + if (startsWith(leafInput, "B")) + { + h.onSetBacklashCorrection(static_cast(strtol(leafInput + 1, nullptr, 10))); + return r; + } + return r; +} + +MeadeResponse handleExtraLevelLeaf(const char *leafInput, IMeadeExtraHandlers &h) +{ + MeadeResponse r; + + if (!h.onLevelIsAvailable()) + { + return makeBooleanResponse(false); + } + + if (leafInput == nullptr || leafInput[0] == '\0') + { + return r; + } + + if (startsWith(leafInput, "GR")) + { + ExtraPitchRoll pr = h.onLevelGetReferenceAngles(); + return makeAnglePair4Response(pr.pitch, pr.roll); + } + if (startsWith(leafInput, "GC")) + { + ExtraPitchRoll pr = h.onLevelGetCurrentAngles(); + return makeAnglePair4Response(pr.pitch, pr.roll); + } + if (startsWith(leafInput, "GT")) + { + return makeNumericFloatResponse(h.onLevelGetTemperature(), 1); + } + if (startsWith(leafInput, "G")) + { + return r; + } + if (startsWith(leafInput, "SP")) + { + h.onLevelSetReferencePitch(static_cast(strtod(leafInput + 2, nullptr))); + return makeBooleanResponse(true); + } + if (startsWith(leafInput, "SR")) + { + h.onLevelSetReferenceRoll(static_cast(strtod(leafInput + 2, nullptr))); + return makeBooleanResponse(true); + } + if (startsWith(leafInput, "S")) + { + return r; + } + if (startsWith(leafInput, "1")) + { + h.onLevelStartup(); + return makeBooleanResponse(true); + } + if (startsWith(leafInput, "0")) + { + h.onLevelShutdown(); + return makeBooleanResponse(true); + } + + // Echo "L" + the original leaf input, matching legacy behavior. + char echoed[MeadeResponse::Capacity]; + echoed[0] = 'L'; + size_t i = 0; + for (; leafInput[i] != '\0' && (i + 2) < sizeof(echoed); ++i) + { + echoed[i + 1] = leafInput[i]; + } + echoed[i + 1] = '\0'; + return makeLevelUnknownResponse(echoed); +} + +} // namespace + +MeadeResponse handleMeadeExtra(const char *suffix, IMeadeExtraHandlers &h) +{ + MeadeResponse r; + + if (suffix == nullptr || suffix[0] == '\0') + { + return r; + } + + if (startsWith(suffix, "FR")) + { + h.onFactoryReset(); + return makeBooleanResponse(true); + } + + if (startsWith(suffix, "D")) + { + const int duration = static_cast(strtol(suffix + 1, nullptr, 10)) - 3; + h.onDriftAlignment(duration); + return r; + } + + if (startsWith(suffix, "G")) + { + return handleExtraGetLeaf(suffix + 1, h); + } + + if (startsWith(suffix, "S")) + { + return handleExtraSetLeaf(suffix + 1, h); + } + + if (startsWith(suffix, "L")) + { + return handleExtraLevelLeaf(suffix + 1, h); + } + + return r; +} + +} // namespace meade +} // namespace core +} // namespace oat diff --git a/src/core/meade/MeadeParserFocus.cpp b/src/core/meade/MeadeParserFocus.cpp new file mode 100644 index 00000000..b5da3fb2 --- /dev/null +++ b/src/core/meade/MeadeParserFocus.cpp @@ -0,0 +1,79 @@ +/** + * @file MeadeParserFocus.cpp + * @brief Focus-family (`:F...`) dispatcher for the Meade LX200 parser. + */ + +#include "MeadeParser.hpp" +#include "MeadeParserHelpers.hpp" + +#include + +namespace oat +{ +namespace core +{ +namespace meade +{ + +MeadeResponse handleMeadeFocus(const char *suffix, IMeadeFocusHandlers &h) +{ + MeadeResponse r; + if (suffix == nullptr || suffix[0] == '\0') + { + return r; + } + + Cursor c(suffix); + + // `:F1#` .. `:F4#` — speed-by-rate digits act as the whole input. + if (c.peek() >= '1' && c.peek() <= '4') + { + c.match(c.peek()); + if (c.atEnd()) + { + h.onFocusSetSpeedByRate(suffix[0] - '0'); + return r; + } + } + switch (c.peek()) + { + case '+': + h.onFocusContinuousIn(); + break; + case '-': + h.onFocusContinuousOut(); + break; + case 'M': + c.match('M'); + h.onFocusMoveBy(strtol(c.remaining(), nullptr, 10)); + break; + case 'F': + h.onFocusSetSpeedByRate(4); + break; + case 'S': + h.onFocusSetSpeedByRate(1); + break; + case 'p': + return makeLongResponse(h.onFocusGetPosition()); + case 'P': + if (h.onFocusIsAvailable()) + { + c.match('P'); + h.onFocusSetPosition(strtol(c.remaining(), nullptr, 10)); + return makeSetSuccessResponse(true); + } + break; + case 'B': + return makeSetSuccessResponse(h.onFocusGetState()); + case 'Q': + h.onFocusStop(); + break; + default: + break; + } + return r; +} + +} // namespace meade +} // namespace core +} // namespace oat diff --git a/src/core/meade/MeadeParserGet.cpp b/src/core/meade/MeadeParserGet.cpp new file mode 100644 index 00000000..fbcea0b9 --- /dev/null +++ b/src/core/meade/MeadeParserGet.cpp @@ -0,0 +1,127 @@ +/** + * @file MeadeParserGet.cpp + * @brief Get-family (`:G...`) dispatcher for the Meade LX200 parser. + */ + +#include "MeadeParser.hpp" +#include "MeadeParserHelpers.hpp" + +namespace oat +{ +namespace core +{ +namespace meade +{ + +MeadeResponse handleMeadeGet(const char *s, IMeadeGetHandlers &h) +{ + MeadeResponse r; + if (!s || s[0] == '\0') + { + return r; + } + + // Two-character commands. + if (s[1] != '\0' && s[2] == '\0') + { + if (s[0] == 'V') + { + switch (s[1]) + { + case 'N': + writeCString(r, h.onFirmwareVersion()); + return r; + case 'P': + writeCString(r, h.onProductName()); + return r; + default: + return r; + } + } + if (s[0] == 'I') + { + switch (s[1]) + { + case 'S': + writeBool01(r, h.onIsSlewing()); + return r; + case 'T': + writeBool01(r, h.onIsTracking()); + return r; + case 'G': + writeBool01(r, h.onIsGuiding()); + return r; + default: + return r; + } + } + return r; + } + + // Single-character commands. + if (s[1] != '\0') + { + return r; + } + + switch (s[0]) + { + case 'R': + writeRa(r, h.onCurrentRa()); + return r; + case 'r': + writeRa(r, h.onTargetRa()); + return r; + case 'D': + writeDec(r, h.onCurrentDec()); + return r; + case 'd': + writeDec(r, h.onTargetDec()); + return r; + case 'X': + writeCString(r, h.onMountStatus()); + return r; + case 't': + writeLatitude(r, h.onSiteLatitude()); + return r; + case 'g': + writeLongitude(r, h.onSiteLongitude()); + return r; + case 'G': + writeUtcOffset(r, h.onUtcOffset()); + return r; + case 'a': + writeTime12h(r, h.onLocalTime()); + return r; + case 'L': + writeTime24h(r, h.onLocalTime()); + return r; + case 'C': + writeLocalDate(r, h.onLocalDate()); + return r; + case 'c': + writeClockFormat(r, h.onClockFormat()); + return r; + case 'T': + writeTrackingRate(r, h.onTrackingRate()); + return r; + case 'M': + writeCString(r, h.onSiteName(1)); + return r; + case 'N': + writeCString(r, h.onSiteName(2)); + return r; + case 'O': + writeCString(r, h.onSiteName(3)); + return r; + case 'P': + writeCString(r, h.onSiteName(4)); + return r; + default: + return r; + } +} + +} // namespace meade +} // namespace core +} // namespace oat diff --git a/src/core/meade/MeadeParserGps.cpp b/src/core/meade/MeadeParserGps.cpp new file mode 100644 index 00000000..96a6dc69 --- /dev/null +++ b/src/core/meade/MeadeParserGps.cpp @@ -0,0 +1,31 @@ +/** + * @file MeadeParserGps.cpp + * @brief GPS-family (`:g...`) dispatcher for the Meade LX200 parser. + */ + +#include "MeadeParser.hpp" +#include "MeadeParserHelpers.hpp" + +namespace oat +{ +namespace core +{ +namespace meade +{ + +MeadeResponse handleMeadeGps(const char *suffix, IMeadeGpsHandlers &h) +{ + MeadeResponse r; + if (suffix == nullptr || suffix[0] != 'T') + { + writeChar(r, '0'); + return r; + } + const bool acquired = h.onStartGpsAcquisition(suffix + 1); + writeChar(r, acquired ? '1' : '0'); + return r; +} + +} // namespace meade +} // namespace core +} // namespace oat diff --git a/src/core/meade/MeadeParserHelpers.cpp b/src/core/meade/MeadeParserHelpers.cpp new file mode 100644 index 00000000..a167b7e1 --- /dev/null +++ b/src/core/meade/MeadeParserHelpers.cpp @@ -0,0 +1,565 @@ +/** + * @file MeadeParserHelpers.cpp + * @brief Shared helper implementations for the Meade LX200 parser. + * + * All symbols live in oat::core::meade. This file is internal — not part of + * the public API (see MeadeParserHelpers.hpp for declarations). + */ + +#include "MeadeParserHelpers.hpp" + +#include +#include +#include +#include + +namespace oat +{ +namespace core +{ +namespace meade +{ + +// --------------------------------------------------------------------------- +// Cursor +// --------------------------------------------------------------------------- + +Cursor::Cursor(const char *p) : _p(p ? p : "") +{ +} + +bool Cursor::atEnd() const +{ + return *_p == '\0'; +} +char Cursor::peek() const +{ + return *_p; +} +const char *Cursor::remaining() const +{ + return _p; +} + +bool Cursor::match(char c) +{ + if (*_p != c) + return false; + ++_p; + return true; +} + +bool Cursor::matchIn(const char *set) +{ + if (*_p == '\0') + return false; + for (const char *s = set; *s; ++s) + { + if (*_p == *s) + { + ++_p; + return true; + } + } + return false; +} + +bool Cursor::digits(int n, unsigned &out) +{ + unsigned v = 0; + for (int i = 0; i < n; ++i) + { + char c = *_p; + if (c < '0' || c > '9') + return false; + v = v * 10 + static_cast(c - '0'); + ++_p; + } + out = v; + return true; +} + +bool Cursor::signed2(int &out) +{ + char sign = peek(); + if (sign != '+' && sign != '-') + return false; + ++_p; + unsigned v = 0; + if (!digits(2, v)) + return false; + out = (sign == '-') ? -static_cast(v) : static_cast(v); + return true; +} + +bool Cursor::signed3(int &out) +{ + char sign = peek(); + if (sign != '+' && sign != '-') + return false; + ++_p; + unsigned v = 0; + if (!digits(3, v)) + return false; + out = (sign == '-') ? -static_cast(v) : static_cast(v); + return true; +} + +// --------------------------------------------------------------------------- +// String helpers +// --------------------------------------------------------------------------- + +bool isExact(const char *input, const char *key) +{ + return strcmp(input != nullptr ? input : "", key) == 0; +} + +bool startsWith(const char *input, const char *prefix) +{ + if (input == nullptr || prefix == nullptr) + { + return false; + } + + while (*prefix != '\0') + { + if (*input == '\0' || *input != *prefix) + { + return false; + } + ++input; + ++prefix; + } + return true; +} + +// --------------------------------------------------------------------------- +// Low-level write primitives +// --------------------------------------------------------------------------- + +void writeChar(MeadeResponse &r, char c) +{ + const size_t n = r.length(); + if (n + 1 >= r.capacity()) + { + return; + } + r.buffer()[n] = c; + r.buffer()[n + 1] = '\0'; + r.setLength(n + 1); +} + +void writeText(MeadeResponse &r, const char *s) +{ + if (!s) + { + return; + } + while (*s) + { + writeChar(r, *s++); + } +} + +void writeTerminator(MeadeResponse &r) +{ + writeChar(r, '#'); +} + +void writeUnsignedPadded(MeadeResponse &r, unsigned value, int width) +{ + char buf[12]; + int n = 0; + if (value == 0) + { + buf[n++] = '0'; + } + else + { + while (value > 0 && n < 11) + { + buf[n++] = static_cast('0' + (value % 10)); + value /= 10; + } + } + while (n < width && n < 11) + { + buf[n++] = '0'; + } + while (n > 0) + { + writeChar(r, buf[--n]); + } +} + +void writeSignedPadded(MeadeResponse &r, int value, int digits) +{ + writeChar(r, value < 0 ? '-' : '+'); + if (value < 0) + { + value = -value; + } + writeUnsignedPadded(r, static_cast(value), digits); +} + +void writeBool01(MeadeResponse &r, bool b) +{ + writeChar(r, b ? '1' : '0'); + writeTerminator(r); +} + +void writeCString(MeadeResponse &r, const char *s) +{ + writeText(r, s); + writeTerminator(r); +} + +// --------------------------------------------------------------------------- +// Format-specific writers +// --------------------------------------------------------------------------- + +void writeRa(MeadeResponse &r, const RaCoordinate &ra) +{ + writeUnsignedPadded(r, ra.hours, 2); + writeChar(r, ':'); + writeUnsignedPadded(r, ra.minutes, 2); + writeChar(r, ':'); + writeUnsignedPadded(r, ra.seconds, 2); + writeTerminator(r); +} + +void writeDec(MeadeResponse &r, const DecCoordinate &d) +{ + int deg = d.degrees; + writeChar(r, deg < 0 ? '-' : '+'); + if (deg < 0) + { + deg = -deg; + } + writeUnsignedPadded(r, static_cast(deg), 2); + writeChar(r, '*'); + writeUnsignedPadded(r, d.minutes, 2); + writeChar(r, '\''); + writeUnsignedPadded(r, d.seconds, 2); + writeTerminator(r); +} + +void writeLatitude(MeadeResponse &r, const MeadeLatitude &l) +{ + int deg = l.degrees; + writeChar(r, deg < 0 ? '-' : '+'); + if (deg < 0) + { + deg = -deg; + } + writeUnsignedPadded(r, static_cast(deg), 2); + writeChar(r, '*'); + writeUnsignedPadded(r, l.minutes, 2); + writeTerminator(r); +} + +void writeLongitude(MeadeResponse &r, const MeadeLongitude &l) +{ + int deg = l.degrees; + writeChar(r, deg < 0 ? '-' : '+'); + if (deg < 0) + { + deg = -deg; + } + writeUnsignedPadded(r, static_cast(deg), 3); + writeChar(r, '*'); + writeUnsignedPadded(r, l.minutes, 2); + writeTerminator(r); +} + +void writeTime24h(MeadeResponse &r, const MeadeLocalTime &t) +{ + writeUnsignedPadded(r, t.hours, 2); + writeChar(r, ':'); + writeUnsignedPadded(r, t.minutes, 2); + writeChar(r, ':'); + writeUnsignedPadded(r, t.seconds, 2); + writeTerminator(r); +} + +void writeTime12h(MeadeResponse &r, const MeadeLocalTime &t) +{ + // The :Ga# Meade command returns 12h wall-clock time. Conversion: 0 -> 12, + // 13..23 -> 1..11 (PM); 1..12 unchanged. The wire format omits AM/PM markers. + uint8_t h = t.hours; + if (h == 0) + { + h = 12; + } + else if (h > 12) + { + h = static_cast(h - 12); + } + MeadeLocalTime t12 = {h, t.minutes, t.seconds}; + writeTime24h(r, t12); +} + +void writeLocalDate(MeadeResponse &r, const MeadeLocalDate &d) +{ + writeUnsignedPadded(r, d.month, 2); + writeChar(r, '/'); + writeUnsignedPadded(r, d.day, 2); + writeChar(r, '/'); + writeUnsignedPadded(r, static_cast(d.year % 100), 2); + writeTerminator(r); +} + +void writeUtcOffset(MeadeResponse &r, int hours) +{ + writeSignedPadded(r, hours, 2); + writeTerminator(r); +} + +void writeClockFormat(MeadeResponse &r, MeadeClockFormat f) +{ + writeText(r, f == MeadeClockFormat::Hours24 ? "24" : "12"); + writeTerminator(r); +} + +void writeTrackingRate(MeadeResponse &r, MeadeTrackingRate t) +{ + const char *s = "60.0"; + switch (t) + { + case MeadeTrackingRate::Sidereal: + s = "60.0"; + break; + case MeadeTrackingRate::Lunar: + s = "57.9"; + break; + case MeadeTrackingRate::Solar: + s = "60.1"; + break; + } + writeText(r, s); + writeTerminator(r); +} + +// Write a positive int without padding or sign. +void writeInt(MeadeResponse &r, int value) +{ + if (value == 0) + { + writeChar(r, '0'); + return; + } + char buf[12]; + int n = 0; + while (value > 0 && n < 11) + { + buf[n++] = static_cast('0' + (value % 10)); + value /= 10; + } + while (n > 0) + { + writeChar(r, buf[--n]); + } +} + +// Write a signed int without padding. +void writeSignedInt(MeadeResponse &r, int value) +{ + if (value < 0) + { + writeChar(r, '-'); + value = -value; + } + writeInt(r, value); +} + +// Write a long (signed) without padding. +void writeLong(MeadeResponse &r, long value) +{ + if (value < 0) + { + writeChar(r, '-'); + value = -value; + } + if (value == 0) + { + writeChar(r, '0'); + return; + } + char buf[22]; + int n = 0; + while (value > 0 && n < 20) + { + buf[n++] = static_cast('0' + (value % 10)); + value /= 10; + } + while (n > 0) + { + writeChar(r, buf[--n]); + } +} + +// Write a float with the given decimal precision (0..9). +// No terminator appended. +void writeFloat(MeadeResponse &r, float value, int precision) +{ + if (precision < 0) + { + precision = 0; + } + if (precision > 9) + { + precision = 9; + } + + double v = static_cast(value); + bool negative = v < 0; + if (negative) + { + v = -v; + } + + // Separate integer and fractional parts. + int intVal = static_cast(v); + double frac = v - static_cast(intVal); + + if (negative) + { + writeChar(r, '-'); + } + writeInt(r, intVal); + + if (precision > 0) + { + writeChar(r, '.'); + for (int i = 0; i < precision; ++i) + { + frac *= 10.0; + int digit = static_cast(frac); + if (digit > 9) + { + digit = 9; // guard against floating-point rounding + } + writeUnsignedPadded(r, static_cast(digit), 1); + frac -= static_cast(digit); + } + } +} + +// --------------------------------------------------------------------------- +// High-level make*Response wrappers +// --------------------------------------------------------------------------- + +MeadeResponse makeLiteralResponse(const char *text) +{ + MeadeResponse r; + writeText(r, text != nullptr ? text : ""); + return r; +} + +MeadeResponse makeSetSuccessResponse(bool ok) +{ + MeadeResponse r; + writeChar(r, ok ? '1' : '0'); + return r; +} + +MeadeResponse makeFramedTextResponse(const char *text) +{ + MeadeResponse r; + writeText(r, text != nullptr ? text : ""); + writeTerminator(r); + return r; +} + +MeadeResponse makeLongResponse(long value) +{ + MeadeResponse r; + writeLong(r, value); + writeTerminator(r); + return r; +} + +MeadeResponse makeBooleanResponse(bool flag) +{ + MeadeResponse r; + writeChar(r, flag ? '1' : '0'); + writeTerminator(r); + return r; +} + +MeadeResponse makeNumericFloatResponse(float value, int precision) +{ + MeadeResponse r; + writeFloat(r, value, precision); + writeTerminator(r); + return r; +} + +MeadeResponse makeIntResponse(int value) +{ + MeadeResponse r; + writeSignedInt(r, value); + writeTerminator(r); + return r; +} + +MeadeResponse makeLongPairPipeResponse(long a, long b) +{ + MeadeResponse r; + writeLong(r, a); + writeChar(r, '|'); + writeLong(r, b); + writeTerminator(r); + return r; +} + +MeadeResponse makeDecLimitsPairResponse(float lo, float hi) +{ + MeadeResponse r; + writeFloat(r, lo, 1); + writeChar(r, '|'); + writeFloat(r, hi, 1); + writeTerminator(r); + return r; +} + +MeadeResponse makeHemisphereResponse(bool north) +{ + MeadeResponse r; + writeChar(r, north ? 'N' : 'S'); + writeTerminator(r); + return r; +} + +MeadeResponse makeCompactHmsResponse(int hours, int minutes, int seconds) +{ + MeadeResponse r; + writeUnsignedPadded(r, static_cast(hours), 2); + writeUnsignedPadded(r, static_cast(minutes), 2); + writeUnsignedPadded(r, static_cast(seconds), 2); + writeTerminator(r); + return r; +} + +MeadeResponse makeAnglePair4Response(float a, float b) +{ + MeadeResponse r; + writeFloat(r, a, 4); + writeChar(r, ','); + writeFloat(r, b, 4); + writeTerminator(r); + return r; +} + +MeadeResponse makeLevelUnknownResponse(const char *echoedCmd) +{ + MeadeResponse r; + writeText(r, "Unknown Level command: X"); + writeText(r, echoedCmd != nullptr ? echoedCmd : ""); + writeTerminator(r); + return r; +} + +} // namespace meade +} // namespace core +} // namespace oat diff --git a/src/core/meade/MeadeParserHelpers.hpp b/src/core/meade/MeadeParserHelpers.hpp new file mode 100644 index 00000000..2c064079 --- /dev/null +++ b/src/core/meade/MeadeParserHelpers.hpp @@ -0,0 +1,117 @@ +#pragma once + +/** + * @file MeadeParserHelpers.hpp + * @brief Private helper declarations shared across MeadeParser family implementations. + * + * This header is internal to src/core/ — not part of the public API. + * All symbols live in oat::core::meade. + */ + +#include "MeadeParser.hpp" + +#include +#include + +namespace oat +{ +namespace core +{ +namespace meade +{ + +// --------------------------------------------------------------------------- +// Cursor — single-pass input cursor with small grammar primitives +// +// Forward-only; never backtracks. Each primitive returns `false` on mismatch +// (cursor is advanced on success). Ideal for fixed-format Meade sub-commands +// like coordinates, times, and dates. +// --------------------------------------------------------------------------- + +class Cursor +{ + public: + explicit Cursor(const char *p); + + bool atEnd() const; + char peek() const; + const char *remaining() const; + + /// Consume one character if it matches `c`; advance on success. + bool match(char c); + + /// Consume one character if it is any of the chars in `set`. + bool matchIn(const char *set); + + /// Read exactly `n` decimal digits into `out` (big-endian, no separators). + bool digits(int n, unsigned &out); + + /// Read "+DD" or "-DD" into a signed int. + bool signed2(int &out); + + /// Read "+DDD" or "-DDD" into a signed int. + bool signed3(int &out); + + private: + const char *_p; +}; + +// --------------------------------------------------------------------------- +// Low-level write primitives — mutate a MeadeResponse incrementally. +// They never append the `#` terminator — the caller adds it via +// `writeTerminator` when needed. +// --------------------------------------------------------------------------- + +void writeChar(MeadeResponse &r, char c); +void writeText(MeadeResponse &r, const char *s); +void writeTerminator(MeadeResponse &r); +void writeUnsignedPadded(MeadeResponse &r, unsigned value, int width); +void writeSignedPadded(MeadeResponse &r, int value, int digits); +void writeBool01(MeadeResponse &r, bool b); +void writeCString(MeadeResponse &r, const char *s); + +void writeRa(MeadeResponse &r, const RaCoordinate &ra); +void writeDec(MeadeResponse &r, const DecCoordinate &d); +void writeLatitude(MeadeResponse &r, const MeadeLatitude &l); +void writeLongitude(MeadeResponse &r, const MeadeLongitude &l); +void writeTime24h(MeadeResponse &r, const MeadeLocalTime &t); +void writeTime12h(MeadeResponse &r, const MeadeLocalTime &t); +void writeLocalDate(MeadeResponse &r, const MeadeLocalDate &d); +void writeUtcOffset(MeadeResponse &r, int hours); +void writeClockFormat(MeadeResponse &r, MeadeClockFormat f); +void writeTrackingRate(MeadeResponse &r, MeadeTrackingRate t); + +void writeInt(MeadeResponse &r, int value); +void writeSignedInt(MeadeResponse &r, int value); +void writeLong(MeadeResponse &r, long value); +void writeFloat(MeadeResponse &r, float value, int precision); + +// --------------------------------------------------------------------------- +// High-level make*Response — thin wrappers: create a response, delegate to +// write*, append `#` when needed, return. +// --------------------------------------------------------------------------- + +MeadeResponse makeLiteralResponse(const char *text); +MeadeResponse makeSetSuccessResponse(bool ok); +MeadeResponse makeFramedTextResponse(const char *text); +MeadeResponse makeLongResponse(long value); +MeadeResponse makeBooleanResponse(bool flag); +MeadeResponse makeNumericFloatResponse(float value, int precision); +MeadeResponse makeIntResponse(int value); +MeadeResponse makeLongPairPipeResponse(long a, long b); +MeadeResponse makeDecLimitsPairResponse(float lo, float hi); +MeadeResponse makeHemisphereResponse(bool north); +MeadeResponse makeCompactHmsResponse(int hours, int minutes, int seconds); +MeadeResponse makeAnglePair4Response(float a, float b); +MeadeResponse makeLevelUnknownResponse(const char *echoedCmd); + +// --------------------------------------------------------------------------- +// String helpers +// --------------------------------------------------------------------------- + +bool isExact(const char *input, const char *key); +bool startsWith(const char *input, const char *prefix); + +} // namespace meade +} // namespace core +} // namespace oat diff --git a/src/core/meade/MeadeParserHome.cpp b/src/core/meade/MeadeParserHome.cpp new file mode 100644 index 00000000..3c0c6416 --- /dev/null +++ b/src/core/meade/MeadeParserHome.cpp @@ -0,0 +1,47 @@ +/** + * @file MeadeParserHome.cpp + * @brief Home-family (`:h...`) dispatcher for the Meade LX200 parser. + */ + +#include "MeadeParser.hpp" +#include "MeadeParserHelpers.hpp" + +namespace oat +{ +namespace core +{ +namespace meade +{ + +MeadeResponse handleMeadeHome(const char *suffix, IMeadeHomeHandlers &h) +{ + MeadeResponse r; + if (suffix == nullptr || suffix[0] == '\0' || suffix[1] != '\0') + { + return r; + } + switch (suffix[0]) + { + case 'P': + h.onPark(); + break; + case 'F': + h.onSlewToHome(); + break; + case 'U': + h.onUnpark(); + writeChar(r, '1'); + break; + case 'Z': + h.onSetAzAltHome(); + writeChar(r, '1'); + break; + default: + break; + } + return r; +} + +} // namespace meade +} // namespace core +} // namespace oat diff --git a/src/core/meade/MeadeParserInit.cpp b/src/core/meade/MeadeParserInit.cpp new file mode 100644 index 00000000..1ddfceae --- /dev/null +++ b/src/core/meade/MeadeParserInit.cpp @@ -0,0 +1,23 @@ +/** + * @file MeadeParserInit.cpp + * @brief Init-family (`:I...`) dispatcher for the Meade LX200 parser. + */ + +#include "MeadeParser.hpp" + +namespace oat +{ +namespace core +{ +namespace meade +{ + +MeadeResponse handleMeadeInit(const char *, IMeadeInitHandlers &h) +{ + h.onEnterSerialControl(); + return MeadeResponse {}; +} + +} // namespace meade +} // namespace core +} // namespace oat diff --git a/src/core/meade/MeadeParserMovement.cpp b/src/core/meade/MeadeParserMovement.cpp new file mode 100644 index 00000000..07f88e19 --- /dev/null +++ b/src/core/meade/MeadeParserMovement.cpp @@ -0,0 +1,187 @@ +/** + * @file MeadeParserMovement.cpp + * @brief Movement-family (`:M...`) dispatcher for the Meade LX200 parser. + */ + +#include "MeadeParser.hpp" +#include "MeadeParserHelpers.hpp" + +#include +#include + +namespace oat +{ +namespace core +{ +namespace meade +{ + +MeadeResponse handleMeadeMovement(const char *suffix, IMeadeMovementHandlers &h) +{ + MeadeResponse r; + if (suffix == nullptr || suffix[0] == '\0') + { + return r; + } + + Cursor c(suffix); + + // `:MS#` — exact match only ("S123" is not a slew-to-target). + if (c.peek() == 'S' && c.match('S') && c.atEnd()) + { + h.onStartSlewToTarget(); + return makeSetSuccessResponse(false); + } + + // `:MAA...#` — any input starting with "AA" requests a home move. + if (c.peek() == 'A' && c.match('A')) + { + if (c.peek() == 'A') + { + c.match('A'); + h.onMoveAzAltHome(); + return makeSetSuccessResponse(true); + } + if (c.peek() == 'Z') + { + c.match('Z'); + const float arcMinutes = static_cast(strtod(c.remaining(), nullptr)); + h.onMoveAzimuth(arcMinutes); + return r; + } + if (c.peek() == 'L') + { + c.match('L'); + const float arcMinutes = static_cast(strtod(c.remaining(), nullptr)); + h.onMoveAltitude(arcMinutes); + return r; + } + return r; + } + + // `:MHR[distance]#` / `:MHD[distance]#` — Hall-sensor auto-home. + if (c.peek() == 'H' && c.match('H')) + { + if (c.peek() == 'R' && c.match('R')) + { + int direction = 0; + char d = c.peek(); + if (d == 'R') + direction = -1; + else if (d == 'L') + direction = 1; + if (direction != 0) + c.match(d); + if (direction == 0) + return makeSetSuccessResponse(false); + return makeSetSuccessResponse(h.onHomeRa(direction, c.remaining())); + } + if (c.peek() == 'D' && c.match('D')) + { + int direction = 0; + char d = c.peek(); + if (d == 'U') + direction = 1; + else if (d == 'D') + direction = -1; + if (direction != 0) + c.match(d); + if (direction == 0) + return makeSetSuccessResponse(false); + return makeSetSuccessResponse(h.onHomeDec(direction, c.remaining())); + } + return r; + } + + // `:MT1#` / `:MT0#` — tracking toggle. + if (c.peek() == 'T' && c.match('T')) + { + if (c.peek() == '1') + { + c.match('1'); + h.onTrackingOn(); + return makeSetSuccessResponse(true); + } + if (c.peek() == '0') + { + c.match('0'); + h.onTrackingOff(); + return makeSetSuccessResponse(true); + } + return makeSetSuccessResponse(false); + } + + // `:MG#` / `:Mg#` — guide pulse. + if ((c.peek() == 'G' || c.peek() == 'g') && c.match(c.peek())) + { + MoveDirection dir = MoveDirection::East; + const char dc = static_cast(tolower(static_cast(c.peek()))); + if (dc == 'n') + dir = MoveDirection::North; + else if (dc == 's') + dir = MoveDirection::South; + else if (dc == 'w') + dir = MoveDirection::West; + c.match(c.peek()); + unsigned d = 0; + if (c.digits(4, d) && c.atEnd()) + { + h.onGuidePulse(dir, static_cast(d)); + return makeLiteralResponse(""); + } + return makeLiteralResponse("0"); + } + + // `:MX#` — move a single stepper by raw step count. + if (c.peek() == 'X' && c.match('X')) + { + MovementAxis axis; + switch (c.peek()) + { + case 'r': + axis = MovementAxis::Ra; + break; + case 'd': + axis = MovementAxis::Dec; + break; + case 'z': + axis = MovementAxis::Azimuth; + break; + case 'l': + axis = MovementAxis::Altitude; + break; + case 'f': + axis = MovementAxis::Focus; + break; + default: + return makeSetSuccessResponse(false); + } + c.match(c.peek()); + const long steps = strtol(c.remaining(), nullptr, 10); + h.onMoveStepper(axis, steps); + return makeSetSuccessResponse(true); + } + + // Continuous slew shortcuts — single direction letter, anything after ignored. + switch (c.peek()) + { + case 'e': + h.onSlewEast(); + return r; + case 'w': + h.onSlewWest(); + return r; + case 'n': + h.onSlewNorth(); + return r; + case 's': + h.onSlewSouth(); + return r; + default: + return r; + } +} + +} // namespace meade +} // namespace core +} // namespace oat diff --git a/src/core/meade/MeadeParserQuit.cpp b/src/core/meade/MeadeParserQuit.cpp new file mode 100644 index 00000000..a2bbd17a --- /dev/null +++ b/src/core/meade/MeadeParserQuit.cpp @@ -0,0 +1,64 @@ +/** + * @file MeadeParserQuit.cpp + * @brief Quit-family (`:Q...`) dispatcher for the Meade LX200 parser. + */ + +#include "MeadeParser.hpp" + +namespace oat +{ +namespace core +{ +namespace meade +{ + +MeadeResponse handleMeadeQuit(const char *suffix, IMeadeQuitHandlers &h) +{ + MeadeResponse r; + if (suffix == nullptr) + { + return r; + } + + // Empty suffix == :Q# == StopAll. + if (suffix[0] == '\0') + { + h.onStopAll(); + return r; + } + + // All remaining variants are a single character. + if (suffix[1] != '\0') + { + return r; + } + + switch (suffix[0]) + { + case 'a': + h.onStopDirectionalAll(); + break; + case 'e': + h.onStopEast(); + break; + case 'w': + h.onStopWest(); + break; + case 'n': + h.onStopNorth(); + break; + case 's': + h.onStopSouth(); + break; + case 'q': + h.onQuitControlMode(); + break; + default: + break; + } + return r; +} + +} // namespace meade +} // namespace core +} // namespace oat diff --git a/src/core/meade/MeadeParserSet.cpp b/src/core/meade/MeadeParserSet.cpp new file mode 100644 index 00000000..beee1280 --- /dev/null +++ b/src/core/meade/MeadeParserSet.cpp @@ -0,0 +1,276 @@ +/** + * @file MeadeParserSet.cpp + * @brief Set-family (`:S...`) dispatcher for the Meade LX200 parser. + */ + +#include "MeadeParser.hpp" +#include "MeadeParserHelpers.hpp" + +#include +#include + +namespace oat +{ +namespace core +{ +namespace meade +{ + +namespace +{ + +// Format: "[+-]DDMM:SS" where sep in {'*', ':'}. +bool readDecCoordinate(Cursor &c, DecCoordinate &out) +{ + int deg; + unsigned mm, ss; + if (!c.signed2(deg) || !c.matchIn("*:") || !c.digits(2, mm) || !c.match(':') || !c.digits(2, ss)) + { + return false; + } + out.degrees = static_cast(deg); + out.minutes = static_cast(mm); + out.seconds = static_cast(ss); + return true; +} + +// Format: "HH:MM:SS". +bool readRaCoordinate(Cursor &c, RaCoordinate &out) +{ + unsigned hh, mm, ss; + if (!c.digits(2, hh) || !c.match(':') || !c.digits(2, mm) || !c.match(':') || !c.digits(2, ss)) + { + return false; + } + out.hours = static_cast(hh); + out.minutes = static_cast(mm); + out.seconds = static_cast(ss); + return true; +} + +// Format: "[+-]DDMM" where sep in {'*', ':'}. +bool readLatitude(Cursor &c, MeadeLatitude &out) +{ + int deg; + unsigned mm; + if (!c.signed2(deg) || !c.matchIn("*:") || !c.digits(2, mm)) + { + return false; + } + out.degrees = static_cast(deg); + out.minutes = static_cast(mm); + return true; +} + +// Format: "[+-]DDDMM" where sep in {'*', ':'}. +bool readLongitude(Cursor &c, MeadeLongitude &out) +{ + int deg; + unsigned mm; + if (!c.signed3(deg) || !c.matchIn("*:") || !c.digits(2, mm)) + { + return false; + } + out.degrees = static_cast(deg); + out.minutes = static_cast(mm); + return true; +} + +// Set ack: "1" on success, "0" on failure. No framing terminator. +void writeSetAck(MeadeResponse &r, bool ok) +{ + writeChar(r, ok ? '1' : '0'); +} + +// :SC# success ack: "1Updating Planetary Data#<30 spaces>#". "0" on failure. +void writeSetLocalDateAck(MeadeResponse &r, bool ok) +{ + if (!ok) + { + writeChar(r, '0'); + return; + } + writeText(r, "1Updating Planetary Data"); + writeTerminator(r); + for (int i = 0; i < 30; ++i) + { + writeChar(r, ' '); + } + writeTerminator(r); +} + +} // namespace + +MeadeResponse handleMeadeSet(const char *s, IMeadeSetHandlers &h) +{ + MeadeResponse r; + if (!s || s[0] == '\0') + { + writeChar(r, '0'); + return r; + } + + Cursor c(s + 1); + + switch (s[0]) + { + case 'd': + { + DecCoordinate dec; + if (!readDecCoordinate(c, dec)) + { + writeChar(r, '0'); + return r; + } + writeSetAck(r, h.onSetTargetDec(dec)); + return r; + } + + case 'r': + { + RaCoordinate ra; + if (!readRaCoordinate(c, ra)) + { + writeChar(r, '0'); + return r; + } + writeSetAck(r, h.onSetTargetRa(ra)); + return r; + } + + case 'H': + if (c.peek() == 'L') + { + // HLhhmmss (8 chars) or HLhhmm (6 chars) — no separators on the wire. + c.match('L'); + unsigned hh = 0, mm = 0, ss = 0; + bool ok = false; + if (c.digits(2, hh) && c.digits(2, mm)) + { + if (c.atEnd()) + { + ok = true; + } + else if (c.digits(2, ss) && c.atEnd()) + { + ok = true; + } + } + if (!ok) + { + writeChar(r, '0'); + return r; + } + MeadeLocalTime t {static_cast(hh), static_cast(mm), static_cast(ss)}; + writeSetAck(r, h.onSetLocalSiderealTime(t)); + return r; + } + if (c.peek() == 'P' && c.match('P') && c.atEnd()) + { + writeSetAck(r, h.onSetHomePoint()); + return r; + } + // Bare H = HourAngle: H. Separator at s[3] is not validated + // (legacy behaviour: any single char accepted). + { + unsigned hh, mm; + if (!c.digits(2, hh) || c.peek() == '\0' || !c.match(c.peek()) || !c.digits(2, mm) || !c.atEnd()) + { + writeChar(r, '0'); + return r; + } + writeSetAck(r, h.onSetHourAngle(static_cast(hh), static_cast(mm))); + return r; + } + + case 'Y': + { + // Y. + DecCoordinate dec; + RaCoordinate ra; + if (!readDecCoordinate(c, dec) || !c.match('.') || !readRaCoordinate(c, ra)) + { + writeChar(r, '0'); + return r; + } + writeSetAck(r, h.onSyncCoordinates(dec, ra)); + return r; + } + + case 't': + { + MeadeLatitude lat; + if (!readLatitude(c, lat)) + { + writeChar(r, '0'); + return r; + } + writeSetAck(r, h.onSetSiteLatitude(lat)); + return r; + } + + case 'g': + { + MeadeLongitude lon; + if (!readLongitude(c, lon)) + { + writeChar(r, '0'); + return r; + } + writeSetAck(r, h.onSetSiteLongitude(lon)); + return r; + } + + case 'G': + { + // G
+ int hours; + if (!c.signed2(hours)) + { + writeChar(r, '0'); + return r; + } + writeSetAck(r, h.onSetUtcOffset(hours)); + return r; + } + + case 'L': + { + // L:: + unsigned hh, mm, ss; + if (!c.digits(2, hh) || !c.match(':') || !c.digits(2, mm) || !c.match(':') || !c.digits(2, ss)) + { + writeChar(r, '0'); + return r; + } + MeadeLocalTime t {static_cast(hh), static_cast(mm), static_cast(ss)}; + writeSetAck(r, h.onSetLocalTime(t)); + return r; + } + + case 'C': + { + // C/
/ + unsigned mo, dd, yy; + if (!c.digits(2, mo) || !c.match('/') || !c.digits(2, dd) || !c.match('/') || !c.digits(2, yy)) + { + writeChar(r, '0'); + return r; + } + MeadeLocalDate d; + d.month = static_cast(mo); + d.day = static_cast(dd); + d.year = static_cast(2000 + yy); + writeSetLocalDateAck(r, h.onSetLocalDate(d)); + return r; + } + + default: + writeChar(r, '0'); + return r; + } +} + +} // namespace meade +} // namespace core +} // namespace oat diff --git a/src/core/meade/MeadeParserSlewRate.cpp b/src/core/meade/MeadeParserSlewRate.cpp new file mode 100644 index 00000000..22aa3328 --- /dev/null +++ b/src/core/meade/MeadeParserSlewRate.cpp @@ -0,0 +1,44 @@ +/** + * @file MeadeParserSlewRate.cpp + * @brief SetSlewRate-family (`:R...`) dispatcher for the Meade LX200 parser. + */ + +#include "MeadeParser.hpp" + +namespace oat +{ +namespace core +{ +namespace meade +{ + +MeadeResponse handleMeadeSetSlewRate(const char *suffix, IMeadeSlewRateHandlers &h) +{ + MeadeResponse r; + if (suffix == nullptr || suffix[0] == '\0' || suffix[1] != '\0') + { + return r; + } + switch (suffix[0]) + { + case 'S': + h.onSetSlewRate(4); + break; + case 'M': + h.onSetSlewRate(3); + break; + case 'C': + h.onSetSlewRate(2); + break; + case 'G': + h.onSetSlewRate(1); + break; + default: + break; + } + return r; +} + +} // namespace meade +} // namespace core +} // namespace oat diff --git a/src/core/meade/MeadeParserSyncControl.cpp b/src/core/meade/MeadeParserSyncControl.cpp new file mode 100644 index 00000000..45919a40 --- /dev/null +++ b/src/core/meade/MeadeParserSyncControl.cpp @@ -0,0 +1,33 @@ +/** + * @file MeadeParserSyncControl.cpp + * @brief SyncControl-family (`:C...`) dispatcher for the Meade LX200 parser. + */ + +#include "MeadeParser.hpp" +#include "MeadeParserHelpers.hpp" + +namespace oat +{ +namespace core +{ +namespace meade +{ + +MeadeResponse handleMeadeSyncControl(const char *suffix, IMeadeSyncControlHandlers &h) +{ + MeadeResponse r; + if (suffix != nullptr && suffix[0] == 'M' && suffix[1] == '\0') + { + h.onSyncToTarget(); + writeCString(r, "NONE"); + } + else + { + writeCString(r, "FAIL"); + } + return r; +} + +} // namespace meade +} // namespace core +} // namespace oat diff --git a/src/core/meade/MeadeProtocol.hpp b/src/core/meade/MeadeProtocol.hpp new file mode 100644 index 00000000..b110ca0b --- /dev/null +++ b/src/core/meade/MeadeProtocol.hpp @@ -0,0 +1,1200 @@ + +///////////////////////////////////////////////////////////////////////////////////////// +// +// Serial support +// +// The Serial protocol implemented here is the Meade LX200 Classic protocol with some extensions. +// The Meade protocol commands start with a colon and end with a hash. +// The first letter determines the family of functions (G for Get, S for Set, M for Movement, etc.) +// +// The set of Meade features implemented are: +// +//------------------------------------------------------------------ +// INITIALIZE FAMILY +// +// :I# +// Description: +// Initialize Scope +// Information: +// This puts the Arduino in Serial Control Mode and displays RA on line 1 and +// DEC on line 2 of the display. Serial Control Mode can be ended manually by +// pressing the SELECT key, or programmatically with the :Qq# command. +// Returns: +// nothing +// +//------------------------------------------------------------------ +// SYNC CONTROL FAMILY +// +// :CM# +// Description: +// Synchronize Declination and Right Ascension. +// Information: +// This tells the scope what it is currently pointing at. The scope synchronizes +// to the current target coordinates +// Remarks: +// Set with ":Sd#" and ":Sr#" +// Returns: +// "NONE#" +// +//------------------------------------------------------------------ +// DISTANCE FAMILY +// +// :D# +// Description: +// Query Mount Status +// Information: +// This queries the mount for its slewing status +// Returns: +// "|#" if slewing +// " #" if not +// +//------------------------------------------------------------------ +// GPS FAMILY +// +// :gT# +// Description: +// Set Mount Time +// Information: +// Attempts to set the mount time and location from the GPS for 2 minutes. This is essentially a +// blocking call, no other activities take place (except tracking, but only if interrupt-driven). +// Remarks: +// Use ":Gt#" and ":Gg#" to retrieve Lat and Long, +// Returns: +// "1" if the data was set +// "0" if not (timedout) +// +// :gTnnn# +// Description: +// Set Mount Time w/ timeout +// Information: +// Attempts to set the mount time and location from the GPS with a custom timeout. This is also blocking +// but by using a low timeout, you can avoid long pauses and let the user know that it's not ready yet. +// Returns: +// "1" if the data was set +// "0" if not (timedout) +// Parameters: +// "nnn" is an integer defining the number of milliseconds to wait for the GPS to get a bearing +// +//------------------------------------------------------------------ +// GET FAMILY +// +// :GVP# +// Description: +// Get the Product Name +// Returns: +// "OpenAstroTracker#" if the firmware was compiled for OAT +// "OpenAstroMount#" if the firmware was compiled for OAM +// +// :GVN# +// Description: +// Get the Firmware Version Number +// Returns: +// "V1.major.minor#" from version.h +// +// :Gd# +// Description: +// Get Target Declination +// Returns: +// "sDD*MM'SS#" +// Parameters: +// "s" is + or - +// "DD" is degrees +// "MM" is minutes +// "SS" is seconds +// +// :GD# +// Description: +// Get Current Declination +// Returns: +// "sDD*MM'SS#" +// Parameters: +// "s" is + or - +// "DD" is degrees +// "MM" is minutes +// "SS" is seconds. +// +// :Gr# +// Description: +// Get Target Right Ascension +// Returns: +// HH:MM:SS# +// Parameters: +// "HH" is hour +// "MM" is minutes +// "SS" is seconds +// +// :GR# +// Description: +// Get Current Right Ascension +// Returns: +// "HH:MM:SS#" +// Parameters: +// "HH" is hour +// "MM" is minutes +// "SS" is seconds +// +// :Gt# +// Description: +// Get Site Latitude +// Returns: +// "sDD*MM#" +// Parameters: +// "s" is + or - +// "DD" is the latitude in degrees +// "MM" the minutes +// +// :Gg# +// Description: +// Get Site Longitude +// Returns: +// "sDDD*MM#" +// Parameters: +// "s" is the sign of the longitude +// "DDD" is the degrees +// "MM" is the minutes +// Remarks: +// Note that this is the actual longitude, but east coordinates are negative (opposite of normal cartographic coordinates) +// +// :Gc# +// Description: +// Get current Clock format +// Returns: +// "24#" +// +// :GG# +// Description: +// Get offset to UTC time +// Returns: +// "sHH#" +// Parameters: +// "s" is the sign +// "HH" is the number of hours +// Remarks: +// Note that this is NOT simply the timezone offset you are in (like -8 for Pacific Standard Time), it is the negative of it. So how many hours need to be added to your local time to get to UTC. +// +// :Ga# +// Description: +// Get local time in 12h format +// Returns: +// "HH:MM:SS#" +// Parameters: +// "HH" are hours (modulo 12) +// "MM" are minutes +// "SS" are seconds of the local time +// +// :GL# +// Description: +// Get local time in 24h format +// Returns: +// "HH:MM:SS#" +// Parameters: +// "HH" are hours +// "MM" are minutes +// "SS" are seconds of the local time +// +// :GC# +// Description: +// Get current date +// Returns: +// "MM/DD/YY#" +// Parameters: +// "MM" is the month (1-12) +// "day" is the day (1-31) +// "year" is the lower two digits of the year +// +// :GM# +// Description: +// Get Site Name 1 +// Returns: +// "OAT1#" +// +// :GN# +// Description: +// Get Site Name 2 +// Returns: +// "OAT2#" +// +// :GO# +// Description: +// Get Site Name 3 +// Returns: +// OAT2# +// +// :GP# +// Description: +// Get Site Name 4 +// Returns: +// OAT4# +// +// :GT# +// Description: +// Get tracking rate +// Returns: +// 60.0# +// +//------------------------------------------------------------------ +// GET EXTENSIONS +// +// :GIS# +// Description: +// Get DEC or RA Slewing +// Returns: +// "1#" if either RA or DEC is slewing +// "0#" if not +// +// :GIT# +// Description: +// Get Tracking +// Returns: +// "1#" if tracking is on +// "0#" if not +// +// :GIG# +// Description: +// Get Guiding +// Returns: +// "1#" if currently guiding +// "0#" if not +// +// :GX# +// Description: +// Get Mount Status +// Information: +// String reflecting the mounts' status. The string is a comma-delimited list of statuses. +// Returns: +// "Idle,--T--,11219,0,927,071906,+900000,,#" +// Parameters: +// [0] The mount status. One of 'Idle', 'Parked', 'Parking', 'Guiding', 'SlewToTarget', 'FreeSlew', 'ManualSlew', 'Tracking', 'Homing' +// [1] The motion state (see Remarks below). +// [2] The RA stepper position +// [3] The DEC stepper position +// [4] The Tracking stepper position +// [5] The current RA coordinate +// [6] The current DEC coordinate +// [7] The FOC stepper position (if FOC enabled, else empty) +// Remarks: +// The motion state consists of 6 characters. If the character is a '-', the corresponding axis is not moving. +// First character is RA slewing state ('R' is East, 'r' is West, '-' is stopped). +// Second character is DEC slewing state ('d' is North, 'D' is South, '-' is stopped). +// Third character is TRK slewing state ('T' is Tracking, '-' is stopped). +// Fourth character is AZ slewing state ('Z' and 'z' is adjusting, '-' is stopped). +// Fifth character is ALT slewing state ('A' and 'a' is adjusting, '-' is stopped). +// Sixth character is FOC slewing state ('F' and 'f' is adjusting, '-' is stopped). +// AZ, ALT, and FOC are only set if the corresponding axis is enabled. If not, the character is always '-'. +// Since AZ/ALT rarely move, their positions are not returned here. To get the AZ and ALT stepper positions, use the ":XGAA#" command. +// +//------------------------------------------------------------------ +// SET FAMILY +// +// :SdsDD*MM:SS# +// Description: +// Set Target Declination +// Information: +// This sets the target DEC. Use a Movement command to slew there. +// Parameters: +// "s" is + or - +// "DD" is degrees +// "MM" is minutes +// "SS" is seconds +// Returns: +// "1" if successfully set +// "0" otherwise +// +// :SrHH:MM:SS# +// Description: +// Set Right Ascension +// Information: +// This sets the target RA. Use a Movement command to slew there. +// Returns: +// "1" if successfully set +// "0" otherwise +// Parameters: +// "HH" is hours +// "MM" is minutes +// "SS" is seconds +// +// :StsDD*MM# +// Description: +// Set Site Latitude +// Information: +// This sets the latitude of the location of the mount. +// Returns: +// "1" if successfully set +// "0" otherwise +// Parameters: +// "s" is the sign ('+' or '-') +// "DD" is the degree (90 or less) +// "MM" is minutes +// +// :SgsDDD*MM# +// Description: +// Set Site Longitude +// Information: +// This sets the longitude of the location of the mount. +// Returns: +// "1" if successfully set +// "0" otherwise +// Parameters: +// "s" (optional) is the sign of the longitude (see Remarks) +// "DDD" is the number of degrees +// "MM" is the minutes +// Remarks: +// When a sign is provided, longitudes are interpreted as given, with zero at Greenwich but negative coordinates going east (opposite of normal cartographic coordinates) +// When a sign is not provided, longitudes are from 0 to 360 going WEST with 180 at Greenwich. So 369 is 179W and 1 is 179E. 190 would be 10W and 170 would be 10E. +// +// :SGsHH# +// Description: +// Set Site UTC Offset +// Information: +// This sets the offset of the timezone in which the mount is in hours from UTC. +// Returns: +// "1" +// Parameters: +// "s" is the sign +// "HH" is the number of hours +// +// :SLHH:MM:SS# +// Description: +// Set Site Local Time +// Information: +// This sets the local time of the timezone in which the mount is located. +// Returns: +// "1" +// Parameters: +// "HH" is hours +// "MM" is minutes +// "SS" is seconds +// +// :SCMM/DD/YY# +// Description: +// Set Site Date +// Information: +// This sets the date +// Returns: +// "1Updating Planetary Data# #" +// Parameters: +// "MM" is the month +// "DD" is the day +// "YY" is the year since 2000 +// +//------------------------------------------------------------------ +// SET Extensions +// +// :SHHH:MM# +// Description: +// Set HA (Hour Angle of Polaris) +// Information: +// This sets the scopes HA, which should be that of Polaris. +// Returns: +// "1" if successfully set +// "0" otherwise +// Parameters: +// "HH" is hours +// "MM" is minutes +// +// :SHP# +// Description: +// Set Home Point +// Information: +// This sets the current orientation of the scope as its home point. +// Returns: +// "1" +// +// :SHLHH:MM# +// Description: +// Set LST Time +// Information: +// This sets the scopes LST (and HA). +// Returns: +// "1" if successfully set +// "0" otherwise +// Parameters: +// "HH" is hours +// "MM" is minutes +// +// :SYsDD*MM:SS.HH:MM:SS# +// Description: +// Synchronize Declination and Right Ascension. +// Information: +// This tells the scope what exact coordinates it is currently pointing at. These coordinates become the new current RA/DEC coordinates of the mount. +// Returns: +// "1" if successfully set +// "0" otherwise +// Parameters: +// "s" is + or - +// "DD" is degrees +// "HH" is hours +// "MM" is minutes +// "SS" is seconds +// +//------------------------------------------------------------------ +// RATE CONTROL FAMILY +// +// :Rs# +// Description: +// Set Slew rate +// Parameters: +// "s" is one of 'S', 'M', 'C', or 'G' in order of decreasing speed +// Returns: +// nothing +// +//------------------------------------------------------------------ +// MOVEMENT FAMILY +// +// :MS# +// Description: +// Start Slew to Target (Asynchronously) +// Information: +// This starts slewing the scope to the target RA and DEC coordinates and returns immediately. +// Returns: +// "0" +// +//------------------------------------------------------------------ +// MOVEMENT EXTENSIONS +// +// :MGdnnnn# +// Description: +// Run a Guide pulse +// Information: +// This runs the RA or DEC steppers at an increased or decreased speed (in the case of RA) or a constant speed (in the case of DEC) for a short period of time. It is used for guiding. +// Parameters: +// "d" is one of 'N', 'E', 'W', or 'S' +// "nnnn" is the duration in ms +// Returns: +// "1" +// +// :MTs# +// Description: +// Set Tracking mode +// Information: +// This turns the scopes tracking mode on or off. +// Parameters: +// "s" is "1" to turn on Tracking and "0" to turn it off +// Returns: +// "1" +// +// :Mc# +// Description: +// Start slewing +// Information: +// This starts slewing the mount in the given direction. You must issue a stop command (such as the corresponding ":Qc#", +// where 'c' is the same direction as passed to this command) or ":Q#" (stops all steppers) to stop it. +// Parameters: +// "c" is one of 'n', 'e', 'w', or 's' +// Returns: +// nothing +// +// :MXxnnnnn# +// Description: +// Move stepper +// Information: +// This starts moving one of the steppers by the given amount of steps and returns immediately. Steps can be positive or negative. +// Parameters: +// "x" is the stepper to move (r for RA, d for DEC, f for FOC, z for AZ, l for ALT) +// "nnnn" is the number of steps +// Returns: +// "1" if successfully scheduled, else "0" +// +// :MHRxn# +// Description: +// Home RA stepper via Hall sensor +// Information: +// This attempts to find the hall sensor and to home the RA ring accordingly. +// Parameters: +// "x" is either 'R' or 'L' and determines the direction in which the search starts (L is CW, R is CCW). +// "n" (Optional) is the maximum number of degrees to move while searching for the sensor location. Defaults to 30degs. Limited to the range 5degs - 75degs. +// Remarks: +// The ring is first moved 30 degrees (or the given amount) in the initial direction. If no hall sensor is encountered, +// it will move twice the amount (60 degrees by default) in the opposite direction. +// If a hall sensor is not encountered during that slew, the homing exits with a failure. +// If the sensor is found, it will slew to the middle position of the Hall sensor trigger range and then to the offset +// specified in the Home offset position (set with the ":XSHRnnnn#" command). +// If the RA ring is positioned such that the Hall sensor is already triggered when the command is received, the mount will move +// the RA ring off the trigger in the opposite direction specified for a max of 15 degrees before searching 30 degrees in the +// specified direction. +// Returns: +// "1" if search is started +// "0" if homing has not been enabled in the local configuration file +// +// :MHDxn# +// Description: +// Home DEC stepper via Hall sensor +// Information: +// This attempts to find the hall sensor and to home the DEC axis accordingly. +// Parameters: +// "x" is either 'U' or 'D' and determines the direction in which the search starts (U is up, D is down). +// "n" (Optional) is the maximum number of degrees to move while searching for the sensor location. Defaults to 30degs. Limited to the range 5degs - 75degs. +// Remarks: +// The ring is first moved 30 degrees (or the given amount) in the initial direction. If no hall sensor is encountered, +// it will move twice the amount (60 degrees by default) in the opposite direction. +// If a hall sensor is not encountered during that slew, the homing exits with a failure. +// If the sensor is found, it will slew to the middle position of the Hall sensor trigger range and then to the offset +// specified in the Home offset position (set with the ":XSHDnnnn#" command). +// If the DEC ring is positioned such that the Hall sensor is already triggered when the command is received, the mount will move +// the DEC ring off the trigger in the opposite direction specified for a max of 15 degrees before searching 30 degrees in the +// specified direction. +// Returns: +// "1" if search is started +// "0" if homing has not been enabled in the local configuration file +// +// :MAAH# +// Description: +// Move Azimuth and Altitude to home +// Information: +// If the scope supports automated azimuth and altitude operations, move AZ and ALT axis to their zero positions. +// Returns: +// "1" +// +// :MAZn.nn# +// Description: +// Move Azimuth +// Information: +// If the scope supports automated azimuth operation, move azimuth by n.nn arcminutes +// Parameters: +// "n.nn" is a signed floating point number representing the number of arcminutes to move the mount left or right +// Returns: +// nothing +// +// :MALn.nn# +// Description: +// Move Altitude +// Information: +// If the scope supports automated altitude operation, move altitude by n.nn arcminutes +// Parameters: +// "n.nn" is a signed floating point number representing the number of arcminutes to raise or lower the mount. +// Returns: +// nothing +// +//------------------------------------------------------------------ +// HOME FAMILY +// +// :hP# +// Description: +// Park Scope and stop motors +// Information: +// This slews the scope back to it's home position (RA ring centered, DEC at 90, basically +// pointing at celestial pole), then advances to the parking position (defined by the Homing offsets) +// and stops all movement (including tracking). +// Returns: +// nothing +// +// :hF# +// Description: +// Move Scope to Home position +// Information: +// This slews the scope back to its home position (RA ring centered, DEC +// at 90, basically pointing at celestial pole). Mount will keep tracking. +// Returns: +// nothing +// +//------------------------------------------------------------------ +// HOME/PARK Extensions +// +// :hU# +// Description: +// Unpark Scope +// Information: +// This currently simply turns on tracking. +// Returns: +// "1" +// +// :hZ# +// Description: +// Set home position for AZ and ALT axes +// Information: +// If the mount supports AZ and ALT axes, this call sets their positions to 0 and stores this in persistent storage. +// Returns: +// "1" +// +//------------------------------------------------------------------ +// QUIT MOVEMENT FAMILY +// +// :Q# +// Description: +// Stop all motors +// Information: +// This stops all motors, including tracking. Note that deceleration curves are still followed. +// Returns: +// nothing +// +// :Qd# +// Description: +// Stop Slewing +// Information: +// Stops slew in specified direction where d is n, s, e, w, a (the first four are the cardinal directions, a stands for All). +// Returns: +// nothing +// +//------------------------------------------------------------------ +// QUIT MOVEMENT Extensions +// +// :Qq# +// Description: +// Disconnect, Quit Control mode +// Information: +// This quits Serial Control mode and starts tracking. +// Returns: +// nothing +// +//------------------------------------------------------------------ +// EXTRA OAT FAMILY - These are used by the PC control application OATControl +// +// :XFR# +// Description: +// Perform a Factory Reset +// Information: +// Clears all the EEPROM settings +// Returns: +// "1#" +// +// :XDnnn# +// Description: +// Run drift alignment (only supported if SUPPORT_DRIFT_ALIGNMENT is enabled) +// Information: +// This runs a drift alignment procedure where the mounts slews east, pauses, slews west and pauses. +// Where nnn is the number of seconds the entire alignment should take. The call is blocking and will +// only return once the drift alignment is complete. +// Returns: +// nothing +// +// :XL0# +// Description: +// Turn off the Digital level +// Returns: +// "1#" if successful +// "0#" if there is no Digital Level +// +// :XL1# +// Description: +// Turn on the Digital level +// Returns: +// "1#" if successful +// "0#" if there is no Digital Level +// +// :XLGR# +// Description: +// Digital Level - Get Reference +// Information: +// Gets the reference pitch and roll values of the mount (Digital Level addon). These +// values are the values of the pitch and roll when the mount is level. +// Returns: +// ",#" +// "0#" if there is no Digital Level +// +// :XLGC# +// Description: +// Digital Level - Get Values +// Information: +// Gets the current pitch and roll values of the mount (Digital Level addon). +// Returns: +// ",#" +// "0#" if there is no Digital Level +// +// :XLGT# +// Description: +// Digital Level - Get Temperature +// Information: +// Get the current temperature in Celsius of the mount (Digital Level addon). +// Returns: +// "#" +// "0#" if there is no Digital Level +// +// :XLSR# +// Description: +// Digital Level - Set Reference Roll +// Information: +// Sets the reference roll value of the mount (Digital Level addon). This is the value +// at which the mount is level. +// Returns: +// "1#" if successful +// "0#" if there is no Digital Level +// +// :XLSP# +// Description: +// Digital Level - Set Reference Pitch +// Information: +// Sets the reference pitch value of the mount (Digital Level addon). This is the value +// at which the mount is level. +// Returns: +// "1#" if successful +// "0#" if there is no Digital Level +// +// :XGAA# +// Description: +// Get position of AZ and ALT axes +// Information: +// Get the current position in steps of the AZ and ALT axes if they are enabled. +// If an axis is not enabled, this always returns zero as the axis's value. +// Returns: +// "azpos|altpos#" if either axis is enabled +// +// :XGAH# +// Description: +// Get auto homing state +// Information: +// Get the current state of RA and DEC Autohoming status. Only valid when at least +// one Hall sensor based autohoming axis is enabled. +// Returns: +// "rastate|decstate#" if either axis is enabled +// "|#" if no autohoming is enabled +// Remarks: +// While the mount status (:GX#) is 'Homing', the command returns one of these: +// MOVE_OFF +// MOVING_OFF +// STOP_AT_TIME +// WAIT_FOR_STOP +// START_FIND_START +// FINDING_START +// FINDING_START_REVERSE +// FINDING_END +// RANGE_FOUND +// +// If the mount status (:GX#) is not 'Homing' the command returns one of these: +// SUCCEEDED +// NEVER RUN +// IN PROGRESS +// CANT MOVE OFF SENSOR +// CANT FIND SENSOR BEGIN +// CANT FIND SENSOR END +// +// :XGB# +// Description: +// Get Backlash correction steps +// Information: +// Get the number of steps the RA stepper motor needs to overshoot and backtrack when slewing east. +// Returns: +// "integer#" +// +// :XGCn.nn*m.mm# +// Description: +// Get stepper motor positions for target +// Information: +// Get the positions of stepper motors when pointed at the given coordinates. +// Parameters: +// "n.nn" is the RA coordinate (0.0 - 23.999) +// "m.mm" is the DEC coordinate (-90.00 - +90.00) +// "ralong" is the stepper position of the RA stepper +// "declong" is the stepper position of the DEC stepper +// Returns: +// "ralong,declong#" +// +// :XGR# +// Description: +// Get RA steps +// Information: +// Get the number of steps the RA stepper motor needs to take to rotate RA by one degree +// Returns: +// "float#" +// +// :XGD# +// Description: +// Get DEC steps +// Information: +// Get the number of steps the DEC stepper motor needs to take to rotate DEC by one degree +// Returns: +// "float#" +// +// :XGZ# +// Description: +// Get AZ steps +// Information: +// Get the number of steps the AZ stepper motor needs to take to rotate AZ by one degree +// Returns: +// "float#" if AZ motor is present +// "0#" if AZ is not configured +// +// :XGA# +// Description: +// Get ALT steps +// Information: +// Get the number of steps the ALT stepper motor needs to take to rotate ALT by one degree +// Returns: +// "float#" if ALT motor is present +// "0#" if ALT is not configured +// +// :XGDLx# +// Description: +// Get DEC limits +// Information: +// Get either lower, upper or both limits for the DEC stepper motor in degrees. +// Parameters: +// 'x' is optional or can be 'U' or 'L'. If it is 'U' only the upper bound is returned, +// if it is 'L' only the lower bound is returned and if it is missing, both are returned. +// Returns: +// "float#" or "float|float#" +// +// :XGDP# (obsolete, disabled) +// Description: +// Get DEC parking position +// Information: +// Gets the number of steps from the home position to the parking position for DEC +// Returns: +// "0#" +// +// :XGS# +// Description: +// Get Tracking speed adjustment +// Information: +// Get the adjustment factor used to speed up (>1.0) or slow down (<1.0) the tracking speed of the mount. +// Returns: +// "float#" +// +// :XGST# +// Description: +// Get Remaining Safe Time +// Information: +// Get the number of hours before the RA ring reaches its end. +// Returns: +// "float#" +// +// :XGT# +// Description: +// Get Tracking speed +// Information: +// Get the absolute tracking speed of the mount. +// Returns: +// "float#" +// +// :XGH# +// Description: +// Get HA (Hour Angle of Polaris) +// Information: +// Get the current HA of Polaris that the mount thinks it is. +// Returns: +// "HHMMSS#" +// +// :XGHR# +// Description: +// Get RA Homing offset +// Information: +// Get the RA ring homing offset. +// If a Hall sensor is present this is the number of steps from the center of the sensor range to +// where the actual center position is located. +// If no Hall sensor is present this is the number of steps from the power on position of the RA axis to +// where the actual center position is located. +// Returns: +// "n#" - the number of steps +// +// :XGHD# +// Description: +// Get DEC Homing offset +// Information: +// Get the DEC ring homing offset. +// If a Hall sensor is present this is the number of steps from the center of the sensor range to +// where the actual center position is located. +// If no Hall sensor is present this is the number of steps from the power on position of the DEC axis to +// where the actual center position is located. +// Returns: +// "n#" - the number of steps +// +// :XGHS# +// Description: +// Get Hemisphere +// Information: +// Get the hemisphere that the OAT currently assumes it is operating in. This is set via setting Latitude (see ":St" command) +// Returns: +// "N#" - for northern hemisphere +// "S#" - for southern hemisphere +// +// :XGM# +// Description: +// Get Mount configuration settings +// Returns: +// ",,,,,,,(more features...)#" +// Parameters: +// "" is one of the supported boards (currently Mega, ESP32, MKS) +// "" is a pipe-delimited string of Motor type (NEMA or 28BYJ), Pulley Teeth, Steps per revolution) +// "" is either NO_GPS or GPS, depending on whether a GPS module is present +// "" is either NO_AZ_ALT, AUTO_AZ_ALT, AUTO_AZ, or AUTO_ALT, depending on which AutoPA stepper motors are present +// "" is either NO_GYRO or GYRO depending on whether the Digital level is present +// "" is either NO_LCD or LCD_display_type depending on whether LCD is present and if so, which one +// "" is either NO_FOC or FOC depending on whether the focuser motor is enabled +// "" is either NO_HSAH or HSAH depending on whether the Hall sensor based auto homing for RA is enabled +// "" is either NO_ENDSW or ENDS_RA, ENDSW_DEC, or ENDSW_RA_DEC depending on which axis have end switches installed +// Remarks: +// As OAT/OAM firmware supports more features, these may be appended, separated by a comma. Any further features will +// have a 'NO_xxxxx' if the feature is not supported. +// To differentiate between OAT and OAM, use the Get Product Name (#GVP) command. +// Example: +// "ESP32,28BYJ|16|4096.00,28BYJ|16|4096.00,NO_GPS,NO_AZ_ALT,NO_GYRO,NO_LCD,NO_FOC,NO_ENDSW#" +// +// :XGMS# +// Description: +// Get Mount driver configuration +// Returns: +// ",,|,,|#" +// Parameters: +// "" is one of the supported drivers: TU=TMC2209UART, TS=TMC2209STANDALONE, A=A4983 +// "" is the microstepping divider (1, 2, 4, 8, 15, 21, 64, 128, 256) used when slewing +// "" is the microstepping divider (1, 2, 4, 8, 15, 21, 64, 128, 256) used when tracking RA +// "" is the microstepping divider (1, 2, 4, 8, 15, 21, 64, 128, 256) used when guiding DEC +// Example: +// "TU,8,64|TU,16,64|#" +// +// :XGN# +// Description: +// Get network settings +// Information: +// Gets the current status of the Wifi connection. Reply only available when running on ESP boards. +// Returns: +// "1,,,,:,,#" if Wifi is enabled +// "0,#" if Wifi is not enabled +// +// :XGL# +// Description: +// Get LST +// Information: +// Get the current LST of the mount. +// Returns: +// "HHMMSS#" +// +// :XSBn# +// Description: +// Set Backlash correction steps +// Information: +// Sets the number of steps the RA stepper motor needs to overshoot and backtrack when slewing east. +// Returns: +// nothing +// +// :XSHRnnn# +// Description: +// Set homing offset for RA ring from Hall sensor center +// Information: +// This offset is added to the position of the RA ring when it is centered on the hall sensor triggered range after running. +// the RA homing command (:MHRx#) +// Parameters: +// "n" is the (positive or negative) number of steps that are needed from the center of the Hall sensor trigger range to the actual home position. +// Returns: +// nothing +// +// :XSHDnnn# +// Description: +// Set homing offset for DEC ring from Hall sensor center +// Information: +// This offset is added to the position of the DEC ring when it is centered on the hall sensor triggered range after running. +// the DEC homing command (:MHDx#) +// Parameters: +// "n" is the (positive or negative) number of steps that are needed from the center of the Hall sensor trigger range to the actual home position. +// Returns: +// nothing +// +// :XSRn.n# +// Description: +// Set RA steps +// Information: +// Set the number of steps the RA stepper motor needs to take to rotate by one degree. +// Parameters: +// "n.n" is the number of steps (only one decimal point is supported, must be positive) +// Returns: +// nothing +// +// :XSDn.n# +// Description: +// Set DEC steps +// Information: +// Set the number of steps the DEC stepper motor needs to take to rotate by one degree. +// Parameters: +// "n.n" is the number of steps (only one decimal point is supported, must be positive) +// Returns: +// nothing +// +// :XSAn.n# +// Description: +// Set AZ steps +// Information: +// Set the number of steps the AZ stepper motor needs to take to rotate by one degree. +// Parameters: +// "n.n" is the number of steps (only one decimal point is supported, must be positive) +// Returns: +// nothing +// +// :XSLn.n# +// Description: +// Set ALT steps +// Information: +// Set the number of steps the ALT stepper motor needs to take to rotate by one degree. +// Parameters: +// "n.n" is the number of steps (only one decimal point is supported, must be positive) +// Returns: +// nothing +// +// :XSDLUnnnnn# +// Description: +// Set DEC upper limit +// Information: +// Set the upper limit for the DEC axis to the current position if no parameter is given, +// otherwise to the given angle (in degrees from the home position). +// Parameters: +// "nnnnn" is the number of steps from home that the DEC ring can travel upwards. Passing 0 will reset it to the +// limits defined in your configuration file. Omitting this parameter sets it to the current DEC position. +// Returns: +// nothing +// +// :XSDLu# +// Description: +// Clear DEC upper limit +// Information: +// Resets the upper limit for the DEC axis to the configuration-defined position. +// If not configured, the limit is cleared. +// Returns: +// nothing +// +// :XSDLLnnnnn# +// Description: +// Set DEC lower limit +// Information: +// Set the lower limit for the DEC axis to the current position if no parameter is given, +// otherwise to the given angle (in degrees from the home position). +// Parameters: +// "nnnnn" is the number of steps from home that the DEC ring can travel downwards. Passing 0 will reset it to the +// limits defined in your configuration file. Omitting this parameter sets it to the current DEC position. +// Returns: +// nothing +// +// :XSDLl# +// Description: +// Clear DEC lower limit +// Information: +// Resets the lower limit for the DEC axis to the configuration-defined position. +// If not configured, the limit is cleared. +// Returns: +// nothing +// +// :XSDPnnnn# (obsolete, disabled) +// Description: +// Set DEC parking position offset +// Information: +// This stores the number of steps needed to move from home to the parking position. +// Returns: +// nothing +// +// :XSSn.nnn# +// Description: +// Set Tracking speed adjustment +// Information: +// Set the adjustment factor used to speed up "(>1.0)" or slow down "(<1.0)" the tracking speed of the mount +// Parameters: +// "n.nnn" is the factor to multiply the theoretical speed by +// Returns: +// nothing +// +// :XSTnnnn# +// Description: +// Set Tracking motor position (no movement) +// Information: +// This is purely a debugging aid. It is not recommended to call this unless you know what you are doing. It simply sets the internal tracking steps to the given value. +// Parameters: +// "nnn" is the stepper steps to set +// Returns: +// nothing +// +// :XSMn# +// Description: +// Set Manual Slewing Mode +// Information: +// Toggle the manual slewing mode state where the RA and DEC motors run at a constant speed +// Parameters: +// "n" is '1' to turn it on, otherwise turn it off +// Returns: +// nothing +// +// :XSXn.nnn# +// Description: +// Set RA Speed +// Information: +// Set RA manual slewing speed in degrees/sec immediately. Max is around 2.5 degs/s +// Returns: +// nothing +// Remarks: +// Must be in manual slewing mode. +// +// :XSYn.nnn# +// Description: +// Set DEC Speed +// Information: +// Set DEC manual slewing speed in degrees/sec immediately. Max is around 2.5 degs/s +// Returns: +// nothing +// Remarks: +// Must be in manual slewing mode. +// +//------------------------------------------------------------------ +// FOCUS FAMILY +// +// :F+# +// Description: +// Start Focuser moving inward (toward objective) +// Information: +// Continues pull in until stopped +// Returns: +// nothing +// +// :F-# +// Description: +// Pull out +// Information: +// Continues pull out until stopped +// Returns: +// nothing +// +// :Fn# +// Description: +// Set speed factor +// Information: +// Set focuser speed to where is an ASCII digit 1..4. 1 is slowest, 4 is fastest +// Returns: +// nothing +// +// :FS# +// Description: +// Set slowest speed factor +// Information: +// Set focuser to the slowest speed it can use +// Returns: +// nothing +// +// :FF# +// Description: +// Set fastest speed factor +// Information: +// Set focuser speed to the fastest speed it can use +// Returns: +// nothing +// +// :Fp# +// Description: +// Get position +// Information: +// Get the current position of the focus stepper motor +// Returns: +// "nnn#" "nnn" is the current position of the stepper +// +// :FPnnn# +// Description: +// Set position +// Information: +// Sets the current position of the focus stepper motor +// Returns: +// "1" +// Parameters: +// "nnn" is the new position of the stepper. The stepper is not moved. +// +// :FB# +// Description: +// Get focuser state +// Information: +// Gets the state of the focuser stepper. +// Returns: +// "0" if the focuser is idle +// "1" if the focuser is moving +// +// :FQ# +// Description: +// Stop focuser +// Information: +// Stops the stepper motor of the focuser. +// Returns: +// nothing +// +//------------------------------------------------------------------ +///////////////////////////////////////////////////////////////////////////////////////// diff --git a/src/hal/README.md b/src/hal/README.md new file mode 100644 index 00000000..caa5be4a --- /dev/null +++ b/src/hal/README.md @@ -0,0 +1,37 @@ +# hal/ + +Hardware Abstraction Layer. Pure C++ interfaces describing *what the hardware can do* +(pin toggles, UART bytes, timer ticks, EEPROM cells, OLED panels, …) plus one backend +per platform. + +Planned subdirectories: +- `arduino/` — generic Arduino implementation. +- `avr/` — AVR-specific bits (Timer1/Timer3 ISR, fast pin IO). +- `esp32/` — ESP32-specific (hardware timers, Wi-Fi glue). + +Feature `#ifdef`s are allowed only here, for platform/backend selection. + +Note: the snippets below are illustrative only. They demonstrate layer responsibilities and dependency direction, not the final refactored code shape; actual code can and will differ. + +Minimal go-to example: + +```cpp +namespace hal { + +class IStepperMotor { +public: + virtual ~IStepperMotor() = default; + virtual void setTargetSteps(long targetSteps) = 0; + virtual long currentSteps() const = 0; + virtual void startMotion() = 0; + virtual bool isRunning() const = 0; + virtual void stopMotion() = 0; +}; + +} // namespace hal +``` + +Responsibility: expose raw motor-driving capability such as target position and motion start/stop. +Dependency rule: HAL knows about hardware capabilities and platform backends, not about go-to policy, RA/DEC semantics, or domain state machines. + +See [specs/plan.md](../../specs/plan.md) for the target architecture. diff --git a/src/ports/README.md b/src/ports/README.md new file mode 100644 index 00000000..445515ed --- /dev/null +++ b/src/ports/README.md @@ -0,0 +1,35 @@ +# ports/ + +Domain-level interfaces consumed by [`../core/`](../core/): what the domain *needs* +(axis position, persistent value, "now", a log sink, a transport, …). + +Pure C++ interfaces only. No Arduino, no hardware libraries, no `#ifdef` feature flags. +Adapters in [`../adapters/`](../adapters/) implement these ports on top of [`../hal/`](../hal/). + +Note: the snippets below are illustrative only. They demonstrate layer responsibilities and dependency direction, not the final refactored code shape; actual code can and will differ. + +Minimal go-to example: + +```cpp +class RA { +public: + explicit RA(int32_t milliArcSeconds) : _milliArcSeconds(milliArcSeconds) {} + int32_t milliArcSeconds() const { return _milliArcSeconds; } + +private: + int32_t _milliArcSeconds; +}; + +class IRaAxis { +public: + virtual ~IRaAxis() = default; + virtual void moveTo(const RA &target) = 0; + virtual bool isBusy() const = 0; + virtual void stop() = 0; +}; +``` + +Responsibility: define the axis contract the domain needs for a go-to in domain terms such as RA, not steps. +Dependency rule: ports are consumed by [`../core/`](../core/) and implemented by [`../adapters/`](../adapters/); they do not depend on HAL details. + +See [specs/plan.md](../../specs/plan.md) for the target architecture. diff --git a/unit_tests/test_common/fakes/.clang-format-ignore b/unit_tests/test_common/fakes/.clang-format-ignore deleted file mode 100644 index 2e276af8..00000000 --- a/unit_tests/test_common/fakes/.clang-format-ignore +++ /dev/null @@ -1 +0,0 @@ -fff.h diff --git a/unit_tests/test_common/fakes/fff.h b/unit_tests/test_common/fakes/fff.h deleted file mode 100644 index cdb1c46d..00000000 --- a/unit_tests/test_common/fakes/fff.h +++ /dev/null @@ -1,6588 +0,0 @@ -/* -LICENSE - -The MIT License (MIT) - -Copyright (c) 2010 Michael Long - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. -*/ -#ifndef FAKE_FUNCTIONS -#define FAKE_FUNCTIONS - -#include -#include /* For memset and memcpy */ - -#define FFF_MAX_ARGS (20u) -#ifndef FFF_ARG_HISTORY_LEN - #define FFF_ARG_HISTORY_LEN (50u) -#endif -#ifndef FFF_CALL_HISTORY_LEN - #define FFF_CALL_HISTORY_LEN (50u) -#endif -#ifndef FFF_GCC_FUNCTION_ATTRIBUTES - #define FFF_GCC_FUNCTION_ATTRIBUTES -#endif -#ifndef CUSTOM_FFF_FUNCTION_TEMPLATE -#define CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN, FUNCNAME, ...) \ - RETURN(*FUNCNAME)(__VA_ARGS__) -#endif /* CUSTOM_FFF_FUNCTION_TEMPLATE */ -/* -- INTERNAL HELPER MACROS -- */ -#define SET_RETURN_SEQ(FUNCNAME, ARRAY_POINTER, ARRAY_LEN) \ - FUNCNAME##_fake.return_val_seq = ARRAY_POINTER; \ - FUNCNAME##_fake.return_val_seq_len = ARRAY_LEN; -#define SET_CUSTOM_FAKE_SEQ(FUNCNAME, ARRAY_POINTER, ARRAY_LEN) \ - FUNCNAME##_fake.custom_fake_seq = ARRAY_POINTER; \ - FUNCNAME##_fake.custom_fake_seq_len = ARRAY_LEN; - -/* Defining a function to reset a fake function */ -#define RESET_FAKE(FUNCNAME) { \ - FUNCNAME##_reset(); \ -} \ - - -#define DECLARE_ARG(type, n, FUNCNAME) \ - type arg##n##_val; \ - type arg##n##_history[FFF_ARG_HISTORY_LEN]; - -#define DECLARE_ALL_FUNC_COMMON \ - unsigned int call_count; \ - unsigned int arg_history_len; \ - unsigned int arg_histories_dropped; \ - -#define DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - RETURN_TYPE return_val_history[FFF_ARG_HISTORY_LEN]; - -#define SAVE_ARG(FUNCNAME, n) \ - memcpy((void*)&FUNCNAME##_fake.arg##n##_val, (void*)&arg##n, sizeof(arg##n)); - -#define ROOM_FOR_MORE_HISTORY(FUNCNAME) \ - FUNCNAME##_fake.call_count < FFF_ARG_HISTORY_LEN - -#define SAVE_RET_HISTORY(FUNCNAME, RETVAL) \ - if ((FUNCNAME##_fake.call_count - 1) < FFF_ARG_HISTORY_LEN) \ - memcpy((void *)&FUNCNAME##_fake.return_val_history[FUNCNAME##_fake.call_count - 1], (const void *) &RETVAL, sizeof(RETVAL)); \ - -#define SAVE_ARG_HISTORY(FUNCNAME, ARGN) \ - memcpy((void*)&FUNCNAME##_fake.arg##ARGN##_history[FUNCNAME##_fake.call_count], (void*)&arg##ARGN, sizeof(arg##ARGN)); - -#define HISTORY_DROPPED(FUNCNAME) \ - FUNCNAME##_fake.arg_histories_dropped++ - -#define DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - RETURN_TYPE return_val; \ - int return_val_seq_len; \ - int return_val_seq_idx; \ - RETURN_TYPE * return_val_seq; \ - -#define DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - int custom_fake_seq_len; \ - int custom_fake_seq_idx; \ - -#define INCREMENT_CALL_COUNT(FUNCNAME) \ - FUNCNAME##_fake.call_count++ - -#define RETURN_FAKE_RESULT(FUNCNAME) \ - if (FUNCNAME##_fake.return_val_seq_len){ /* then its a sequence */ \ - if(FUNCNAME##_fake.return_val_seq_idx < FUNCNAME##_fake.return_val_seq_len) { \ - SAVE_RET_HISTORY(FUNCNAME, FUNCNAME##_fake.return_val_seq[FUNCNAME##_fake.return_val_seq_idx]) \ - return FUNCNAME##_fake.return_val_seq[FUNCNAME##_fake.return_val_seq_idx++]; \ - } \ - SAVE_RET_HISTORY(FUNCNAME, FUNCNAME##_fake.return_val_seq[FUNCNAME##_fake.return_val_seq_len-1]) \ - return FUNCNAME##_fake.return_val_seq[FUNCNAME##_fake.return_val_seq_len-1]; /* return last element */ \ - } \ - SAVE_RET_HISTORY(FUNCNAME, FUNCNAME##_fake.return_val) \ - return FUNCNAME##_fake.return_val; \ - -#ifdef __cplusplus - #define FFF_EXTERN_C extern "C"{ - #define FFF_END_EXTERN_C } -#else /* ansi c */ - #define FFF_EXTERN_C - #define FFF_END_EXTERN_C -#endif /* cpp/ansi c */ - -#define DEFINE_RESET_FUNCTION(FUNCNAME) \ - void FUNCNAME##_reset(void){ \ - memset((void*)&FUNCNAME##_fake, 0, sizeof(FUNCNAME##_fake) - sizeof(FUNCNAME##_fake.custom_fake) - sizeof(FUNCNAME##_fake.custom_fake_seq)); \ - FUNCNAME##_fake.custom_fake = NULL; \ - FUNCNAME##_fake.custom_fake_seq = NULL; \ - FUNCNAME##_fake.arg_history_len = FFF_ARG_HISTORY_LEN; \ - } -/* -- END INTERNAL HELPER MACROS -- */ - -typedef void (*fff_function_t)(void); -typedef struct { - fff_function_t call_history[FFF_CALL_HISTORY_LEN]; - unsigned int call_history_idx; -} fff_globals_t; - -FFF_EXTERN_C -extern fff_globals_t fff; -FFF_END_EXTERN_C - -#define DEFINE_FFF_GLOBALS \ - FFF_EXTERN_C \ - fff_globals_t fff; \ - FFF_END_EXTERN_C - -#define FFF_RESET_HISTORY() \ - fff.call_history_idx = 0; \ - memset(fff.call_history, 0, sizeof(fff.call_history)); - -#define REGISTER_CALL(function) \ - if(fff.call_history_idx < FFF_CALL_HISTORY_LEN) \ - fff.call_history[fff.call_history_idx++] = (fff_function_t)function; - -#define DECLARE_FAKE_VOID_FUNC0(FUNCNAME) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, void); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, void); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(void); \ - -#define DEFINE_FAKE_VOID_FUNC0(FUNCNAME) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(void){ \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC0(FUNCNAME) \ - DECLARE_FAKE_VOID_FUNC0(FUNCNAME) \ - DEFINE_FAKE_VOID_FUNC0(FUNCNAME) \ - - -#define DECLARE_FAKE_VOID_FUNC1(FUNCNAME, ARG0_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0); \ - -#define DEFINE_FAKE_VOID_FUNC1(FUNCNAME, ARG0_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0){ \ - SAVE_ARG(FUNCNAME, 0); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC1(FUNCNAME, ARG0_TYPE) \ - DECLARE_FAKE_VOID_FUNC1(FUNCNAME, ARG0_TYPE) \ - DEFINE_FAKE_VOID_FUNC1(FUNCNAME, ARG0_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC2(FUNCNAME, ARG0_TYPE, ARG1_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1); \ - -#define DEFINE_FAKE_VOID_FUNC2(FUNCNAME, ARG0_TYPE, ARG1_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC2(FUNCNAME, ARG0_TYPE, ARG1_TYPE) \ - DECLARE_FAKE_VOID_FUNC2(FUNCNAME, ARG0_TYPE, ARG1_TYPE) \ - DEFINE_FAKE_VOID_FUNC2(FUNCNAME, ARG0_TYPE, ARG1_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC3(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2); \ - -#define DEFINE_FAKE_VOID_FUNC3(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC3(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE) \ - DECLARE_FAKE_VOID_FUNC3(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE) \ - DEFINE_FAKE_VOID_FUNC3(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC4(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3); \ - -#define DEFINE_FAKE_VOID_FUNC4(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC4(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE) \ - DECLARE_FAKE_VOID_FUNC4(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE) \ - DEFINE_FAKE_VOID_FUNC4(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC5(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4); \ - -#define DEFINE_FAKE_VOID_FUNC5(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC5(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE) \ - DECLARE_FAKE_VOID_FUNC5(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE) \ - DEFINE_FAKE_VOID_FUNC5(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC6(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5); \ - -#define DEFINE_FAKE_VOID_FUNC6(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC6(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE) \ - DECLARE_FAKE_VOID_FUNC6(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE) \ - DEFINE_FAKE_VOID_FUNC6(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC7(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6); \ - -#define DEFINE_FAKE_VOID_FUNC7(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC7(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE) \ - DECLARE_FAKE_VOID_FUNC7(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE) \ - DEFINE_FAKE_VOID_FUNC7(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC8(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7); \ - -#define DEFINE_FAKE_VOID_FUNC8(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC8(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE) \ - DECLARE_FAKE_VOID_FUNC8(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE) \ - DEFINE_FAKE_VOID_FUNC8(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC9(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8); \ - -#define DEFINE_FAKE_VOID_FUNC9(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC9(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE) \ - DECLARE_FAKE_VOID_FUNC9(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE) \ - DEFINE_FAKE_VOID_FUNC9(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC10(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9); \ - -#define DEFINE_FAKE_VOID_FUNC10(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC10(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE) \ - DECLARE_FAKE_VOID_FUNC10(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE) \ - DEFINE_FAKE_VOID_FUNC10(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC11(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10); \ - -#define DEFINE_FAKE_VOID_FUNC11(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC11(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE) \ - DECLARE_FAKE_VOID_FUNC11(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE) \ - DEFINE_FAKE_VOID_FUNC11(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC12(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11); \ - -#define DEFINE_FAKE_VOID_FUNC12(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC12(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE) \ - DECLARE_FAKE_VOID_FUNC12(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE) \ - DEFINE_FAKE_VOID_FUNC12(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC13(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12); \ - -#define DEFINE_FAKE_VOID_FUNC13(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC13(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE) \ - DECLARE_FAKE_VOID_FUNC13(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE) \ - DEFINE_FAKE_VOID_FUNC13(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC14(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13); \ - -#define DEFINE_FAKE_VOID_FUNC14(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC14(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE) \ - DECLARE_FAKE_VOID_FUNC14(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE) \ - DEFINE_FAKE_VOID_FUNC14(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC15(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14); \ - -#define DEFINE_FAKE_VOID_FUNC15(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC15(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE) \ - DECLARE_FAKE_VOID_FUNC15(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE) \ - DEFINE_FAKE_VOID_FUNC15(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC16(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15); \ - -#define DEFINE_FAKE_VOID_FUNC16(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC16(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE) \ - DECLARE_FAKE_VOID_FUNC16(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE) \ - DEFINE_FAKE_VOID_FUNC16(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC17(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ARG(ARG16_TYPE, 16, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16); \ - -#define DEFINE_FAKE_VOID_FUNC17(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - SAVE_ARG(FUNCNAME, 16); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - SAVE_ARG_HISTORY(FUNCNAME, 16); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC17(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE) \ - DECLARE_FAKE_VOID_FUNC17(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE) \ - DEFINE_FAKE_VOID_FUNC17(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC18(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ARG(ARG16_TYPE, 16, FUNCNAME) \ - DECLARE_ARG(ARG17_TYPE, 17, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17); \ - -#define DEFINE_FAKE_VOID_FUNC18(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - SAVE_ARG(FUNCNAME, 16); \ - SAVE_ARG(FUNCNAME, 17); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - SAVE_ARG_HISTORY(FUNCNAME, 16); \ - SAVE_ARG_HISTORY(FUNCNAME, 17); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC18(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE) \ - DECLARE_FAKE_VOID_FUNC18(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE) \ - DEFINE_FAKE_VOID_FUNC18(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC19(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ARG(ARG16_TYPE, 16, FUNCNAME) \ - DECLARE_ARG(ARG17_TYPE, 17, FUNCNAME) \ - DECLARE_ARG(ARG18_TYPE, 18, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ARG18_TYPE arg18); \ - -#define DEFINE_FAKE_VOID_FUNC19(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ARG18_TYPE arg18){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - SAVE_ARG(FUNCNAME, 16); \ - SAVE_ARG(FUNCNAME, 17); \ - SAVE_ARG(FUNCNAME, 18); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - SAVE_ARG_HISTORY(FUNCNAME, 16); \ - SAVE_ARG_HISTORY(FUNCNAME, 17); \ - SAVE_ARG_HISTORY(FUNCNAME, 18); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC19(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE) \ - DECLARE_FAKE_VOID_FUNC19(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE) \ - DEFINE_FAKE_VOID_FUNC19(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC20(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ARG19_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ARG(ARG16_TYPE, 16, FUNCNAME) \ - DECLARE_ARG(ARG17_TYPE, 17, FUNCNAME) \ - DECLARE_ARG(ARG18_TYPE, 18, FUNCNAME) \ - DECLARE_ARG(ARG19_TYPE, 19, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ARG19_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ARG19_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ARG18_TYPE arg18, ARG19_TYPE arg19); \ - -#define DEFINE_FAKE_VOID_FUNC20(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ARG19_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ARG18_TYPE arg18, ARG19_TYPE arg19){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - SAVE_ARG(FUNCNAME, 16); \ - SAVE_ARG(FUNCNAME, 17); \ - SAVE_ARG(FUNCNAME, 18); \ - SAVE_ARG(FUNCNAME, 19); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - SAVE_ARG_HISTORY(FUNCNAME, 16); \ - SAVE_ARG_HISTORY(FUNCNAME, 17); \ - SAVE_ARG_HISTORY(FUNCNAME, 18); \ - SAVE_ARG_HISTORY(FUNCNAME, 19); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18, arg19); \ - } \ - else{ \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18, arg19); \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18, arg19); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC20(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ARG19_TYPE) \ - DECLARE_FAKE_VOID_FUNC20(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ARG19_TYPE) \ - DEFINE_FAKE_VOID_FUNC20(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ARG19_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC0(RETURN_TYPE, FUNCNAME) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, void); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, void); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(void); \ - -#define DEFINE_FAKE_VALUE_FUNC0(RETURN_TYPE, FUNCNAME) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(void){ \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC0(RETURN_TYPE, FUNCNAME) \ - DECLARE_FAKE_VALUE_FUNC0(RETURN_TYPE, FUNCNAME) \ - DEFINE_FAKE_VALUE_FUNC0(RETURN_TYPE, FUNCNAME) \ - - -#define DECLARE_FAKE_VALUE_FUNC1(RETURN_TYPE, FUNCNAME, ARG0_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0); \ - -#define DEFINE_FAKE_VALUE_FUNC1(RETURN_TYPE, FUNCNAME, ARG0_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0){ \ - SAVE_ARG(FUNCNAME, 0); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC1(RETURN_TYPE, FUNCNAME, ARG0_TYPE) \ - DECLARE_FAKE_VALUE_FUNC1(RETURN_TYPE, FUNCNAME, ARG0_TYPE) \ - DEFINE_FAKE_VALUE_FUNC1(RETURN_TYPE, FUNCNAME, ARG0_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC2(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1); \ - -#define DEFINE_FAKE_VALUE_FUNC2(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC2(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE) \ - DECLARE_FAKE_VALUE_FUNC2(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE) \ - DEFINE_FAKE_VALUE_FUNC2(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC3(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2); \ - -#define DEFINE_FAKE_VALUE_FUNC3(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC3(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE) \ - DECLARE_FAKE_VALUE_FUNC3(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE) \ - DEFINE_FAKE_VALUE_FUNC3(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC4(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3); \ - -#define DEFINE_FAKE_VALUE_FUNC4(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC4(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE) \ - DECLARE_FAKE_VALUE_FUNC4(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE) \ - DEFINE_FAKE_VALUE_FUNC4(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC5(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4); \ - -#define DEFINE_FAKE_VALUE_FUNC5(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC5(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE) \ - DECLARE_FAKE_VALUE_FUNC5(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE) \ - DEFINE_FAKE_VALUE_FUNC5(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC6(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5); \ - -#define DEFINE_FAKE_VALUE_FUNC6(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC6(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE) \ - DECLARE_FAKE_VALUE_FUNC6(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE) \ - DEFINE_FAKE_VALUE_FUNC6(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC7(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6); \ - -#define DEFINE_FAKE_VALUE_FUNC7(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC7(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE) \ - DECLARE_FAKE_VALUE_FUNC7(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE) \ - DEFINE_FAKE_VALUE_FUNC7(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC8(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7); \ - -#define DEFINE_FAKE_VALUE_FUNC8(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC8(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE) \ - DECLARE_FAKE_VALUE_FUNC8(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE) \ - DEFINE_FAKE_VALUE_FUNC8(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC9(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8); \ - -#define DEFINE_FAKE_VALUE_FUNC9(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC9(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE) \ - DECLARE_FAKE_VALUE_FUNC9(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE) \ - DEFINE_FAKE_VALUE_FUNC9(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC10(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9); \ - -#define DEFINE_FAKE_VALUE_FUNC10(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC10(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE) \ - DECLARE_FAKE_VALUE_FUNC10(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE) \ - DEFINE_FAKE_VALUE_FUNC10(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC11(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10); \ - -#define DEFINE_FAKE_VALUE_FUNC11(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC11(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE) \ - DECLARE_FAKE_VALUE_FUNC11(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE) \ - DEFINE_FAKE_VALUE_FUNC11(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC12(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11); \ - -#define DEFINE_FAKE_VALUE_FUNC12(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC12(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE) \ - DECLARE_FAKE_VALUE_FUNC12(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE) \ - DEFINE_FAKE_VALUE_FUNC12(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC13(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12); \ - -#define DEFINE_FAKE_VALUE_FUNC13(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC13(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE) \ - DECLARE_FAKE_VALUE_FUNC13(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE) \ - DEFINE_FAKE_VALUE_FUNC13(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC14(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13); \ - -#define DEFINE_FAKE_VALUE_FUNC14(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC14(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE) \ - DECLARE_FAKE_VALUE_FUNC14(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE) \ - DEFINE_FAKE_VALUE_FUNC14(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC15(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14); \ - -#define DEFINE_FAKE_VALUE_FUNC15(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC15(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE) \ - DECLARE_FAKE_VALUE_FUNC15(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE) \ - DEFINE_FAKE_VALUE_FUNC15(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC16(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15); \ - -#define DEFINE_FAKE_VALUE_FUNC16(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC16(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE) \ - DECLARE_FAKE_VALUE_FUNC16(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE) \ - DEFINE_FAKE_VALUE_FUNC16(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC17(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ARG(ARG16_TYPE, 16, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16); \ - -#define DEFINE_FAKE_VALUE_FUNC17(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - SAVE_ARG(FUNCNAME, 16); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - SAVE_ARG_HISTORY(FUNCNAME, 16); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC17(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE) \ - DECLARE_FAKE_VALUE_FUNC17(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE) \ - DEFINE_FAKE_VALUE_FUNC17(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC18(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ARG(ARG16_TYPE, 16, FUNCNAME) \ - DECLARE_ARG(ARG17_TYPE, 17, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17); \ - -#define DEFINE_FAKE_VALUE_FUNC18(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - SAVE_ARG(FUNCNAME, 16); \ - SAVE_ARG(FUNCNAME, 17); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - SAVE_ARG_HISTORY(FUNCNAME, 16); \ - SAVE_ARG_HISTORY(FUNCNAME, 17); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC18(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE) \ - DECLARE_FAKE_VALUE_FUNC18(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE) \ - DEFINE_FAKE_VALUE_FUNC18(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC19(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ARG(ARG16_TYPE, 16, FUNCNAME) \ - DECLARE_ARG(ARG17_TYPE, 17, FUNCNAME) \ - DECLARE_ARG(ARG18_TYPE, 18, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ARG18_TYPE arg18); \ - -#define DEFINE_FAKE_VALUE_FUNC19(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ARG18_TYPE arg18){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - SAVE_ARG(FUNCNAME, 16); \ - SAVE_ARG(FUNCNAME, 17); \ - SAVE_ARG(FUNCNAME, 18); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - SAVE_ARG_HISTORY(FUNCNAME, 16); \ - SAVE_ARG_HISTORY(FUNCNAME, 17); \ - SAVE_ARG_HISTORY(FUNCNAME, 18); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC19(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE) \ - DECLARE_FAKE_VALUE_FUNC19(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE) \ - DEFINE_FAKE_VALUE_FUNC19(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE) \ - - -#define DECLARE_FAKE_VALUE_FUNC20(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ARG19_TYPE) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ARG(ARG16_TYPE, 16, FUNCNAME) \ - DECLARE_ARG(ARG17_TYPE, 17, FUNCNAME) \ - DECLARE_ARG(ARG18_TYPE, 18, FUNCNAME) \ - DECLARE_ARG(ARG19_TYPE, 19, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ARG19_TYPE); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ARG19_TYPE); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ARG18_TYPE arg18, ARG19_TYPE arg19); \ - -#define DEFINE_FAKE_VALUE_FUNC20(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ARG19_TYPE) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ARG18_TYPE arg18, ARG19_TYPE arg19){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - SAVE_ARG(FUNCNAME, 16); \ - SAVE_ARG(FUNCNAME, 17); \ - SAVE_ARG(FUNCNAME, 18); \ - SAVE_ARG(FUNCNAME, 19); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - SAVE_ARG_HISTORY(FUNCNAME, 16); \ - SAVE_ARG_HISTORY(FUNCNAME, 17); \ - SAVE_ARG_HISTORY(FUNCNAME, 18); \ - SAVE_ARG_HISTORY(FUNCNAME, 19); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18, arg19); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - else{ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18, arg19); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - } \ - if (FUNCNAME##_fake.custom_fake != NULL){ \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18, arg19); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC20(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ARG19_TYPE) \ - DECLARE_FAKE_VALUE_FUNC20(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ARG19_TYPE) \ - DEFINE_FAKE_VALUE_FUNC20(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ARG19_TYPE) \ - - -#define DECLARE_FAKE_VOID_FUNC2_VARARG(FUNCNAME, ARG0_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ...); \ - -#define DEFINE_FAKE_VOID_FUNC2_VARARG(FUNCNAME, ARG0_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg0); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg0); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg0); \ - FUNCNAME##_fake.custom_fake(arg0, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC2_VARARG(FUNCNAME, ARG0_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC2_VARARG(FUNCNAME, ARG0_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC2_VARARG(FUNCNAME, ARG0_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC3_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ...); \ - -#define DEFINE_FAKE_VOID_FUNC3_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg1); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg1); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg1); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC3_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC3_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC3_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC4_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ...); \ - -#define DEFINE_FAKE_VOID_FUNC4_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg2); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg2); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg2); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC4_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC4_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC4_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC5_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ...); \ - -#define DEFINE_FAKE_VOID_FUNC5_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg3); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg3); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg3); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC5_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC5_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC5_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC6_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ...); \ - -#define DEFINE_FAKE_VOID_FUNC6_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg4); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg4); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg4); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC6_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC6_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC6_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC7_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ...); \ - -#define DEFINE_FAKE_VOID_FUNC7_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg5); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg5); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg5); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC7_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC7_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC7_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC8_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ...); \ - -#define DEFINE_FAKE_VOID_FUNC8_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg6); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg6); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg6); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC8_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC8_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC8_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC9_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ...); \ - -#define DEFINE_FAKE_VOID_FUNC9_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg7); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg7); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg7); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC9_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC9_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC9_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC10_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ...); \ - -#define DEFINE_FAKE_VOID_FUNC10_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg8); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg8); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg8); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC10_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC10_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC10_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC11_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ...); \ - -#define DEFINE_FAKE_VOID_FUNC11_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg9); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg9); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg9); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC11_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC11_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC11_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC12_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ...); \ - -#define DEFINE_FAKE_VOID_FUNC12_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg10); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg10); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg10); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC12_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC12_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC12_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC13_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ...); \ - -#define DEFINE_FAKE_VOID_FUNC13_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg11); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg11); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg11); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC13_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC13_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC13_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC14_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ...); \ - -#define DEFINE_FAKE_VOID_FUNC14_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg12); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg12); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg12); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC14_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC14_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC14_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC15_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ...); \ - -#define DEFINE_FAKE_VOID_FUNC15_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg13); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg13); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg13); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC15_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC15_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC15_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC16_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ...); \ - -#define DEFINE_FAKE_VOID_FUNC16_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg14); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg14); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg14); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC16_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC16_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC16_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC17_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ...); \ - -#define DEFINE_FAKE_VOID_FUNC17_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg15); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg15); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg15); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC17_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC17_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC17_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC18_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ARG(ARG16_TYPE, 16, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ...); \ - -#define DEFINE_FAKE_VOID_FUNC18_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - SAVE_ARG(FUNCNAME, 16); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - SAVE_ARG_HISTORY(FUNCNAME, 16); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg16); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg16); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg16); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC18_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC18_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC18_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC19_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ARG(ARG16_TYPE, 16, FUNCNAME) \ - DECLARE_ARG(ARG17_TYPE, 17, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ...); \ - -#define DEFINE_FAKE_VOID_FUNC19_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - SAVE_ARG(FUNCNAME, 16); \ - SAVE_ARG(FUNCNAME, 17); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - SAVE_ARG_HISTORY(FUNCNAME, 16); \ - SAVE_ARG_HISTORY(FUNCNAME, 17); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg17); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg17); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg17); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC19_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC19_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC19_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ...) \ - - -#define DECLARE_FAKE_VOID_FUNC20_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ARG(ARG16_TYPE, 16, FUNCNAME) \ - DECLARE_ARG(ARG17_TYPE, 17, FUNCNAME) \ - DECLARE_ARG(ARG18_TYPE, 18, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(void, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ARG18_TYPE arg18, ...); \ - -#define DEFINE_FAKE_VOID_FUNC20_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - void FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ARG18_TYPE arg18, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - SAVE_ARG(FUNCNAME, 16); \ - SAVE_ARG(FUNCNAME, 17); \ - SAVE_ARG(FUNCNAME, 18); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - SAVE_ARG_HISTORY(FUNCNAME, 16); \ - SAVE_ARG_HISTORY(FUNCNAME, 17); \ - SAVE_ARG_HISTORY(FUNCNAME, 18); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg18); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18, ap); \ - va_end(ap); \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg18); \ - FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18, ap); \ - va_end(ap); \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - va_list ap; \ - va_start(ap, arg18); \ - FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18, ap); \ - va_end(ap); \ - } \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VOID_FUNC20_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ...) \ - DECLARE_FAKE_VOID_FUNC20_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ...) \ - DEFINE_FAKE_VOID_FUNC20_VARARG(FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC2_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC2_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg0); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg0); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg0); \ - ret = FUNCNAME##_fake.custom_fake(arg0, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC2_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC2_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC2_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC3_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC3_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg1); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg1); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg1); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC3_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC3_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC3_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC4_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC4_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg2); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg2); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg2); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC4_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC4_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC4_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC5_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC5_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg3); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg3); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg3); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC5_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC5_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC5_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC6_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC6_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg4); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg4); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg4); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC6_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC6_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC6_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC7_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC7_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg5); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg5); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg5); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC7_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC7_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC7_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC8_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC8_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg6); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg6); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg6); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC8_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC8_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC8_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC9_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC9_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg7); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg7); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg7); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC9_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC9_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC9_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC10_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC10_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg8); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg8); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg8); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC10_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC10_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC10_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC11_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC11_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg9); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg9); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg9); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC11_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC11_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC11_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC12_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC12_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg10); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg10); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg10); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC12_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC12_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC12_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC13_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC13_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg11); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg11); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg11); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC13_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC13_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC13_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC14_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC14_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg12); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg12); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg12); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC14_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC14_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC14_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC15_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC15_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg13); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg13); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg13); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC15_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC15_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC15_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC16_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC16_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg14); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg14); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg14); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC16_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC16_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC16_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC17_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC17_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg15); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg15); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg15); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC17_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC17_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC17_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC18_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ARG(ARG16_TYPE, 16, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC18_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - SAVE_ARG(FUNCNAME, 16); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - SAVE_ARG_HISTORY(FUNCNAME, 16); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg16); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg16); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg16); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC18_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC18_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC18_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC19_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ARG(ARG16_TYPE, 16, FUNCNAME) \ - DECLARE_ARG(ARG17_TYPE, 17, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC19_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - SAVE_ARG(FUNCNAME, 16); \ - SAVE_ARG(FUNCNAME, 17); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - SAVE_ARG_HISTORY(FUNCNAME, 16); \ - SAVE_ARG_HISTORY(FUNCNAME, 17); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg17); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg17); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg17); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC19_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC19_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC19_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ...) \ - - -#define DECLARE_FAKE_VALUE_FUNC20_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ...) \ - typedef struct FUNCNAME##_Fake { \ - DECLARE_ARG(ARG0_TYPE, 0, FUNCNAME) \ - DECLARE_ARG(ARG1_TYPE, 1, FUNCNAME) \ - DECLARE_ARG(ARG2_TYPE, 2, FUNCNAME) \ - DECLARE_ARG(ARG3_TYPE, 3, FUNCNAME) \ - DECLARE_ARG(ARG4_TYPE, 4, FUNCNAME) \ - DECLARE_ARG(ARG5_TYPE, 5, FUNCNAME) \ - DECLARE_ARG(ARG6_TYPE, 6, FUNCNAME) \ - DECLARE_ARG(ARG7_TYPE, 7, FUNCNAME) \ - DECLARE_ARG(ARG8_TYPE, 8, FUNCNAME) \ - DECLARE_ARG(ARG9_TYPE, 9, FUNCNAME) \ - DECLARE_ARG(ARG10_TYPE, 10, FUNCNAME) \ - DECLARE_ARG(ARG11_TYPE, 11, FUNCNAME) \ - DECLARE_ARG(ARG12_TYPE, 12, FUNCNAME) \ - DECLARE_ARG(ARG13_TYPE, 13, FUNCNAME) \ - DECLARE_ARG(ARG14_TYPE, 14, FUNCNAME) \ - DECLARE_ARG(ARG15_TYPE, 15, FUNCNAME) \ - DECLARE_ARG(ARG16_TYPE, 16, FUNCNAME) \ - DECLARE_ARG(ARG17_TYPE, 17, FUNCNAME) \ - DECLARE_ARG(ARG18_TYPE, 18, FUNCNAME) \ - DECLARE_ALL_FUNC_COMMON \ - DECLARE_VALUE_FUNCTION_VARIABLES(RETURN_TYPE) \ - DECLARE_RETURN_VALUE_HISTORY(RETURN_TYPE) \ - DECLARE_CUSTOM_FAKE_SEQ_VARIABLES \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, custom_fake, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, va_list ap); \ - CUSTOM_FFF_FUNCTION_TEMPLATE(RETURN_TYPE, *custom_fake_seq, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, va_list ap); \ - } FUNCNAME##_Fake; \ - extern FUNCNAME##_Fake FUNCNAME##_fake; \ - void FUNCNAME##_reset(void); \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ARG18_TYPE arg18, ...); \ - -#define DEFINE_FAKE_VALUE_FUNC20_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ...) \ - FUNCNAME##_Fake FUNCNAME##_fake; \ - RETURN_TYPE FFF_GCC_FUNCTION_ATTRIBUTES FUNCNAME(ARG0_TYPE arg0, ARG1_TYPE arg1, ARG2_TYPE arg2, ARG3_TYPE arg3, ARG4_TYPE arg4, ARG5_TYPE arg5, ARG6_TYPE arg6, ARG7_TYPE arg7, ARG8_TYPE arg8, ARG9_TYPE arg9, ARG10_TYPE arg10, ARG11_TYPE arg11, ARG12_TYPE arg12, ARG13_TYPE arg13, ARG14_TYPE arg14, ARG15_TYPE arg15, ARG16_TYPE arg16, ARG17_TYPE arg17, ARG18_TYPE arg18, ...){ \ - SAVE_ARG(FUNCNAME, 0); \ - SAVE_ARG(FUNCNAME, 1); \ - SAVE_ARG(FUNCNAME, 2); \ - SAVE_ARG(FUNCNAME, 3); \ - SAVE_ARG(FUNCNAME, 4); \ - SAVE_ARG(FUNCNAME, 5); \ - SAVE_ARG(FUNCNAME, 6); \ - SAVE_ARG(FUNCNAME, 7); \ - SAVE_ARG(FUNCNAME, 8); \ - SAVE_ARG(FUNCNAME, 9); \ - SAVE_ARG(FUNCNAME, 10); \ - SAVE_ARG(FUNCNAME, 11); \ - SAVE_ARG(FUNCNAME, 12); \ - SAVE_ARG(FUNCNAME, 13); \ - SAVE_ARG(FUNCNAME, 14); \ - SAVE_ARG(FUNCNAME, 15); \ - SAVE_ARG(FUNCNAME, 16); \ - SAVE_ARG(FUNCNAME, 17); \ - SAVE_ARG(FUNCNAME, 18); \ - if(ROOM_FOR_MORE_HISTORY(FUNCNAME)){ \ - SAVE_ARG_HISTORY(FUNCNAME, 0); \ - SAVE_ARG_HISTORY(FUNCNAME, 1); \ - SAVE_ARG_HISTORY(FUNCNAME, 2); \ - SAVE_ARG_HISTORY(FUNCNAME, 3); \ - SAVE_ARG_HISTORY(FUNCNAME, 4); \ - SAVE_ARG_HISTORY(FUNCNAME, 5); \ - SAVE_ARG_HISTORY(FUNCNAME, 6); \ - SAVE_ARG_HISTORY(FUNCNAME, 7); \ - SAVE_ARG_HISTORY(FUNCNAME, 8); \ - SAVE_ARG_HISTORY(FUNCNAME, 9); \ - SAVE_ARG_HISTORY(FUNCNAME, 10); \ - SAVE_ARG_HISTORY(FUNCNAME, 11); \ - SAVE_ARG_HISTORY(FUNCNAME, 12); \ - SAVE_ARG_HISTORY(FUNCNAME, 13); \ - SAVE_ARG_HISTORY(FUNCNAME, 14); \ - SAVE_ARG_HISTORY(FUNCNAME, 15); \ - SAVE_ARG_HISTORY(FUNCNAME, 16); \ - SAVE_ARG_HISTORY(FUNCNAME, 17); \ - SAVE_ARG_HISTORY(FUNCNAME, 18); \ - } \ - else{ \ - HISTORY_DROPPED(FUNCNAME); \ - } \ - INCREMENT_CALL_COUNT(FUNCNAME); \ - REGISTER_CALL(FUNCNAME); \ - if (FUNCNAME##_fake.custom_fake_seq_len){ /* a sequence of custom fakes */ \ - if (FUNCNAME##_fake.custom_fake_seq_idx < FUNCNAME##_fake.custom_fake_seq_len){ \ - va_list ap; \ - va_start(ap, arg18); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_idx++](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - else{ \ - va_list ap; \ - va_start(ap, arg18); \ - RETURN_TYPE ret = FUNCNAME##_fake.custom_fake_seq[FUNCNAME##_fake.custom_fake_seq_len-1](arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18, ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - va_end(ap); \ - return ret; \ - } \ - } \ - if(FUNCNAME##_fake.custom_fake){ \ - RETURN_TYPE ret; \ - va_list ap; \ - va_start(ap, arg18); \ - ret = FUNCNAME##_fake.custom_fake(arg0, arg1, arg2, arg3, arg4, arg5, arg6, arg7, arg8, arg9, arg10, arg11, arg12, arg13, arg14, arg15, arg16, arg17, arg18, ap); \ - va_end(ap); \ - SAVE_RET_HISTORY(FUNCNAME, ret); \ - return ret; \ - } \ - RETURN_FAKE_RESULT(FUNCNAME) \ - } \ - DEFINE_RESET_FUNCTION(FUNCNAME) \ - -#define FAKE_VALUE_FUNC20_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ...) \ - DECLARE_FAKE_VALUE_FUNC20_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ...) \ - DEFINE_FAKE_VALUE_FUNC20_VARARG(RETURN_TYPE, FUNCNAME, ARG0_TYPE, ARG1_TYPE, ARG2_TYPE, ARG3_TYPE, ARG4_TYPE, ARG5_TYPE, ARG6_TYPE, ARG7_TYPE, ARG8_TYPE, ARG9_TYPE, ARG10_TYPE, ARG11_TYPE, ARG12_TYPE, ARG13_TYPE, ARG14_TYPE, ARG15_TYPE, ARG16_TYPE, ARG17_TYPE, ARG18_TYPE, ...) \ - -/* MSVC expand macro fix */ -#define EXPAND(x) x - -#define PP_NARG_MINUS2(...) EXPAND(PP_NARG_MINUS2_(__VA_ARGS__, PP_RSEQ_N_MINUS2())) - -#define PP_NARG_MINUS2_(...) EXPAND(PP_ARG_MINUS2_N(__VA_ARGS__)) - -#define PP_ARG_MINUS2_N(returnVal, _0, _1, _2, _3, _4, _5, _6, _7, _8, _9, _10, _11, _12, _13, _14, _15, _16, _17, _18, _19, _20, N, ...) N - -#define PP_RSEQ_N_MINUS2() 20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0 - -#define PP_NARG_MINUS1(...) EXPAND(PP_NARG_MINUS1_(__VA_ARGS__, PP_RSEQ_N_MINUS1())) - -#define PP_NARG_MINUS1_(...) EXPAND(PP_ARG_MINUS1_N(__VA_ARGS__)) - -#define PP_ARG_MINUS1_N( _0, _1, _2, _3, _4, _5, _6, _7, _8, _9, _10, _11, _12, _13, _14, _15, _16, _17, _18, _19, _20, N, ...) N - -#define PP_RSEQ_N_MINUS1() 20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0 - - - -/* DECLARE AND DEFINE FAKE FUNCTIONS - PLACE IN TEST FILES */ - -#define FAKE_VALUE_FUNC(...) EXPAND(FUNC_VALUE_(PP_NARG_MINUS2(__VA_ARGS__), __VA_ARGS__)) - -#define FUNC_VALUE_(N,...) EXPAND(FUNC_VALUE_N(N,__VA_ARGS__)) - -#define FUNC_VALUE_N(N,...) EXPAND(FAKE_VALUE_FUNC ## N(__VA_ARGS__)) - - -#define FAKE_VOID_FUNC(...) EXPAND(FUNC_VOID_(PP_NARG_MINUS1(__VA_ARGS__), __VA_ARGS__)) - -#define FUNC_VOID_(N,...) EXPAND(FUNC_VOID_N(N,__VA_ARGS__)) - -#define FUNC_VOID_N(N,...) EXPAND(FAKE_VOID_FUNC ## N(__VA_ARGS__)) - - -#define FAKE_VALUE_FUNC_VARARG(...) EXPAND(FUNC_VALUE_VARARG_(PP_NARG_MINUS2(__VA_ARGS__), __VA_ARGS__)) - -#define FUNC_VALUE_VARARG_(N,...) EXPAND(FUNC_VALUE_VARARG_N(N,__VA_ARGS__)) - -#define FUNC_VALUE_VARARG_N(N,...) EXPAND(FAKE_VALUE_FUNC ## N ## _VARARG(__VA_ARGS__)) - - -#define FAKE_VOID_FUNC_VARARG(...) EXPAND(FUNC_VOID_VARARG_(PP_NARG_MINUS1(__VA_ARGS__), __VA_ARGS__)) - -#define FUNC_VOID_VARARG_(N,...) EXPAND(FUNC_VOID_VARARG_N(N,__VA_ARGS__)) - -#define FUNC_VOID_VARARG_N(N,...) EXPAND(FAKE_VOID_FUNC ## N ## _VARARG(__VA_ARGS__)) - - - -/* DECLARE FAKE FUNCTIONS - PLACE IN HEADER FILES */ - -#define DECLARE_FAKE_VALUE_FUNC(...) EXPAND(DECLARE_FUNC_VALUE_(PP_NARG_MINUS2(__VA_ARGS__), __VA_ARGS__)) - -#define DECLARE_FUNC_VALUE_(N,...) EXPAND(DECLARE_FUNC_VALUE_N(N,__VA_ARGS__)) - -#define DECLARE_FUNC_VALUE_N(N,...) EXPAND(DECLARE_FAKE_VALUE_FUNC ## N(__VA_ARGS__)) - - -#define DECLARE_FAKE_VOID_FUNC(...) EXPAND(DECLARE_FUNC_VOID_(PP_NARG_MINUS1(__VA_ARGS__), __VA_ARGS__)) - -#define DECLARE_FUNC_VOID_(N,...) EXPAND(DECLARE_FUNC_VOID_N(N,__VA_ARGS__)) - -#define DECLARE_FUNC_VOID_N(N,...) EXPAND(DECLARE_FAKE_VOID_FUNC ## N(__VA_ARGS__)) - - -#define DECLARE_FAKE_VALUE_FUNC_VARARG(...) EXPAND(DECLARE_FUNC_VALUE_VARARG_(PP_NARG_MINUS2(__VA_ARGS__), __VA_ARGS__)) - -#define DECLARE_FUNC_VALUE_VARARG_(N,...) EXPAND(DECLARE_FUNC_VALUE_VARARG_N(N,__VA_ARGS__)) - -#define DECLARE_FUNC_VALUE_VARARG_N(N,...) EXPAND(DECLARE_FAKE_VALUE_FUNC ## N ## _VARARG(__VA_ARGS__)) - - -#define DECLARE_FAKE_VOID_FUNC_VARARG(...) EXPAND(DECLARE_FUNC_VOID_VARARG_(PP_NARG_MINUS1(__VA_ARGS__), __VA_ARGS__)) - -#define DECLARE_FUNC_VOID_VARARG_(N,...) EXPAND(DECLARE_FUNC_VOID_VARARG_N(N,__VA_ARGS__)) - -#define DECLARE_FUNC_VOID_VARARG_N(N,...) EXPAND(DECLARE_FAKE_VOID_FUNC ## N ## _VARARG(__VA_ARGS__)) - - - -/* DEFINE FAKE FUNCTIONS - PLACE IN SOURCE FILES */ - -#define DEFINE_FAKE_VALUE_FUNC(...) EXPAND(DEFINE_FUNC_VALUE_(PP_NARG_MINUS2(__VA_ARGS__), __VA_ARGS__)) - -#define DEFINE_FUNC_VALUE_(N,...) EXPAND(DEFINE_FUNC_VALUE_N(N,__VA_ARGS__)) - -#define DEFINE_FUNC_VALUE_N(N,...) EXPAND(DEFINE_FAKE_VALUE_FUNC ## N(__VA_ARGS__)) - - -#define DEFINE_FAKE_VOID_FUNC(...) EXPAND(DEFINE_FUNC_VOID_(PP_NARG_MINUS1(__VA_ARGS__), __VA_ARGS__)) - -#define DEFINE_FUNC_VOID_(N,...) EXPAND(DEFINE_FUNC_VOID_N(N,__VA_ARGS__)) - -#define DEFINE_FUNC_VOID_N(N,...) EXPAND(DEFINE_FAKE_VOID_FUNC ## N(__VA_ARGS__)) - - -#define DEFINE_FAKE_VALUE_FUNC_VARARG(...) EXPAND(DEFINE_FUNC_VALUE_VARARG_(PP_NARG_MINUS2(__VA_ARGS__), __VA_ARGS__)) - -#define DEFINE_FUNC_VALUE_VARARG_(N,...) EXPAND(DEFINE_FUNC_VALUE_VARARG_N(N,__VA_ARGS__)) - -#define DEFINE_FUNC_VALUE_VARARG_N(N,...) EXPAND(DEFINE_FAKE_VALUE_FUNC ## N ## _VARARG(__VA_ARGS__)) - - -#define DEFINE_FAKE_VOID_FUNC_VARARG(...) EXPAND(DEFINE_FUNC_VOID_VARARG_(PP_NARG_MINUS1(__VA_ARGS__), __VA_ARGS__)) - -#define DEFINE_FUNC_VOID_VARARG_(N,...) EXPAND(DEFINE_FUNC_VOID_VARARG_N(N,__VA_ARGS__)) - -#define DEFINE_FUNC_VOID_VARARG_N(N,...) EXPAND(DEFINE_FAKE_VOID_FUNC ## N ## _VARARG(__VA_ARGS__)) - - - - -#endif /* FAKE_FUNCTIONS */ diff --git a/unit_tests/test_common/test_MappedDict.cpp b/unit_tests/test_common/test_MappedDict.cpp index fb61fc70..c915c878 100644 --- a/unit_tests/test_common/test_MappedDict.cpp +++ b/unit_tests/test_common/test_MappedDict.cpp @@ -44,7 +44,7 @@ void test_function_mapped_dict_bounds(void) void test_function_mapped_dict_zero_size(void) { - MappedDict::DictEntry_t lookupTable[] = {}; + MappedDict::DictEntry_t lookupTable[] = {{'\0', 0}}; auto idxLookup = MappedDict(lookupTable, 0); int intIdx; diff --git a/unit_tests/test_meade/test_MeadeDistance.cpp b/unit_tests/test_meade/test_MeadeDistance.cpp new file mode 100644 index 00000000..07c560ab --- /dev/null +++ b/unit_tests/test_meade/test_MeadeDistance.cpp @@ -0,0 +1,72 @@ +// Wire-byte tests for the Meade Distance-bars dispatcher (`handleMeadeDistance`). +// +// The `:D#` command reports motion status as a single byte ('|' while +// slewing, ' ' when idle) followed by the standard terminator. Any suffix +// is treated identically (legacy lenient behaviour). + +#include + +#include "core/meade/MeadeParser.hpp" + +namespace meade = oat::core::meade; + +namespace +{ + +class FakeHandlers : public meade::IMeadeDistanceHandlers +{ + public: + bool slewing = false; + int callCount = 0; + + bool onIsSlewingRaOrDec() override + { + ++callCount; + return slewing; + } +}; + +const char *dispatch(const char *suffix, FakeHandlers &h) +{ + static meade::MeadeResponse last; + last = meade::handleMeadeDistance(suffix, h); + return last.c_str(); +} + +} // namespace + +namespace +{ + +void test_distance_idle_emits_space() +{ + FakeHandlers h; + h.slewing = false; + TEST_ASSERT_EQUAL_STRING(" #", dispatch("", h)); + TEST_ASSERT_EQUAL_INT(1, h.callCount); +} + +void test_distance_slewing_emits_pipe() +{ + FakeHandlers h; + h.slewing = true; + TEST_ASSERT_EQUAL_STRING("|#", dispatch("", h)); + TEST_ASSERT_EQUAL_INT(1, h.callCount); +} + +void test_distance_ignores_suffix_bytes() +{ + FakeHandlers h; + h.slewing = true; + TEST_ASSERT_EQUAL_STRING("|#", dispatch("xyz", h)); + TEST_ASSERT_EQUAL_INT(1, h.callCount); +} + +} // namespace + +void register_meade_distance_tests() +{ + RUN_TEST(test_distance_idle_emits_space); + RUN_TEST(test_distance_slewing_emits_pipe); + RUN_TEST(test_distance_ignores_suffix_bytes); +} diff --git a/unit_tests/test_meade/test_MeadeExtra.cpp b/unit_tests/test_meade/test_MeadeExtra.cpp new file mode 100644 index 00000000..9b3194aa --- /dev/null +++ b/unit_tests/test_meade/test_MeadeExtra.cpp @@ -0,0 +1,545 @@ +// Wire-byte tests for the Meade Extra dispatcher (`handleMeadeExtra`). +// +// Covers representative `:X...` sub-commands across the five family branches: +// - FactoryReset (`:XFR`) → "1#" +// - DriftAlignment (`:XD`) → "" (no-op on the dispatcher level) +// - Get-leaves (`:XG...`) → diverse tag shapes +// - Set-leaves (`:XS...`) → "" with side-effects on handler +// - Level-leaves (`:XL...`) → SetSuccess / pair / fallback +// +// Compile-time hardware guards live in the overrides; the dispatcher itself +// is hardware-agnostic and exercised directly here via a fake handler. + +#include + +#include "core/meade/MeadeParser.hpp" + +namespace meade = oat::core::meade; + +namespace +{ + +class FakeExtra : public meade::IMeadeExtraHandlers +{ + public: + // Captured calls + bool factoryResetCalled = false; + bool driftCalled = false; + int driftDuration = 0; + bool getDecLimitsCalled = false; + bool levelAvailable = true; + bool startupCalled = false; + bool shutdownCalled = false; + + // Returned values + float raSpd = 100.5f; + float decSpd = 200.25f; + float altSpd = 12.5f; + float azSpd = 13.5f; + meade::ExtraDecLimits decLimits {-30.5f, 45.5f}; + float speedCalibration = 1.00125f; + float remainingSafeTime = 3.5f; + float trackingSpeed = 0.0041667f; + int backlash = 7; + const char *autoHomeStates = "RA:Idle,DEC:Idle"; + meade::ExtraAzAltPositions azalt {123L, 456L}; + meade::ExtraStepperCoords targetCoords {1000L, 2000L}; + const char *stepperInfo = "RA:TMC,DEC:TMC"; + const char *hardwareInfo = "MEGA,RAMPS"; + const char *logBuffer = "abc"; + long raHomeOff = -10L; + long decHomeOff = 20L; + bool northern = true; + meade::ExtraHms hourAngle {3, 4, 5}; + meade::ExtraHms lst {6, 7, 8}; + const char *networkStatus = "WL,OAT,192.168.1.10"; + meade::ExtraPitchRoll refAngles {1.1f, 2.2f}; + meade::ExtraPitchRoll curAngles {3.3f, 4.4f}; + float gyroTemperature = 22.5f; + + // Captured Set arguments + float setRaSpd = 0.0f; + float setDecSpd = 0.0f; + bool decLimitLowerPayload = false; + float decLimitLowerVal = 0.0f; + bool clearLowerCalled = false; + bool clearUpperCalled = false; + long setTrackingStepperPos = 0; + bool setManualSlew = false; + int setBacklash = 0; + long setRaHomingOffset = 0L; + + void onFactoryReset() override + { + factoryResetCalled = true; + } + void onDriftAlignment(int duration) override + { + driftCalled = true; + driftDuration = duration; + } + float onGetRaStepsPerDegree() override + { + return raSpd; + } + float onGetDecStepsPerDegree() override + { + return decSpd; + } + float onGetAltStepsPerDegree() override + { + return altSpd; + } + float onGetAzStepsPerDegree() override + { + return azSpd; + } + meade::ExtraDecLimits onGetDecLimits() override + { + getDecLimitsCalled = true; + return decLimits; + } + float onGetTrackingSpeedCalibration() override + { + return speedCalibration; + } + float onGetRemainingSafeTime() override + { + return remainingSafeTime; + } + float onGetTrackingSpeed() override + { + return trackingSpeed; + } + int onGetBacklashSteps() override + { + return backlash; + } + const char *onGetAutoHomingStates() override + { + return autoHomeStates; + } + meade::ExtraAzAltPositions onGetAzAltPositions() override + { + return azalt; + } + meade::ExtraStepperCoords onGetTargetCoordinatePositions(float, float) override + { + return targetCoords; + } + const char *onGetStepperInfo() override + { + return stepperInfo; + } + const char *onGetMountHardwareInfo() override + { + return hardwareInfo; + } + const char *onGetLogBuffer() override + { + return logBuffer; + } + long onGetRaHomingOffset() override + { + return raHomeOff; + } + long onGetDecHomingOffset() override + { + return decHomeOff; + } + bool onGetHemisphere() override + { + return northern; + } + meade::ExtraHms onGetHourAngle() override + { + return hourAngle; + } + meade::ExtraHms onGetLocalSiderealTime() override + { + return lst; + } + const char *onGetNetworkStatus() override + { + return networkStatus; + } + + void onSetRaStepsPerDegree(float v) override + { + setRaSpd = v; + } + void onSetDecStepsPerDegree(float v) override + { + setDecSpd = v; + } + void onSetAzStepsPerDegree(float) override + { + } + void onSetAltStepsPerDegree(float) override + { + } + void onSetDecLimitLower(bool havePayload, float value) override + { + decLimitLowerPayload = havePayload; + decLimitLowerVal = value; + } + void onSetDecLimitUpper(bool, float) override + { + } + void onClearDecLimitLower() override + { + clearLowerCalled = true; + } + void onClearDecLimitUpper() override + { + clearUpperCalled = true; + } + void onSetTrackingSpeedCalibration(float) override + { + } + void onSetTrackingStepperPosition(long v) override + { + setTrackingStepperPos = v; + } + void onSetManualSlewMode(bool enable) override + { + setManualSlew = enable; + } + void onSetRaManualSpeed(float) override + { + } + void onSetDecManualSpeed(float) override + { + } + void onSetBacklashCorrection(int v) override + { + setBacklash = v; + } + void onSetRaHomingOffset(long v) override + { + setRaHomingOffset = v; + } + void onSetDecHomingOffset(long) override + { + } + + bool onLevelIsAvailable() override + { + return levelAvailable; + } + meade::ExtraPitchRoll onLevelGetReferenceAngles() override + { + return refAngles; + } + meade::ExtraPitchRoll onLevelGetCurrentAngles() override + { + return curAngles; + } + float onLevelGetTemperature() override + { + return gyroTemperature; + } + void onLevelSetReferencePitch(float) override + { + } + void onLevelSetReferenceRoll(float) override + { + } + void onLevelStartup() override + { + startupCalled = true; + } + void onLevelShutdown() override + { + shutdownCalled = true; + } +}; + +const char *dispatch(const char *suffix, FakeExtra &h) +{ + static meade::MeadeResponse last; + last = meade::handleMeadeExtra(suffix, h); + return last.c_str(); +} + +} // namespace + +namespace +{ + +// ---- Family-level ----------------------------------------------------------- + +void test_extra_factory_reset_emits_one_terminator_and_calls_handler() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("1#", dispatch("FR", h)); + TEST_ASSERT_TRUE(h.factoryResetCalled); +} + +void test_extra_drift_alignment_emits_empty_and_passes_duration_minus_three() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("", dispatch("D5", h)); + TEST_ASSERT_TRUE(h.driftCalled); + TEST_ASSERT_EQUAL_INT(2, h.driftDuration); +} + +void test_extra_unknown_family_emits_empty() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("", dispatch("Z", h)); +} + +void test_extra_empty_suffix_emits_empty() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("", dispatch("", h)); +} + +// ---- Get leaves ------------------------------------------------------------- + +void test_extra_get_ra_steps_per_degree_numeric_float_one_decimal() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("100.5#", dispatch("GR", h)); +} + +void test_extra_get_dec_limit_both_pipe_pair() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("-30.5|45.5#", dispatch("GDL", h)); + TEST_ASSERT_TRUE(h.getDecLimitsCalled); +} + +void test_extra_get_dec_limit_lower_only_uses_lo_value() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("-30.5#", dispatch("GDLL", h)); +} + +void test_extra_get_dec_limit_upper_only_uses_hi_value() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("45.5#", dispatch("GDLU", h)); +} + +void test_extra_get_dec_limit_invalid_variant_fixed_false() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("0#", dispatch("GDLQ", h)); +} + +void test_extra_get_dec_parking_fixed_false() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("0#", dispatch("GDP", h)); +} + +void test_extra_get_backlash_steps_int() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("7#", dispatch("GB", h)); +} + +void test_extra_get_az_alt_positions_long_pair_pipe() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("123|456#", dispatch("GAA", h)); +} + +void test_extra_get_target_coordinate_positions_parses_payload() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("1000|2000#", dispatch("GC10.5*-20.0", h)); +} + +void test_extra_get_target_coordinate_positions_malformed_emits_empty() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("", dispatch("GC", h)); +} + +void test_extra_get_auto_homing_states_text() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("RA:Idle,DEC:Idle#", dispatch("GAH", h)); +} + +void test_extra_get_log_buffer_literal_no_terminator() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("abc", dispatch("GO", h)); +} + +void test_extra_get_ra_homing_offset_long() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("-10#", dispatch("GHR", h)); +} + +void test_extra_get_hemisphere_returns_hemisphere_format() +{ + FakeExtra h; + h.northern = true; + TEST_ASSERT_EQUAL_STRING("N#", dispatch("GHS", h)); +} + +void test_extra_get_hour_angle_compact_hms() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("030405#", dispatch("GH", h)); +} + +void test_extra_get_local_sidereal_time_compact_hms() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("060708#", dispatch("GL", h)); +} + +void test_extra_get_network_status_text() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("WL,OAT,192.168.1.10#", dispatch("GN", h)); +} + +// ---- Set leaves ------------------------------------------------------------- + +void test_extra_set_ra_steps_per_degree_emits_empty_and_captures_value() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("", dispatch("SR123.5", h)); + TEST_ASSERT_EQUAL_FLOAT(123.5f, h.setRaSpd); +} + +void test_extra_set_dec_steps_per_degree_zero_value_skipped() +{ + FakeExtra h; + h.setDecSpd = -1.0f; + TEST_ASSERT_EQUAL_STRING("", dispatch("SD0", h)); + // Legacy: only positive values are committed; sentinel stays unchanged. + TEST_ASSERT_EQUAL_FLOAT(-1.0f, h.setDecSpd); +} + +void test_extra_set_dec_limit_lower_with_payload() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("", dispatch("SDLL-25.5", h)); + TEST_ASSERT_TRUE(h.decLimitLowerPayload); + TEST_ASSERT_EQUAL_FLOAT(-25.5f, h.decLimitLowerVal); +} + +void test_extra_set_dec_limit_lower_without_payload_uses_current_position() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("", dispatch("SDLL", h)); + TEST_ASSERT_FALSE(h.decLimitLowerPayload); +} + +void test_extra_set_dec_limit_lower_clear_invokes_clear() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("", dispatch("SDLl", h)); + TEST_ASSERT_TRUE(h.clearLowerCalled); +} + +void test_extra_set_manual_slew_mode_one_enables() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("", dispatch("SM1", h)); + TEST_ASSERT_TRUE(h.setManualSlew); +} + +void test_extra_set_manual_slew_mode_zero_disables() +{ + FakeExtra h; + h.setManualSlew = true; + TEST_ASSERT_EQUAL_STRING("", dispatch("SM0", h)); + TEST_ASSERT_FALSE(h.setManualSlew); +} + +void test_extra_set_backlash_correction_captures_int() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("", dispatch("SB42", h)); + TEST_ASSERT_EQUAL_INT(42, h.setBacklash); +} + +void test_extra_set_dec_parking_is_no_op_but_emits_empty() +{ + FakeExtra h; + TEST_ASSERT_EQUAL_STRING("", dispatch("SDP", h)); +} + +// ---- Level leaves ----------------------------------------------------------- + +void test_extra_level_unavailable_returns_zero_terminator() +{ + FakeExtra h; + h.levelAvailable = false; + TEST_ASSERT_EQUAL_STRING("0#", dispatch("LGC", h)); + TEST_ASSERT_FALSE(h.startupCalled); +} + +void test_extra_level_startup_returns_one_terminator_when_available() +{ + FakeExtra h; + h.levelAvailable = true; + TEST_ASSERT_EQUAL_STRING("1#", dispatch("L1", h)); + TEST_ASSERT_TRUE(h.startupCalled); +} + +void test_extra_level_shutdown_returns_one_terminator_when_available() +{ + FakeExtra h; + h.levelAvailable = true; + TEST_ASSERT_EQUAL_STRING("1#", dispatch("L0", h)); + TEST_ASSERT_TRUE(h.shutdownCalled); +} + +void test_extra_level_get_temperature_numeric_float_when_available() +{ + FakeExtra h; + h.levelAvailable = true; + h.gyroTemperature = 23.5f; + TEST_ASSERT_EQUAL_STRING("23.5#", dispatch("LGT", h)); +} + +} // namespace + +void register_meade_extra_tests() +{ + RUN_TEST(test_extra_factory_reset_emits_one_terminator_and_calls_handler); + RUN_TEST(test_extra_drift_alignment_emits_empty_and_passes_duration_minus_three); + RUN_TEST(test_extra_unknown_family_emits_empty); + RUN_TEST(test_extra_empty_suffix_emits_empty); + RUN_TEST(test_extra_get_ra_steps_per_degree_numeric_float_one_decimal); + RUN_TEST(test_extra_get_dec_limit_both_pipe_pair); + RUN_TEST(test_extra_get_dec_limit_lower_only_uses_lo_value); + RUN_TEST(test_extra_get_dec_limit_upper_only_uses_hi_value); + RUN_TEST(test_extra_get_dec_limit_invalid_variant_fixed_false); + RUN_TEST(test_extra_get_dec_parking_fixed_false); + RUN_TEST(test_extra_get_backlash_steps_int); + RUN_TEST(test_extra_get_az_alt_positions_long_pair_pipe); + RUN_TEST(test_extra_get_target_coordinate_positions_parses_payload); + RUN_TEST(test_extra_get_target_coordinate_positions_malformed_emits_empty); + RUN_TEST(test_extra_get_auto_homing_states_text); + RUN_TEST(test_extra_get_log_buffer_literal_no_terminator); + RUN_TEST(test_extra_get_ra_homing_offset_long); + RUN_TEST(test_extra_get_hemisphere_returns_hemisphere_format); + RUN_TEST(test_extra_get_hour_angle_compact_hms); + RUN_TEST(test_extra_get_local_sidereal_time_compact_hms); + RUN_TEST(test_extra_get_network_status_text); + RUN_TEST(test_extra_set_ra_steps_per_degree_emits_empty_and_captures_value); + RUN_TEST(test_extra_set_dec_steps_per_degree_zero_value_skipped); + RUN_TEST(test_extra_set_dec_limit_lower_with_payload); + RUN_TEST(test_extra_set_dec_limit_lower_without_payload_uses_current_position); + RUN_TEST(test_extra_set_dec_limit_lower_clear_invokes_clear); + RUN_TEST(test_extra_set_manual_slew_mode_one_enables); + RUN_TEST(test_extra_set_manual_slew_mode_zero_disables); + RUN_TEST(test_extra_set_backlash_correction_captures_int); + RUN_TEST(test_extra_set_dec_parking_is_no_op_but_emits_empty); + RUN_TEST(test_extra_level_unavailable_returns_zero_terminator); + RUN_TEST(test_extra_level_startup_returns_one_terminator_when_available); + RUN_TEST(test_extra_level_shutdown_returns_one_terminator_when_available); + RUN_TEST(test_extra_level_get_temperature_numeric_float_when_available); +} diff --git a/unit_tests/test_meade/test_MeadeFocus.cpp b/unit_tests/test_meade/test_MeadeFocus.cpp new file mode 100644 index 00000000..454cbe31 --- /dev/null +++ b/unit_tests/test_meade/test_MeadeFocus.cpp @@ -0,0 +1,229 @@ +// Wire-byte tests for the Meade Focus dispatcher (`handleMeadeFocus`). +// +// Covers all `:F...` sub-commands: continuous motion, MoveBy, speed-by-rate +// (digits 1-4 + F/S aliases), GetPosition, SetPosition (gated by +// onFocusIsAvailable), GetState, and Stop. + +#include + +#include "core/meade/MeadeParser.hpp" + +namespace meade = oat::core::meade; + +namespace +{ + +class FakeHandlers : public meade::IMeadeFocusHandlers +{ + public: + bool continuousIn = false; + bool continuousOut = false; + bool moveByCalled = false; + long moveBySteps = 0; + bool setSpeedCalled = false; + int setSpeedRate = 0; + bool stopCalled = false; + bool setPosCalled = false; + long setPosSteps = 0; + long position = 0; + bool available = true; + bool runningState = false; + + void onFocusContinuousIn() override + { + continuousIn = true; + } + void onFocusContinuousOut() override + { + continuousOut = true; + } + void onFocusMoveBy(long steps) override + { + moveByCalled = true; + moveBySteps = steps; + } + void onFocusSetSpeedByRate(int rate) override + { + setSpeedCalled = true; + setSpeedRate = rate; + } + void onFocusStop() override + { + stopCalled = true; + } + long onFocusGetPosition() override + { + return position; + } + bool onFocusIsAvailable() override + { + return available; + } + void onFocusSetPosition(long steps) override + { + setPosCalled = true; + setPosSteps = steps; + } + bool onFocusGetState() override + { + return runningState; + } +}; + +const char *dispatch(const char *suffix, FakeHandlers &h) +{ + static meade::MeadeResponse last; + last = meade::handleMeadeFocus(suffix, h); + return last.c_str(); +} + +} // namespace + +namespace +{ + +void test_focus_continuous_in_empty_response() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("+", h)); + TEST_ASSERT_TRUE(h.continuousIn); +} + +void test_focus_continuous_out_empty_response() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("-", h)); + TEST_ASSERT_TRUE(h.continuousOut); +} + +void test_focus_move_by_parses_signed_long() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("M-123", h)); + TEST_ASSERT_TRUE(h.moveByCalled); + TEST_ASSERT_EQUAL_INT(-123, h.moveBySteps); +} + +void test_focus_speed_by_rate_digit_1() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("1", h)); + TEST_ASSERT_TRUE(h.setSpeedCalled); + TEST_ASSERT_EQUAL_INT(1, h.setSpeedRate); +} + +void test_focus_speed_by_rate_digit_4() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("4", h)); + TEST_ASSERT_TRUE(h.setSpeedCalled); + TEST_ASSERT_EQUAL_INT(4, h.setSpeedRate); +} + +void test_focus_set_fastest_rate_F_maps_to_4() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("F", h)); + TEST_ASSERT_TRUE(h.setSpeedCalled); + TEST_ASSERT_EQUAL_INT(4, h.setSpeedRate); +} + +void test_focus_set_slowest_rate_S_maps_to_1() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("S", h)); + TEST_ASSERT_TRUE(h.setSpeedCalled); + TEST_ASSERT_EQUAL_INT(1, h.setSpeedRate); +} + +void test_focus_get_position_emits_long_with_terminator() +{ + FakeHandlers h; + h.position = 12345; + TEST_ASSERT_EQUAL_STRING("12345#", dispatch("p", h)); +} + +void test_focus_get_position_zero_emits_zero_terminator() +{ + FakeHandlers h; + h.position = 0; + TEST_ASSERT_EQUAL_STRING("0#", dispatch("p", h)); +} + +void test_focus_set_position_available_emits_one_no_terminator() +{ + FakeHandlers h; + h.available = true; + TEST_ASSERT_EQUAL_STRING("1", dispatch("P777", h)); + TEST_ASSERT_TRUE(h.setPosCalled); + TEST_ASSERT_EQUAL_INT(777, h.setPosSteps); +} + +void test_focus_set_position_unavailable_emits_empty_no_call() +{ + FakeHandlers h; + h.available = false; + TEST_ASSERT_EQUAL_STRING("", dispatch("P777", h)); + TEST_ASSERT_FALSE(h.setPosCalled); +} + +void test_focus_get_state_true_emits_one() +{ + FakeHandlers h; + h.runningState = true; + TEST_ASSERT_EQUAL_STRING("1", dispatch("B", h)); +} + +void test_focus_get_state_false_emits_zero() +{ + FakeHandlers h; + h.runningState = false; + TEST_ASSERT_EQUAL_STRING("0", dispatch("B", h)); +} + +void test_focus_stop_emits_empty() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("Q", h)); + TEST_ASSERT_TRUE(h.stopCalled); +} + +void test_focus_empty_suffix_emits_empty_no_call() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("", h)); + TEST_ASSERT_FALSE(h.continuousIn); + TEST_ASSERT_FALSE(h.continuousOut); + TEST_ASSERT_FALSE(h.moveByCalled); + TEST_ASSERT_FALSE(h.setSpeedCalled); + TEST_ASSERT_FALSE(h.stopCalled); +} + +void test_focus_unknown_suffix_emits_empty_no_call() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("Z", h)); + TEST_ASSERT_FALSE(h.setSpeedCalled); +} + +} // namespace + +void register_meade_focus_tests() +{ + RUN_TEST(test_focus_continuous_in_empty_response); + RUN_TEST(test_focus_continuous_out_empty_response); + RUN_TEST(test_focus_move_by_parses_signed_long); + RUN_TEST(test_focus_speed_by_rate_digit_1); + RUN_TEST(test_focus_speed_by_rate_digit_4); + RUN_TEST(test_focus_set_fastest_rate_F_maps_to_4); + RUN_TEST(test_focus_set_slowest_rate_S_maps_to_1); + RUN_TEST(test_focus_get_position_emits_long_with_terminator); + RUN_TEST(test_focus_get_position_zero_emits_zero_terminator); + RUN_TEST(test_focus_set_position_available_emits_one_no_terminator); + RUN_TEST(test_focus_set_position_unavailable_emits_empty_no_call); + RUN_TEST(test_focus_get_state_true_emits_one); + RUN_TEST(test_focus_get_state_false_emits_zero); + RUN_TEST(test_focus_stop_emits_empty); + RUN_TEST(test_focus_empty_suffix_emits_empty_no_call); + RUN_TEST(test_focus_unknown_suffix_emits_empty_no_call); +} diff --git a/unit_tests/test_meade/test_MeadeGet.cpp b/unit_tests/test_meade/test_MeadeGet.cpp new file mode 100644 index 00000000..0e5a2b03 --- /dev/null +++ b/unit_tests/test_meade/test_MeadeGet.cpp @@ -0,0 +1,353 @@ +// Wire-byte tests for the Meade Get-family dispatcher (`handleMeadeGet`). +// +// Each test exercises a single Meade `:G...` sub-command suffix end-to-end: +// it calls the parser entry point with a stub handler and asserts the exact +// bytes emitted on the wire. The stub records which callback fired so we +// also catch silent regressions where the wrong handler is invoked. + +#include + +#include + +#include "core/meade/MeadeParser.hpp" + +namespace meade = oat::core::meade; + +namespace +{ + +class FakeHandlers : public meade::IMeadeGetHandlers +{ + public: + const char *lastCall = nullptr; + + // ---- Defaults (overridable per test via direct member assignment) ---- + const char *firmware = "V1.2.3"; + const char *product = "OpenAstroTracker"; + const char *status = "Idle,---,0,0"; + const char *siteNames = nullptr; // when null, default OAT is returned + + meade::RaCoordinate currentRa = {1, 2, 3}; + meade::RaCoordinate targetRa = {4, 5, 6}; + meade::DecCoordinate currentDec = {7, 8, 9}; + meade::DecCoordinate targetDec = {-10, 11, 12}; + bool isSlewing = false; + bool isTracking = true; + bool isGuiding = false; + meade::MeadeLatitude latitude = {47, 30}; + meade::MeadeLongitude longitude = {-12, 30}; + int utcOffset = -5; + meade::MeadeLocalTime localTime = {14, 45, 6}; + meade::MeadeLocalDate localDate = {3, 7, 2024}; + meade::MeadeClockFormat clockFmt = meade::MeadeClockFormat::Hours24; + meade::MeadeTrackingRate trackRate = meade::MeadeTrackingRate::Sidereal; + + char siteScratch[8] = {0}; + + const char *onFirmwareVersion() override + { + lastCall = "fw"; + return firmware; + } + const char *onProductName() override + { + lastCall = "product"; + return product; + } + meade::RaCoordinate onCurrentRa() override + { + lastCall = "currentRa"; + return currentRa; + } + meade::RaCoordinate onTargetRa() override + { + lastCall = "targetRa"; + return targetRa; + } + meade::DecCoordinate onCurrentDec() override + { + lastCall = "currentDec"; + return currentDec; + } + meade::DecCoordinate onTargetDec() override + { + lastCall = "targetDec"; + return targetDec; + } + const char *onMountStatus() override + { + lastCall = "status"; + return status; + } + bool onIsSlewing() override + { + lastCall = "slewing"; + return isSlewing; + } + bool onIsTracking() override + { + lastCall = "tracking"; + return isTracking; + } + bool onIsGuiding() override + { + lastCall = "guiding"; + return isGuiding; + } + meade::MeadeLatitude onSiteLatitude() override + { + lastCall = "lat"; + return latitude; + } + meade::MeadeLongitude onSiteLongitude() override + { + lastCall = "lon"; + return longitude; + } + int onUtcOffset() override + { + lastCall = "utc"; + return utcOffset; + } + meade::MeadeLocalTime onLocalTime() override + { + lastCall = "time"; + return localTime; + } + meade::MeadeLocalDate onLocalDate() override + { + lastCall = "date"; + return localDate; + } + meade::MeadeClockFormat onClockFormat() override + { + lastCall = "clock"; + return clockFmt; + } + meade::MeadeTrackingRate onTrackingRate() override + { + lastCall = "rate"; + return trackRate; + } + const char *onSiteName(uint8_t index) override + { + lastCall = "siteName"; + if (siteNames) + { + return siteNames; + } + siteScratch[0] = 'O'; + siteScratch[1] = 'A'; + siteScratch[2] = 'T'; + siteScratch[3] = static_cast('0' + index); + siteScratch[4] = '\0'; + return siteScratch; + } +}; + +const char *dispatch(const char *suffix, FakeHandlers &h) +{ + static meade::MeadeResponse last; + last = meade::handleMeadeGet(suffix, h); + return last.c_str(); +} + +} // namespace + +namespace +{ + +void test_firmware_version_two_char_command() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("V1.2.3#", dispatch("VN", h)); + TEST_ASSERT_EQUAL_STRING("fw", h.lastCall); +} + +void test_product_name_two_char_command() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("OpenAstroTracker#", dispatch("VP", h)); + TEST_ASSERT_EQUAL_STRING("product", h.lastCall); +} + +void test_current_ra_formats_hh_mm_ss() +{ + FakeHandlers h; + h.currentRa = {14, 45, 6}; + TEST_ASSERT_EQUAL_STRING("14:45:06#", dispatch("R", h)); + TEST_ASSERT_EQUAL_STRING("currentRa", h.lastCall); +} + +void test_target_ra_formats_hh_mm_ss() +{ + FakeHandlers h; + h.targetRa = {0, 0, 0}; + TEST_ASSERT_EQUAL_STRING("00:00:00#", dispatch("r", h)); + TEST_ASSERT_EQUAL_STRING("targetRa", h.lastCall); +} + +void test_current_dec_signed_dms() +{ + FakeHandlers h; + h.currentDec = {47, 30, 15}; + TEST_ASSERT_EQUAL_STRING("+47*30'15#", dispatch("D", h)); + TEST_ASSERT_EQUAL_STRING("currentDec", h.lastCall); +} + +void test_target_dec_negative() +{ + FakeHandlers h; + h.targetDec = {-12, 45, 0}; + TEST_ASSERT_EQUAL_STRING("-12*45'00#", dispatch("d", h)); + TEST_ASSERT_EQUAL_STRING("targetDec", h.lastCall); +} + +void test_mount_status_passes_through() +{ + FakeHandlers h; + h.status = "Idle,---,0,0"; + TEST_ASSERT_EQUAL_STRING("Idle,---,0,0#", dispatch("X", h)); + TEST_ASSERT_EQUAL_STRING("status", h.lastCall); +} + +void test_is_slewing_emits_zero_one() +{ + FakeHandlers h; + h.isSlewing = true; + TEST_ASSERT_EQUAL_STRING("1#", dispatch("IS", h)); + TEST_ASSERT_EQUAL_STRING("slewing", h.lastCall); + h.isSlewing = false; + TEST_ASSERT_EQUAL_STRING("0#", dispatch("IS", h)); +} + +void test_is_tracking_emits_zero_one() +{ + FakeHandlers h; + h.isTracking = false; + TEST_ASSERT_EQUAL_STRING("0#", dispatch("IT", h)); + TEST_ASSERT_EQUAL_STRING("tracking", h.lastCall); +} + +void test_is_guiding_emits_zero_one() +{ + FakeHandlers h; + h.isGuiding = true; + TEST_ASSERT_EQUAL_STRING("1#", dispatch("IG", h)); + TEST_ASSERT_EQUAL_STRING("guiding", h.lastCall); +} + +void test_site_latitude_signed_two_digit_deg() +{ + FakeHandlers h; + h.latitude = {47, 30}; + TEST_ASSERT_EQUAL_STRING("+47*30#", dispatch("t", h)); + h.latitude = {-12, 45}; + TEST_ASSERT_EQUAL_STRING("-12*45#", dispatch("t", h)); +} + +void test_site_longitude_signed_three_digit_deg() +{ + FakeHandlers h; + h.longitude = {12, 30}; + TEST_ASSERT_EQUAL_STRING("+012*30#", dispatch("g", h)); + h.longitude = {-122, 45}; + TEST_ASSERT_EQUAL_STRING("-122*45#", dispatch("g", h)); +} + +void test_utc_offset_signs_and_pads() +{ + FakeHandlers h; + h.utcOffset = -5; + TEST_ASSERT_EQUAL_STRING("-05#", dispatch("G", h)); + h.utcOffset = 3; + TEST_ASSERT_EQUAL_STRING("+03#", dispatch("G", h)); +} + +void test_local_time_24h_format() +{ + FakeHandlers h; + h.localTime = {14, 45, 6}; + TEST_ASSERT_EQUAL_STRING("14:45:06#", dispatch("L", h)); + TEST_ASSERT_EQUAL_STRING("time", h.lastCall); +} + +void test_local_time_12h_converts_pm() +{ + FakeHandlers h; + h.localTime = {14, 45, 6}; // 14:xx -> 02:xx in 12h + TEST_ASSERT_EQUAL_STRING("02:45:06#", dispatch("a", h)); + h.localTime = {0, 30, 0}; // 00 -> 12 + TEST_ASSERT_EQUAL_STRING("12:30:00#", dispatch("a", h)); + h.localTime = {7, 8, 9}; // morning unchanged + TEST_ASSERT_EQUAL_STRING("07:08:09#", dispatch("a", h)); +} + +void test_local_date_truncates_year_to_two_digits() +{ + FakeHandlers h; + h.localDate = {3, 7, 2024}; + TEST_ASSERT_EQUAL_STRING("03/07/24#", dispatch("C", h)); + TEST_ASSERT_EQUAL_STRING("date", h.lastCall); +} + +void test_clock_format_24h() +{ + FakeHandlers h; + h.clockFmt = meade::MeadeClockFormat::Hours24; + TEST_ASSERT_EQUAL_STRING("24#", dispatch("c", h)); + h.clockFmt = meade::MeadeClockFormat::Hours12; + TEST_ASSERT_EQUAL_STRING("12#", dispatch("c", h)); +} + +void test_tracking_rate_sidereal() +{ + FakeHandlers h; + h.trackRate = meade::MeadeTrackingRate::Sidereal; + TEST_ASSERT_EQUAL_STRING("60.0#", dispatch("T", h)); +} + +void test_site_name_slots_invoke_handler_with_index() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("OAT1#", dispatch("M", h)); + TEST_ASSERT_EQUAL_STRING("OAT2#", dispatch("N", h)); + TEST_ASSERT_EQUAL_STRING("OAT3#", dispatch("O", h)); + TEST_ASSERT_EQUAL_STRING("OAT4#", dispatch("P", h)); + TEST_ASSERT_EQUAL_STRING("siteName", h.lastCall); +} + +void test_unknown_suffix_returns_empty() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("ZZ", h)); + TEST_ASSERT_EQUAL_STRING("", dispatch("Q", h)); + TEST_ASSERT_EQUAL_STRING("", dispatch("", h)); + TEST_ASSERT_NULL(h.lastCall); +} + +} // namespace + +void register_meade_get_tests() +{ + RUN_TEST(test_firmware_version_two_char_command); + RUN_TEST(test_product_name_two_char_command); + RUN_TEST(test_current_ra_formats_hh_mm_ss); + RUN_TEST(test_target_ra_formats_hh_mm_ss); + RUN_TEST(test_current_dec_signed_dms); + RUN_TEST(test_target_dec_negative); + RUN_TEST(test_mount_status_passes_through); + RUN_TEST(test_is_slewing_emits_zero_one); + RUN_TEST(test_is_tracking_emits_zero_one); + RUN_TEST(test_is_guiding_emits_zero_one); + RUN_TEST(test_site_latitude_signed_two_digit_deg); + RUN_TEST(test_site_longitude_signed_three_digit_deg); + RUN_TEST(test_utc_offset_signs_and_pads); + RUN_TEST(test_local_time_24h_format); + RUN_TEST(test_local_time_12h_converts_pm); + RUN_TEST(test_local_date_truncates_year_to_two_digits); + RUN_TEST(test_clock_format_24h); + RUN_TEST(test_tracking_rate_sidereal); + RUN_TEST(test_site_name_slots_invoke_handler_with_index); + RUN_TEST(test_unknown_suffix_returns_empty); +} diff --git a/unit_tests/test_meade/test_MeadeGps.cpp b/unit_tests/test_meade/test_MeadeGps.cpp new file mode 100644 index 00000000..60da5ecb --- /dev/null +++ b/unit_tests/test_meade/test_MeadeGps.cpp @@ -0,0 +1,94 @@ +// Wire-byte tests for the Meade GPS dispatcher (`handleMeadeGps`). +// +// `:gT#` invokes onStartGpsAcquisition with the payload bytes and +// emits "1" on success / "0" on timeout. Any other suffix emits "0" without +// invoking the handler. + +#include + +#include + +#include "core/meade/MeadeParser.hpp" + +namespace meade = oat::core::meade; + +namespace +{ + +class FakeHandlers : public meade::IMeadeGpsHandlers +{ + public: + bool nextResult = false; + bool called = false; + char lastPayload[64] = {0}; + + bool onStartGpsAcquisition(const char *timeoutPayload) override + { + called = true; + std::strncpy(lastPayload, timeoutPayload ? timeoutPayload : "", sizeof(lastPayload) - 1); + return nextResult; + } +}; + +const char *dispatch(const char *suffix, FakeHandlers &h) +{ + static meade::MeadeResponse last; + last = meade::handleMeadeGps(suffix, h); + return last.c_str(); +} + +} // namespace + +namespace +{ + +void test_gps_t_success_emits_one() +{ + FakeHandlers h; + h.nextResult = true; + TEST_ASSERT_EQUAL_STRING("1", dispatch("T", h)); + TEST_ASSERT_TRUE(h.called); + TEST_ASSERT_EQUAL_STRING("", h.lastPayload); +} + +void test_gps_t_failure_emits_zero() +{ + FakeHandlers h; + h.nextResult = false; + TEST_ASSERT_EQUAL_STRING("0", dispatch("T", h)); + TEST_ASSERT_TRUE(h.called); +} + +void test_gps_t_with_payload_forwards_payload() +{ + FakeHandlers h; + h.nextResult = true; + TEST_ASSERT_EQUAL_STRING("1", dispatch("T120000", h)); + TEST_ASSERT_TRUE(h.called); + TEST_ASSERT_EQUAL_STRING("120000", h.lastPayload); +} + +void test_gps_unknown_suffix_emits_zero_no_call() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", dispatch("Q", h)); + TEST_ASSERT_FALSE(h.called); +} + +void test_gps_empty_suffix_emits_zero_no_call() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", dispatch("", h)); + TEST_ASSERT_FALSE(h.called); +} + +} // namespace + +void register_meade_gps_tests() +{ + RUN_TEST(test_gps_t_success_emits_one); + RUN_TEST(test_gps_t_failure_emits_zero); + RUN_TEST(test_gps_t_with_payload_forwards_payload); + RUN_TEST(test_gps_unknown_suffix_emits_zero_no_call); + RUN_TEST(test_gps_empty_suffix_emits_zero_no_call); +} diff --git a/unit_tests/test_meade/test_MeadeHome.cpp b/unit_tests/test_meade/test_MeadeHome.cpp new file mode 100644 index 00000000..6b1d13b0 --- /dev/null +++ b/unit_tests/test_meade/test_MeadeHome.cpp @@ -0,0 +1,111 @@ +// Wire-byte tests for the Meade Home dispatcher (`handleMeadeHome`). +// +// `:hP#`/`:hF#` perform park/slew-to-home and emit an empty response. +// `:hU#`/`:hZ#` unpark / set the Az/Alt home and emit `"1"`. Any other +// suffix is ignored and produces an empty response. + +#include + +#include "core/meade/MeadeParser.hpp" + +namespace meade = oat::core::meade; + +namespace +{ + +class FakeHandlers : public meade::IMeadeHomeHandlers +{ + public: + const char *lastCall = ""; + + void onPark() override + { + lastCall = "park"; + } + void onSlewToHome() override + { + lastCall = "home"; + } + void onUnpark() override + { + lastCall = "unpark"; + } + void onSetAzAltHome() override + { + lastCall = "azalt"; + } +}; + +const char *dispatch(const char *suffix, FakeHandlers &h) +{ + static meade::MeadeResponse last; + last = meade::handleMeadeHome(suffix, h); + return last.c_str(); +} + +} // namespace + +namespace +{ + +void test_home_p_parks_and_emits_empty() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("P", h)); + TEST_ASSERT_EQUAL_STRING("park", h.lastCall); +} + +void test_home_f_slews_home_and_emits_empty() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("F", h)); + TEST_ASSERT_EQUAL_STRING("home", h.lastCall); +} + +void test_home_u_unparks_and_emits_one() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("U", h)); + TEST_ASSERT_EQUAL_STRING("unpark", h.lastCall); +} + +void test_home_z_sets_azalt_and_emits_one() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("Z", h)); + TEST_ASSERT_EQUAL_STRING("azalt", h.lastCall); +} + +void test_home_unknown_suffix_emits_empty() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("Q", h)); + TEST_ASSERT_EQUAL_STRING("", h.lastCall); +} + +void test_home_empty_suffix_emits_empty() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("", h)); + TEST_ASSERT_EQUAL_STRING("", h.lastCall); +} + +void test_home_trailing_bytes_do_not_call_handler() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("Px", h)); + TEST_ASSERT_EQUAL_STRING("", h.lastCall); +} + +} // namespace + +void register_meade_home_tests() +{ + RUN_TEST(test_home_p_parks_and_emits_empty); + RUN_TEST(test_home_f_slews_home_and_emits_empty); + RUN_TEST(test_home_u_unparks_and_emits_one); + RUN_TEST(test_home_z_sets_azalt_and_emits_one); + RUN_TEST(test_home_unknown_suffix_emits_empty); + RUN_TEST(test_home_empty_suffix_emits_empty); + RUN_TEST(test_home_trailing_bytes_do_not_call_handler); +} diff --git a/unit_tests/test_meade/test_MeadeInit.cpp b/unit_tests/test_meade/test_MeadeInit.cpp new file mode 100644 index 00000000..8017380e --- /dev/null +++ b/unit_tests/test_meade/test_MeadeInit.cpp @@ -0,0 +1,56 @@ +// Wire-byte tests for the Meade Init dispatcher (`handleMeadeInit`). +// +// `:I#` hands UI over to serial control; the wire response is empty. + +#include + +#include "core/meade/MeadeParser.hpp" + +namespace meade = oat::core::meade; + +namespace +{ + +class FakeHandlers : public meade::IMeadeInitHandlers +{ + public: + int callCount = 0; + void onEnterSerialControl() override + { + ++callCount; + } +}; + +const char *dispatch(const char *suffix, FakeHandlers &h) +{ + static meade::MeadeResponse last; + last = meade::handleMeadeInit(suffix, h); + return last.c_str(); +} + +} // namespace + +namespace +{ + +void test_init_empty_response() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("", h)); + TEST_ASSERT_EQUAL_INT(1, h.callCount); +} + +void test_init_ignores_suffix() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("xyz", h)); + TEST_ASSERT_EQUAL_INT(1, h.callCount); +} + +} // namespace + +void register_meade_init_tests() +{ + RUN_TEST(test_init_empty_response); + RUN_TEST(test_init_ignores_suffix); +} diff --git a/unit_tests/test_meade/test_MeadeMovement.cpp b/unit_tests/test_meade/test_MeadeMovement.cpp new file mode 100644 index 00000000..b5319db8 --- /dev/null +++ b/unit_tests/test_meade/test_MeadeMovement.cpp @@ -0,0 +1,361 @@ +// Wire-byte tests for the Meade Movement dispatcher (`handleMeadeMovement`). +// +// Covers all `:M...` sub-commands: SlewToTarget, TrackingToggle, GuidePulse, +// MoveAzAltHome, axis-nudge (AZ/AL), continuous slews (e/w/n/s), MoveStepper +// (X), and Hall-sensor auto-home (HR/HD). + +#include + +#include "core/meade/MeadeParser.hpp" + +namespace meade = oat::core::meade; + +namespace +{ + +class FakeHandlers : public meade::IMeadeMovementHandlers +{ + public: + int slewToTargetCalls = 0; + int trackingOnCalls = 0; + int trackingOffCalls = 0; + + int guidePulseCalls = 0; + meade::MoveDirection lastDir = meade::MoveDirection::East; + int lastDurationMs = 0; + + int azAltHomeCalls = 0; + int azCalls = 0; + float lastAzArc = 0.0f; + int alCalls = 0; + float lastAlArc = 0.0f; + + int slewE = 0, slewW = 0, slewN = 0, slewS = 0; + + int moveStepperCalls = 0; + meade::MovementAxis lastAxis = meade::MovementAxis::Ra; + long lastSteps = 0; + + int homeRaCalls = 0; + int homeDecCalls = 0; + int lastHomeRaDirection = 0; + int lastHomeDecDirection = 0; + const char *lastRaPayload = nullptr; + const char *lastDecPayload = nullptr; + bool homeRaResult = true; + bool homeDecResult = true; + + void onStartSlewToTarget() override + { + ++slewToTargetCalls; + } + void onTrackingOn() override + { + ++trackingOnCalls; + } + void onTrackingOff() override + { + ++trackingOffCalls; + } + void onGuidePulse(meade::MoveDirection dir, int durationMs) override + { + ++guidePulseCalls; + lastDir = dir; + lastDurationMs = durationMs; + } + void onMoveAzAltHome() override + { + ++azAltHomeCalls; + } + void onMoveAzimuth(float arcMinutes) override + { + ++azCalls; + lastAzArc = arcMinutes; + } + void onMoveAltitude(float arcMinutes) override + { + ++alCalls; + lastAlArc = arcMinutes; + } + void onSlewEast() override + { + ++slewE; + } + void onSlewWest() override + { + ++slewW; + } + void onSlewNorth() override + { + ++slewN; + } + void onSlewSouth() override + { + ++slewS; + } + void onMoveStepper(meade::MovementAxis axis, long steps) override + { + ++moveStepperCalls; + lastAxis = axis; + lastSteps = steps; + } + bool onHomeRa(int direction, const char *distancePayload) override + { + ++homeRaCalls; + lastHomeRaDirection = direction; + lastRaPayload = distancePayload; + return homeRaResult; + } + bool onHomeDec(int direction, const char *distancePayload) override + { + ++homeDecCalls; + lastHomeDecDirection = direction; + lastDecPayload = distancePayload; + return homeDecResult; + } +}; + +meade::MeadeResponse run(const char *suffix, FakeHandlers &h) +{ + return meade::handleMeadeMovement(suffix, h); +} + +} // namespace + +namespace +{ + +void test_empty_or_null_suffix_returns_empty(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", run("", h).c_str()); + TEST_ASSERT_EQUAL_STRING("", run(nullptr, h).c_str()); + TEST_ASSERT_EQUAL_INT(0, h.slewToTargetCalls); +} + +void test_slew_to_target_emits_zero_and_calls_handler(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", run("S", h).c_str()); + TEST_ASSERT_EQUAL_INT(1, h.slewToTargetCalls); +} + +void test_slew_with_trailing_bytes_is_unknown(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", run("S123", h).c_str()); + TEST_ASSERT_EQUAL_INT(0, h.slewToTargetCalls); +} + +void test_tracking_on(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", run("T1", h).c_str()); + TEST_ASSERT_EQUAL_INT(1, h.trackingOnCalls); +} + +void test_tracking_off(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", run("T0", h).c_str()); + TEST_ASSERT_EQUAL_INT(1, h.trackingOffCalls); +} + +void test_tracking_bare_or_bad_byte_emits_zero(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", run("T", h).c_str()); + TEST_ASSERT_EQUAL_STRING("0", run("T2", h).c_str()); + TEST_ASSERT_EQUAL_INT(0, h.trackingOnCalls); + TEST_ASSERT_EQUAL_INT(0, h.trackingOffCalls); +} + +void test_guide_pulse_lowercase_directions(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", run("Gn0403", h).c_str()); + TEST_ASSERT_EQUAL_INT(1, h.guidePulseCalls); + TEST_ASSERT_EQUAL_INT(static_cast(meade::MoveDirection::North), static_cast(h.lastDir)); + TEST_ASSERT_EQUAL_INT(403, h.lastDurationMs); + + TEST_ASSERT_EQUAL_STRING("", run("gs0100", h).c_str()); + TEST_ASSERT_EQUAL_INT(static_cast(meade::MoveDirection::South), static_cast(h.lastDir)); + TEST_ASSERT_EQUAL_INT(100, h.lastDurationMs); + + TEST_ASSERT_EQUAL_STRING("", run("Ge0001", h).c_str()); + TEST_ASSERT_EQUAL_INT(static_cast(meade::MoveDirection::East), static_cast(h.lastDir)); + TEST_ASSERT_EQUAL_INT(1, h.lastDurationMs); + + TEST_ASSERT_EQUAL_STRING("", run("GW9999", h).c_str()); + TEST_ASSERT_EQUAL_INT(static_cast(meade::MoveDirection::West), static_cast(h.lastDir)); + TEST_ASSERT_EQUAL_INT(9999, h.lastDurationMs); +} + +void test_guide_pulse_uppercase_direction_accepted(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", run("GN0500", h).c_str()); + TEST_ASSERT_EQUAL_INT(static_cast(meade::MoveDirection::North), static_cast(h.lastDir)); + TEST_ASSERT_EQUAL_INT(500, h.lastDurationMs); +} + +void test_guide_pulse_unknown_direction_defaults_to_east(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", run("Gx0123", h).c_str()); + TEST_ASSERT_EQUAL_INT(1, h.guidePulseCalls); + TEST_ASSERT_EQUAL_INT(static_cast(meade::MoveDirection::East), static_cast(h.lastDir)); +} + +void test_guide_pulse_malformed_emits_zero(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", run("Gn040", h).c_str()); // too short + TEST_ASSERT_EQUAL_STRING("0", run("Gn04030", h).c_str()); // too long + TEST_ASSERT_EQUAL_STRING("0", run("Gn04A3", h).c_str()); // non-digit + TEST_ASSERT_EQUAL_INT(0, h.guidePulseCalls); +} + +void test_move_az_alt_home(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", run("AA", h).c_str()); + TEST_ASSERT_EQUAL_INT(1, h.azAltHomeCalls); +} + +void test_move_azimuth(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", run("AZ+32.5", h).c_str()); + TEST_ASSERT_EQUAL_INT(1, h.azCalls); + TEST_ASSERT_FLOAT_WITHIN(0.001f, 32.5f, h.lastAzArc); +} + +void test_move_altitude(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", run("AL-12.25", h).c_str()); + TEST_ASSERT_EQUAL_INT(1, h.alCalls); + TEST_ASSERT_FLOAT_WITHIN(0.001f, -12.25f, h.lastAlArc); +} + +void test_continuous_slew_shortcuts(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", run("e", h).c_str()); + TEST_ASSERT_EQUAL_STRING("", run("w", h).c_str()); + TEST_ASSERT_EQUAL_STRING("", run("n", h).c_str()); + TEST_ASSERT_EQUAL_STRING("", run("s", h).c_str()); + TEST_ASSERT_EQUAL_INT(1, h.slewE); + TEST_ASSERT_EQUAL_INT(1, h.slewW); + TEST_ASSERT_EQUAL_INT(1, h.slewN); + TEST_ASSERT_EQUAL_INT(1, h.slewS); +} + +void test_move_stepper_each_axis(void) +{ + struct Case { + const char *suffix; + meade::MovementAxis axis; + long steps; + }; + static const Case cases[] = { + {"Xr1000", meade::MovementAxis::Ra, 1000}, + {"Xd-250", meade::MovementAxis::Dec, -250}, + {"Xz42", meade::MovementAxis::Azimuth, 42}, + {"Xl0", meade::MovementAxis::Altitude, 0}, + {"Xf-7", meade::MovementAxis::Focus, -7}, + }; + for (auto &c : cases) + { + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", run(c.suffix, h).c_str()); + TEST_ASSERT_EQUAL_INT(1, h.moveStepperCalls); + TEST_ASSERT_EQUAL_INT(static_cast(c.axis), static_cast(h.lastAxis)); + TEST_ASSERT_EQUAL_INT(c.steps, h.lastSteps); + } +} + +void test_move_stepper_invalid_axis_returns_zero(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", run("Xq500", h).c_str()); + TEST_ASSERT_EQUAL_STRING("0", run("X", h).c_str()); + TEST_ASSERT_EQUAL_INT(0, h.moveStepperCalls); +} + +void test_home_ra_directions(void) +{ + FakeHandlers h; + h.homeRaResult = true; + TEST_ASSERT_EQUAL_STRING("1", run("HRR30", h).c_str()); + TEST_ASSERT_EQUAL_INT(1, h.homeRaCalls); + TEST_ASSERT_EQUAL_INT(-1, h.lastHomeRaDirection); + TEST_ASSERT_EQUAL_STRING("30", h.lastRaPayload); + + TEST_ASSERT_EQUAL_STRING("1", run("HRL", h).c_str()); + TEST_ASSERT_EQUAL_INT(2, h.homeRaCalls); + TEST_ASSERT_EQUAL_INT(1, h.lastHomeRaDirection); + TEST_ASSERT_EQUAL_STRING("", h.lastRaPayload); +} + +void test_home_ra_bad_direction_emits_zero_without_calling(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", run("HR", h).c_str()); + TEST_ASSERT_EQUAL_STRING("0", run("HRX", h).c_str()); + TEST_ASSERT_EQUAL_INT(0, h.homeRaCalls); +} + +void test_home_dec_directions(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", run("HDU45", h).c_str()); + TEST_ASSERT_EQUAL_INT(1, h.lastHomeDecDirection); + TEST_ASSERT_EQUAL_STRING("45", h.lastDecPayload); + + TEST_ASSERT_EQUAL_STRING("1", run("HDD", h).c_str()); + TEST_ASSERT_EQUAL_INT(-1, h.lastHomeDecDirection); +} + +void test_home_dec_handler_failure_propagates(void) +{ + FakeHandlers h; + h.homeDecResult = false; + TEST_ASSERT_EQUAL_STRING("0", run("HDU10", h).c_str()); + TEST_ASSERT_EQUAL_INT(1, h.homeDecCalls); +} + +void test_unknown_suffix_returns_empty(void) +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", run("Q", h).c_str()); + TEST_ASSERT_EQUAL_STRING("", run("Z123", h).c_str()); +} + +} // namespace + +void register_meade_movement_tests() +{ + RUN_TEST(test_empty_or_null_suffix_returns_empty); + RUN_TEST(test_slew_to_target_emits_zero_and_calls_handler); + RUN_TEST(test_slew_with_trailing_bytes_is_unknown); + RUN_TEST(test_tracking_on); + RUN_TEST(test_tracking_off); + RUN_TEST(test_tracking_bare_or_bad_byte_emits_zero); + RUN_TEST(test_guide_pulse_lowercase_directions); + RUN_TEST(test_guide_pulse_uppercase_direction_accepted); + RUN_TEST(test_guide_pulse_unknown_direction_defaults_to_east); + RUN_TEST(test_guide_pulse_malformed_emits_zero); + RUN_TEST(test_move_az_alt_home); + RUN_TEST(test_move_azimuth); + RUN_TEST(test_move_altitude); + RUN_TEST(test_continuous_slew_shortcuts); + RUN_TEST(test_move_stepper_each_axis); + RUN_TEST(test_move_stepper_invalid_axis_returns_zero); + RUN_TEST(test_home_ra_directions); + RUN_TEST(test_home_ra_bad_direction_emits_zero_without_calling); + RUN_TEST(test_home_dec_directions); + RUN_TEST(test_home_dec_handler_failure_propagates); + RUN_TEST(test_unknown_suffix_returns_empty); +} diff --git a/unit_tests/test_meade/test_MeadeParser.cpp b/unit_tests/test_meade/test_MeadeParser.cpp new file mode 100644 index 00000000..c899bd83 --- /dev/null +++ b/unit_tests/test_meade/test_MeadeParser.cpp @@ -0,0 +1,121 @@ +#include + +#include "core/meade/MeadeParser.hpp" + +namespace meade = oat::core::meade; + +using meade::MeadeParseResult; +using meade::parseMeadeCommand; + +namespace +{ + +void assert_invalid_parse(const char *input) +{ + MeadeParseResult result = parseMeadeCommand(input); + TEST_ASSERT_FALSE(result.valid); + TEST_ASSERT_EQUAL_CHAR('\0', result.family); + TEST_ASSERT_TRUE(result.payload.empty()); +} + +void assert_valid_parse(const char *input, char expected_family, const char *expected_payload) +{ + MeadeParseResult result = parseMeadeCommand(input); + TEST_ASSERT_TRUE(result.valid); + TEST_ASSERT_EQUAL_CHAR(expected_family, result.family); + TEST_ASSERT_EQUAL_STRING(expected_payload, result.payload.c_str()); +} + +void test_meade_parser_rejects_empty_and_too_short_inputs(void) +{ + assert_invalid_parse(""); + assert_invalid_parse(":"); +} + +void test_meade_parser_rejects_missing_colon(void) +{ + assert_invalid_parse("GR#"); +} + +void test_meade_parser_returns_family_and_payload_for_get_ra(void) +{ + MeadeParseResult result = parseMeadeCommand(":GR#"); + TEST_ASSERT_TRUE(result.valid); + TEST_ASSERT_EQUAL_CHAR('G', result.family); + TEST_ASSERT_EQUAL_STRING("R", result.payload.c_str()); +} + +void test_meade_parser_strips_spaces_and_trailing_hash(void) +{ + MeadeParseResult result = parseMeadeCommand(": G R #"); + TEST_ASSERT_TRUE(result.valid); + TEST_ASSERT_EQUAL_CHAR('G', result.family); + TEST_ASSERT_EQUAL_STRING("R", result.payload.c_str()); +} + +void test_meade_parser_preserves_payload_for_quit_command(void) +{ + MeadeParseResult result = parseMeadeCommand(":Qq#"); + TEST_ASSERT_TRUE(result.valid); + TEST_ASSERT_EQUAL_CHAR('Q', result.family); + TEST_ASSERT_EQUAL_STRING("q", result.payload.c_str()); +} + +void test_meade_parser_accepts_command_without_trailing_hash(void) +{ + MeadeParseResult result = parseMeadeCommand(":MS"); + TEST_ASSERT_TRUE(result.valid); + TEST_ASSERT_EQUAL_CHAR('M', result.family); + TEST_ASSERT_EQUAL_STRING("S", result.payload.c_str()); +} + +void test_meade_parser_classifies_all_top_level_families(void) +{ + struct ParseCase { + const char *input; + char family; + const char *payload; + }; + + static const ParseCase parse_cases[] = { + {":Sd+12*34:56#", 'S', "d+12*34:56"}, + {":MS#", 'M', "S"}, + {":GR#", 'G', "R"}, + {":gT#", 'g', "T"}, + {":CM#", 'C', "M"}, + {":hP#", 'h', "P"}, + {":I#", 'I', ""}, + {":Qq#", 'Q', "q"}, + {":RS#", 'R', "S"}, + {":D#", 'D', ""}, + {":XFR#", 'X', "FR"}, + {":F+#", 'F', "+"}, + }; + + for (unsigned int index = 0; index < (sizeof(parse_cases) / sizeof(parse_cases[0])); ++index) + { + assert_valid_parse(parse_cases[index].input, parse_cases[index].family, parse_cases[index].payload); + } +} + +void test_meade_parser_rejects_unknown_top_level_family(void) +{ + MeadeParseResult result = parseMeadeCommand(":Z12#"); + TEST_ASSERT_FALSE(result.valid); + TEST_ASSERT_EQUAL_CHAR('\0', result.family); + TEST_ASSERT_TRUE(result.payload.empty()); +} + +} // namespace + +void register_meade_parser_tests() +{ + RUN_TEST(test_meade_parser_rejects_empty_and_too_short_inputs); + RUN_TEST(test_meade_parser_rejects_missing_colon); + RUN_TEST(test_meade_parser_returns_family_and_payload_for_get_ra); + RUN_TEST(test_meade_parser_strips_spaces_and_trailing_hash); + RUN_TEST(test_meade_parser_preserves_payload_for_quit_command); + RUN_TEST(test_meade_parser_accepts_command_without_trailing_hash); + RUN_TEST(test_meade_parser_classifies_all_top_level_families); + RUN_TEST(test_meade_parser_rejects_unknown_top_level_family); +} diff --git a/unit_tests/test_meade/test_MeadeQuit.cpp b/unit_tests/test_meade/test_MeadeQuit.cpp new file mode 100644 index 00000000..933ed341 --- /dev/null +++ b/unit_tests/test_meade/test_MeadeQuit.cpp @@ -0,0 +1,142 @@ +// Wire-byte tests for the Meade Quit-family dispatcher (`handleMeadeQuit`). +// +// Every Quit sub-command emits an empty wire response; the test value lives +// in which handler callback fires, captured by `FakeHandlers`. Unknown +// sub-commands must NOT invoke any callback. + +#include + +#include + +#include "core/meade/MeadeParser.hpp" + +namespace meade = oat::core::meade; + +namespace +{ + +class FakeHandlers : public meade::IMeadeQuitHandlers +{ + public: + const char *lastCall = nullptr; + + void onStopAll() override + { + lastCall = "all"; + } + void onStopDirectionalAll() override + { + lastCall = "directional"; + } + void onStopEast() override + { + lastCall = "east"; + } + void onStopWest() override + { + lastCall = "west"; + } + void onStopNorth() override + { + lastCall = "north"; + } + void onStopSouth() override + { + lastCall = "south"; + } + void onQuitControlMode() override + { + lastCall = "quitControl"; + } +}; + +const char *dispatch(const char *suffix, FakeHandlers &h) +{ + static meade::MeadeResponse last; + last = meade::handleMeadeQuit(suffix, h); + return last.c_str(); +} + +} // namespace + +namespace +{ + +void test_empty_suffix_stops_all() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("", h)); + TEST_ASSERT_EQUAL_STRING("all", h.lastCall); +} + +void test_a_suffix_stops_directional_all() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("a", h)); + TEST_ASSERT_EQUAL_STRING("directional", h.lastCall); +} + +void test_e_suffix_stops_east() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("e", h)); + TEST_ASSERT_EQUAL_STRING("east", h.lastCall); +} + +void test_w_suffix_stops_west() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("w", h)); + TEST_ASSERT_EQUAL_STRING("west", h.lastCall); +} + +void test_n_suffix_stops_north() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("n", h)); + TEST_ASSERT_EQUAL_STRING("north", h.lastCall); +} + +void test_s_suffix_stops_south() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("s", h)); + TEST_ASSERT_EQUAL_STRING("south", h.lastCall); +} + +void test_q_suffix_quits_control_mode() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("q", h)); + TEST_ASSERT_EQUAL_STRING("quitControl", h.lastCall); +} + +void test_unknown_suffix_does_not_call_handler() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("z", h)); + TEST_ASSERT_NULL(h.lastCall); +} + +void test_multi_char_suffix_does_not_call_handler() +{ + FakeHandlers h; + // Single-char commands only; "ea" is not a valid stop-east. + TEST_ASSERT_EQUAL_STRING("", dispatch("ea", h)); + TEST_ASSERT_NULL(h.lastCall); +} + +} // namespace + +void register_meade_quit_tests() +{ + RUN_TEST(test_empty_suffix_stops_all); + RUN_TEST(test_a_suffix_stops_directional_all); + RUN_TEST(test_e_suffix_stops_east); + RUN_TEST(test_w_suffix_stops_west); + RUN_TEST(test_n_suffix_stops_north); + RUN_TEST(test_s_suffix_stops_south); + RUN_TEST(test_q_suffix_quits_control_mode); + RUN_TEST(test_unknown_suffix_does_not_call_handler); + RUN_TEST(test_multi_char_suffix_does_not_call_handler); +} diff --git a/unit_tests/test_meade/test_MeadeSet.cpp b/unit_tests/test_meade/test_MeadeSet.cpp new file mode 100644 index 00000000..e771a51b --- /dev/null +++ b/unit_tests/test_meade/test_MeadeSet.cpp @@ -0,0 +1,436 @@ +// Wire-byte tests for the Meade Set-family dispatcher (`handleMeadeSet`). +// +// Each test exercises a single Meade `:S...` (or sync `:SY...`) sub-command +// suffix end-to-end: it calls the dispatcher with a stub handler and asserts +// the exact bytes emitted on the wire, plus the typed values the handler +// observed. The stub records which callback fired so we also catch silent +// regressions where the wrong handler is invoked. + +#include + +#include + +#include "core/meade/MeadeParser.hpp" + +namespace meade = oat::core::meade; + +namespace +{ + +class FakeHandlers : public meade::IMeadeSetHandlers +{ + public: + const char *lastCall = nullptr; + + // ---- Configurable return values -------------------------------------- + bool nextResult = true; // What every onSet* returns by default. + + // ---- Captured arguments --------------------------------------------- + meade::DecCoordinate dec {}; + meade::RaCoordinate ra {}; + meade::MeadeLocalTime lst {}; + uint8_t haHours = 0; + uint8_t haMinutes = 0; + meade::DecCoordinate syncDec {}; + meade::RaCoordinate syncRa {}; + meade::MeadeLatitude lat {}; + meade::MeadeLongitude lon {}; + int utc = 0; + meade::MeadeLocalTime time {}; + meade::MeadeLocalDate date {}; + + bool onSetTargetDec(meade::DecCoordinate v) override + { + lastCall = "targetDec"; + dec = v; + return nextResult; + } + bool onSetTargetRa(meade::RaCoordinate v) override + { + lastCall = "targetRa"; + ra = v; + return nextResult; + } + bool onSetLocalSiderealTime(meade::MeadeLocalTime v) override + { + lastCall = "lst"; + lst = v; + return nextResult; + } + bool onSetHomePoint() override + { + lastCall = "home"; + return nextResult; + } + bool onSetHourAngle(uint8_t hh, uint8_t mm) override + { + lastCall = "ha"; + haHours = hh; + haMinutes = mm; + return nextResult; + } + bool onSyncCoordinates(meade::DecCoordinate d, meade::RaCoordinate r) override + { + lastCall = "sync"; + syncDec = d; + syncRa = r; + return nextResult; + } + bool onSetSiteLatitude(meade::MeadeLatitude v) override + { + lastCall = "lat"; + lat = v; + return nextResult; + } + bool onSetSiteLongitude(meade::MeadeLongitude v) override + { + lastCall = "lon"; + lon = v; + return nextResult; + } + bool onSetUtcOffset(int v) override + { + lastCall = "utc"; + utc = v; + return nextResult; + } + bool onSetLocalTime(meade::MeadeLocalTime v) override + { + lastCall = "time"; + time = v; + return nextResult; + } + bool onSetLocalDate(meade::MeadeLocalDate v) override + { + lastCall = "date"; + date = v; + return nextResult; + } +}; + +const char *dispatch(const char *suffix, FakeHandlers &h) +{ + static meade::MeadeResponse last; + last = meade::handleMeadeSet(suffix, h); + return last.c_str(); +} + +} // namespace + +namespace +{ + +// ---- Target DEC (d) ---------------------------------------------------- + +void test_set_target_dec_happy_path() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("d+84*03:02", h)); + TEST_ASSERT_EQUAL_STRING("targetDec", h.lastCall); + TEST_ASSERT_EQUAL_INT(84, h.dec.degrees); + TEST_ASSERT_EQUAL_UINT8(3, h.dec.minutes); + TEST_ASSERT_EQUAL_UINT8(2, h.dec.seconds); +} + +void test_set_target_dec_negative_with_colon_separator() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("d-12:45:30", h)); + TEST_ASSERT_EQUAL_INT(-12, h.dec.degrees); + TEST_ASSERT_EQUAL_UINT8(45, h.dec.minutes); + TEST_ASSERT_EQUAL_UINT8(30, h.dec.seconds); +} + +void test_set_target_dec_handler_failure_returns_zero() +{ + FakeHandlers h; + h.nextResult = false; + TEST_ASSERT_EQUAL_STRING("0", dispatch("d+10*20:30", h)); + TEST_ASSERT_EQUAL_STRING("targetDec", h.lastCall); +} + +void test_set_target_dec_malformed_does_not_call_handler() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", dispatch("d+84X03:02", h)); + TEST_ASSERT_NULL(h.lastCall); +} + +// ---- Target RA (r) ----------------------------------------------------- + +void test_set_target_ra_happy_path() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("r04:03:02", h)); + TEST_ASSERT_EQUAL_STRING("targetRa", h.lastCall); + TEST_ASSERT_EQUAL_UINT8(4, h.ra.hours); + TEST_ASSERT_EQUAL_UINT8(3, h.ra.minutes); + TEST_ASSERT_EQUAL_UINT8(2, h.ra.seconds); +} + +void test_set_target_ra_malformed_does_not_call_handler() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", dispatch("r04-03-02", h)); + TEST_ASSERT_NULL(h.lastCall); +} + +// ---- Local Sidereal Time (HL) ----------------------------------------- + +void test_set_lst_with_seconds() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("HL123456", h)); + TEST_ASSERT_EQUAL_STRING("lst", h.lastCall); + TEST_ASSERT_EQUAL_UINT8(12, h.lst.hours); + TEST_ASSERT_EQUAL_UINT8(34, h.lst.minutes); + TEST_ASSERT_EQUAL_UINT8(56, h.lst.seconds); +} + +void test_set_lst_without_seconds() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("HL1234", h)); + TEST_ASSERT_EQUAL_UINT8(12, h.lst.hours); + TEST_ASSERT_EQUAL_UINT8(34, h.lst.minutes); + TEST_ASSERT_EQUAL_UINT8(0, h.lst.seconds); +} + +void test_set_lst_malformed_length_does_not_call_handler() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", dispatch("HL12345", h)); + TEST_ASSERT_NULL(h.lastCall); +} + +// ---- Home Point (HP) -------------------------------------------------- + +void test_set_home_point_happy_path() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("HP", h)); + TEST_ASSERT_EQUAL_STRING("home", h.lastCall); +} + +void test_set_home_point_handler_failure_returns_zero() +{ + FakeHandlers h; + h.nextResult = false; + TEST_ASSERT_EQUAL_STRING("0", dispatch("HP", h)); +} + +// ---- Hour Angle (H) --------------------------------------------------- + +void test_set_hour_angle_happy_path() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("H12:34", h)); + TEST_ASSERT_EQUAL_STRING("ha", h.lastCall); + TEST_ASSERT_EQUAL_UINT8(12, h.haHours); + TEST_ASSERT_EQUAL_UINT8(34, h.haMinutes); +} + +void test_set_hour_angle_malformed_does_not_call_handler() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", dispatch("H1X:34", h)); + TEST_ASSERT_NULL(h.lastCall); +} + +// ---- Sync Coordinates (Y) --------------------------------------------- + +void test_sync_coordinates_happy_path() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("Y+84*03:02.18:34:12", h)); + TEST_ASSERT_EQUAL_STRING("sync", h.lastCall); + TEST_ASSERT_EQUAL_INT(84, h.syncDec.degrees); + TEST_ASSERT_EQUAL_UINT8(3, h.syncDec.minutes); + TEST_ASSERT_EQUAL_UINT8(2, h.syncDec.seconds); + TEST_ASSERT_EQUAL_UINT8(18, h.syncRa.hours); + TEST_ASSERT_EQUAL_UINT8(34, h.syncRa.minutes); + TEST_ASSERT_EQUAL_UINT8(12, h.syncRa.seconds); +} + +void test_sync_coordinates_missing_dot_does_not_call_handler() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", dispatch("Y+84*03:02X18:34:12", h)); + TEST_ASSERT_NULL(h.lastCall); +} + +// ---- Site Latitude (t) ------------------------------------------------ + +void test_set_site_latitude_positive() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("t+30*29", h)); + TEST_ASSERT_EQUAL_STRING("lat", h.lastCall); + TEST_ASSERT_EQUAL_INT(30, h.lat.degrees); + TEST_ASSERT_EQUAL_UINT8(29, h.lat.minutes); +} + +void test_set_site_latitude_negative_with_colon() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("t-45:15", h)); + TEST_ASSERT_EQUAL_INT(-45, h.lat.degrees); + TEST_ASSERT_EQUAL_UINT8(15, h.lat.minutes); +} + +void test_set_site_latitude_malformed_does_not_call_handler() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", dispatch("t30*29", h)); // missing sign + TEST_ASSERT_NULL(h.lastCall); +} + +// ---- Site Longitude (g) ----------------------------------------------- + +void test_set_site_longitude_three_digit_degrees() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("g+097*34", h)); + TEST_ASSERT_EQUAL_STRING("lon", h.lastCall); + TEST_ASSERT_EQUAL_INT(97, h.lon.degrees); + TEST_ASSERT_EQUAL_UINT8(34, h.lon.minutes); +} + +void test_set_site_longitude_malformed_short_does_not_call_handler() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", dispatch("g+97*34", h)); // 2-digit degrees + TEST_ASSERT_NULL(h.lastCall); +} + +// ---- UTC Offset (G) --------------------------------------------------- + +void test_set_utc_offset_positive() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("G+05", h)); + TEST_ASSERT_EQUAL_STRING("utc", h.lastCall); + TEST_ASSERT_EQUAL_INT(5, h.utc); +} + +void test_set_utc_offset_negative() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("G-08", h)); + TEST_ASSERT_EQUAL_INT(-8, h.utc); +} + +void test_set_utc_offset_malformed_length_does_not_call_handler() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", dispatch("G+5", h)); + TEST_ASSERT_NULL(h.lastCall); +} + +// ---- Local Time (L) --------------------------------------------------- + +void test_set_local_time_happy_path() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1", dispatch("L19:33:03", h)); + TEST_ASSERT_EQUAL_STRING("time", h.lastCall); + TEST_ASSERT_EQUAL_UINT8(19, h.time.hours); + TEST_ASSERT_EQUAL_UINT8(33, h.time.minutes); + TEST_ASSERT_EQUAL_UINT8(3, h.time.seconds); +} + +void test_set_local_time_malformed_does_not_call_handler() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", dispatch("L19-33-03", h)); + TEST_ASSERT_NULL(h.lastCall); +} + +// ---- Local Date (C) --------------------------------------------------- + +void test_set_local_date_success_emits_planetary_ack() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("1Updating Planetary Data# #", dispatch("C04/30/24", h)); + TEST_ASSERT_EQUAL_STRING("date", h.lastCall); + TEST_ASSERT_EQUAL_UINT8(4, h.date.month); + TEST_ASSERT_EQUAL_UINT8(30, h.date.day); + TEST_ASSERT_EQUAL_UINT16(2024, h.date.year); +} + +void test_set_local_date_failure_returns_zero_only() +{ + FakeHandlers h; + h.nextResult = false; + TEST_ASSERT_EQUAL_STRING("0", dispatch("C04/30/24", h)); +} + +void test_set_local_date_malformed_does_not_call_handler() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", dispatch("C04-30-24", h)); + TEST_ASSERT_NULL(h.lastCall); +} + +// ---- Top-level routing ------------------------------------------------ + +void test_unknown_set_subcommand_returns_zero() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", dispatch("Z42", h)); + TEST_ASSERT_NULL(h.lastCall); +} + +void test_empty_suffix_returns_zero() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("0", dispatch("", h)); + TEST_ASSERT_NULL(h.lastCall); +} + +} // namespace + +void register_meade_set_tests() +{ + RUN_TEST(test_set_target_dec_happy_path); + RUN_TEST(test_set_target_dec_negative_with_colon_separator); + RUN_TEST(test_set_target_dec_handler_failure_returns_zero); + RUN_TEST(test_set_target_dec_malformed_does_not_call_handler); + + RUN_TEST(test_set_target_ra_happy_path); + RUN_TEST(test_set_target_ra_malformed_does_not_call_handler); + + RUN_TEST(test_set_lst_with_seconds); + RUN_TEST(test_set_lst_without_seconds); + RUN_TEST(test_set_lst_malformed_length_does_not_call_handler); + + RUN_TEST(test_set_home_point_happy_path); + RUN_TEST(test_set_home_point_handler_failure_returns_zero); + + RUN_TEST(test_set_hour_angle_happy_path); + RUN_TEST(test_set_hour_angle_malformed_does_not_call_handler); + + RUN_TEST(test_sync_coordinates_happy_path); + RUN_TEST(test_sync_coordinates_missing_dot_does_not_call_handler); + + RUN_TEST(test_set_site_latitude_positive); + RUN_TEST(test_set_site_latitude_negative_with_colon); + RUN_TEST(test_set_site_latitude_malformed_does_not_call_handler); + + RUN_TEST(test_set_site_longitude_three_digit_degrees); + RUN_TEST(test_set_site_longitude_malformed_short_does_not_call_handler); + + RUN_TEST(test_set_utc_offset_positive); + RUN_TEST(test_set_utc_offset_negative); + RUN_TEST(test_set_utc_offset_malformed_length_does_not_call_handler); + + RUN_TEST(test_set_local_time_happy_path); + RUN_TEST(test_set_local_time_malformed_does_not_call_handler); + + RUN_TEST(test_set_local_date_success_emits_planetary_ack); + RUN_TEST(test_set_local_date_failure_returns_zero_only); + RUN_TEST(test_set_local_date_malformed_does_not_call_handler); + + RUN_TEST(test_unknown_set_subcommand_returns_zero); + RUN_TEST(test_empty_suffix_returns_zero); +} diff --git a/unit_tests/test_meade/test_MeadeSlewRate.cpp b/unit_tests/test_meade/test_MeadeSlewRate.cpp new file mode 100644 index 00000000..95e27dfe --- /dev/null +++ b/unit_tests/test_meade/test_MeadeSlewRate.cpp @@ -0,0 +1,100 @@ +// Wire-byte tests for the Meade SetSlewRate dispatcher (`handleMeadeSetSlewRate`). +// +// `:RS#`/`:RM#`/`:RC#`/`:RG#` map to mount slew rates 4/3/2/1 with empty wire +// responses. Unknown or malformed suffixes are ignored and emit empty. + +#include + +#include "core/meade/MeadeParser.hpp" + +namespace meade = oat::core::meade; + +namespace +{ + +class FakeHandlers : public meade::IMeadeSlewRateHandlers +{ + public: + int lastRate = -1; + int callCount = 0; + + void onSetSlewRate(uint8_t rate) override + { + lastRate = static_cast(rate); + ++callCount; + } +}; + +const char *dispatch(const char *suffix, FakeHandlers &h) +{ + static meade::MeadeResponse last; + last = meade::handleMeadeSetSlewRate(suffix, h); + return last.c_str(); +} + +} // namespace + +namespace +{ + +void test_slew_rate_s_sets_4() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("S", h)); + TEST_ASSERT_EQUAL_INT(4, h.lastRate); +} + +void test_slew_rate_m_sets_3() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("M", h)); + TEST_ASSERT_EQUAL_INT(3, h.lastRate); +} + +void test_slew_rate_c_sets_2() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("C", h)); + TEST_ASSERT_EQUAL_INT(2, h.lastRate); +} + +void test_slew_rate_g_sets_1() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("G", h)); + TEST_ASSERT_EQUAL_INT(1, h.lastRate); +} + +void test_slew_rate_unknown_suffix_no_call() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("Q", h)); + TEST_ASSERT_EQUAL_INT(0, h.callCount); +} + +void test_slew_rate_multi_char_suffix_no_call() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("SS", h)); + TEST_ASSERT_EQUAL_INT(0, h.callCount); +} + +void test_slew_rate_empty_suffix_no_call() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("", dispatch("", h)); + TEST_ASSERT_EQUAL_INT(0, h.callCount); +} + +} // namespace + +void register_meade_slew_rate_tests() +{ + RUN_TEST(test_slew_rate_s_sets_4); + RUN_TEST(test_slew_rate_m_sets_3); + RUN_TEST(test_slew_rate_c_sets_2); + RUN_TEST(test_slew_rate_g_sets_1); + RUN_TEST(test_slew_rate_unknown_suffix_no_call); + RUN_TEST(test_slew_rate_multi_char_suffix_no_call); + RUN_TEST(test_slew_rate_empty_suffix_no_call); +} diff --git a/unit_tests/test_meade/test_MeadeSync.cpp b/unit_tests/test_meade/test_MeadeSync.cpp new file mode 100644 index 00000000..1293e87f --- /dev/null +++ b/unit_tests/test_meade/test_MeadeSync.cpp @@ -0,0 +1,73 @@ +// Wire-byte tests for the Meade SyncControl dispatcher (`handleMeadeSyncControl`). +// +// `:CM#` syncs the mount to the previously-set target and emits "NONE#". +// Any other suffix elicits "FAIL#" with no handler call. + +#include + +#include "core/meade/MeadeParser.hpp" + +namespace meade = oat::core::meade; + +namespace +{ + +class FakeHandlers : public meade::IMeadeSyncControlHandlers +{ + public: + int callCount = 0; + void onSyncToTarget() override + { + ++callCount; + } +}; + +const char *dispatch(const char *suffix, FakeHandlers &h) +{ + static meade::MeadeResponse last; + last = meade::handleMeadeSyncControl(suffix, h); + return last.c_str(); +} + +} // namespace + +namespace +{ + +void test_sync_to_target_emits_none() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("NONE#", dispatch("M", h)); + TEST_ASSERT_EQUAL_INT(1, h.callCount); +} + +void test_sync_unknown_suffix_emits_fail() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("FAIL#", dispatch("Q", h)); + TEST_ASSERT_EQUAL_INT(0, h.callCount); +} + +void test_sync_empty_suffix_emits_fail() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("FAIL#", dispatch("", h)); + TEST_ASSERT_EQUAL_INT(0, h.callCount); +} + +void test_sync_trailing_bytes_emit_fail() +{ + FakeHandlers h; + TEST_ASSERT_EQUAL_STRING("FAIL#", dispatch("Mx", h)); + TEST_ASSERT_EQUAL_INT(0, h.callCount); +} + +} // namespace + +void register_meade_sync_tests() +{ + RUN_TEST(test_sync_to_target_emits_none); + RUN_TEST(test_sync_unknown_suffix_emits_fail); + RUN_TEST(test_sync_empty_suffix_emits_fail); + RUN_TEST(test_sync_trailing_bytes_emit_fail); +} diff --git a/unit_tests/test_meade/test_main.cpp b/unit_tests/test_meade/test_main.cpp new file mode 100644 index 00000000..571e4c5e --- /dev/null +++ b/unit_tests/test_meade/test_main.cpp @@ -0,0 +1,45 @@ +#include + +void register_meade_parser_tests(); +void register_meade_distance_tests(); +void register_meade_extra_tests(); +void register_meade_focus_tests(); +void register_meade_get_tests(); +void register_meade_gps_tests(); +void register_meade_home_tests(); +void register_meade_init_tests(); +void register_meade_movement_tests(); +void register_meade_quit_tests(); +void register_meade_set_tests(); +void register_meade_slew_rate_tests(); +void register_meade_sync_tests(); + +void setUp(void) +{ +} + +void tearDown(void) +{ +} + +int main(int, char **) +{ + UNITY_BEGIN(); + + register_meade_parser_tests(); + + register_meade_get_tests(); + register_meade_set_tests(); + register_meade_quit_tests(); + register_meade_distance_tests(); + register_meade_init_tests(); + register_meade_sync_tests(); + register_meade_home_tests(); + register_meade_slew_rate_tests(); + register_meade_gps_tests(); + register_meade_focus_tests(); + register_meade_movement_tests(); + register_meade_extra_tests(); + + return UNITY_END(); +} \ No newline at end of file