diff --git a/.github/workflows/build.yml b/.github/workflows/build.yml new file mode 100644 index 0000000..2fd1e99 --- /dev/null +++ b/.github/workflows/build.yml @@ -0,0 +1,42 @@ +name: Build on Windows + +on: + push: + branches: [main] + pull_request: + branches: [main] + workflow_dispatch: + +env: + BUILD_TYPE: Release + +jobs: + build-windows: + runs-on: windows-2022 + + steps: + - name: Checkout repository + uses: actions/checkout@v3 + + - name: Set up MSBuild and CMake + uses: microsoft/setup-msbuild@v1.3 + + - name: Install MSYS2 (Git Bash) + uses: msys2/setup-msys2@v2 + with: + update: true + + - name: Configure and build C++ wrapper (DLL) + shell: bash + run: | + ./build_and_install_flexiv_rdk_dll.sh + + - name: Build C# example + run: | + cd csharp + dotnet build build.csproj -c Release + + - name: Run C# example + run: | + cd csharp + dotnet run --project build.csproj -c Release diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..26a307e --- /dev/null +++ b/.gitignore @@ -0,0 +1,370 @@ +## Ignore Visual Studio temporary files, build results, and +## files generated by popular Visual Studio add-ons. +## +## Get latest from https://github.com/github/gitignore/blob/master/VisualStudio.gitignore + +# User-specific files +*.rsuser +*.suo +*.user +*.userosscache +*.sln.docstates + +# User-specific files (MonoDevelop/Xamarin Studio) +*.userprefs + +# Mono auto generated files +mono_crash.* + +# Build results +[Dd]ebug/ +[Dd]ebugPublic/ +[Rr]elease/ +[Rr]eleases/ +x64/ +x86/ +[Ww][Ii][Nn]32/ +[Aa][Rr][Mm]/ +[Aa][Rr][Mm]64/ +bld/ +[Bb]in/ +[Oo]bj/ +[Oo]ut/ +[Ll]og/ +[Ll]ogs/ + +# Visual Studio 2015/2017 cache/options directory +.vs/ +# Uncomment if you have tasks that create the project's static files in wwwroot +#wwwroot/ + +# Visual Studio 2017 auto generated files +Generated\ Files/ + +# MSTest test Results +[Tt]est[Rr]esult*/ +[Bb]uild[Ll]og.* + +# NUnit +*.VisualState.xml +TestResult.xml +nunit-*.xml + +# Build Results of an ATL Project +[Dd]ebugPS/ +[Rr]eleasePS/ +dlldata.c + +# Benchmark Results +BenchmarkDotNet.Artifacts/ + +# .NET Core +project.lock.json +project.fragment.lock.json +artifacts/ + +# ASP.NET Scaffolding +ScaffoldingReadMe.txt + +# StyleCop +StyleCopReport.xml + +# Files built by Visual Studio +*_i.c +*_p.c +*_h.h +*.ilk +*.meta +*.obj +*.iobj +*.pch +*.pdb +*.ipdb +*.pgc +*.pgd +*.rsp +*.sbr +*.tlb +*.tli +*.tlh +*.tmp +*.tmp_proj +*_wpftmp.csproj +*.log +*.vspscc +*.vssscc +.builds +*.pidb +*.svclog +*.scc + +# Chutzpah Test files +_Chutzpah* + +# Visual C++ cache files +ipch/ +*.aps +*.ncb +*.opendb +*.opensdf +*.sdf +*.cachefile +*.VC.db +*.VC.VC.opendb + +# Visual Studio profiler +*.psess +*.vsp +*.vspx +*.sap + +# Visual Studio Trace Files +*.e2e + +# TFS 2012 Local Workspace +$tf/ + +# Guidance Automation Toolkit +*.gpState + +# ReSharper is a .NET coding add-in +_ReSharper*/ +*.[Rr]e[Ss]harper +*.DotSettings.user + +# TeamCity is a build add-in +_TeamCity* + +# DotCover is a Code Coverage Tool +*.dotCover + +# AxoCover is a Code Coverage Tool +.axoCover/* +!.axoCover/settings.json + +# Coverlet is a free, cross platform Code Coverage Tool +coverage*.json +coverage*.xml +coverage*.info + +# Visual Studio code coverage results +*.coverage +*.coveragexml + +# NCrunch +_NCrunch_* +.*crunch*.local.xml +nCrunchTemp_* + +# MightyMoose +*.mm.* +AutoTest.Net/ + +# Web workbench (sass) +.sass-cache/ + +# Installshield output folder +[Ee]xpress/ + +# DocProject is a documentation generator add-in +DocProject/buildhelp/ +DocProject/Help/*.HxT +DocProject/Help/*.HxC +DocProject/Help/*.hhc +DocProject/Help/*.hhk +DocProject/Help/*.hhp +DocProject/Help/Html2 +DocProject/Help/html + +# Click-Once directory +publish/ + +# Publish Web Output +*.[Pp]ublish.xml +*.azurePubxml +# Note: Comment the next line if you want to checkin your web deploy settings, +# but database connection strings (with potential passwords) will be unencrypted +*.pubxml +*.publishproj + +# Microsoft Azure Web App publish settings. Comment the next line if you want to +# checkin your Azure Web App publish settings, but sensitive information contained +# in these scripts will be unencrypted +PublishScripts/ + +# NuGet Packages +*.nupkg +# NuGet Symbol Packages +*.snupkg +# The packages folder can be ignored because of Package Restore +**/[Pp]ackages/* +# except build/, which is used as an MSBuild target. +!**/[Pp]ackages/build/ +# Uncomment if necessary however generally it will be regenerated when needed +#!**/[Pp]ackages/repositories.config +# NuGet v3's project.json files produces more ignorable files +*.nuget.props +*.nuget.targets + +# Microsoft Azure Build Output +csx/ +*.build.csdef + +# Microsoft Azure Emulator +ecf/ +rcf/ + +# Windows Store app package directories and files +AppPackages/ +BundleArtifacts/ +Package.StoreAssociation.xml +_pkginfo.txt +*.appx +*.appxbundle +*.appxupload + +# Visual Studio cache files +# files ending in .cache can be ignored +*.[Cc]ache +# but keep track of directories ending in .cache +!?*.[Cc]ache/ + +# Others +ClientBin/ +~$* +*~ +*.dbmdl +*.dbproj.schemaview +*.jfm +*.pfx +*.publishsettings +orleans.codegen.cs + +# Including strong name files can present a security risk +# (https://github.com/github/gitignore/pull/2483#issue-259490424) +#*.snk + +# Since there are multiple workflows, uncomment next line to ignore bower_components +# (https://github.com/github/gitignore/pull/1529#issuecomment-104372622) +#bower_components/ + +# RIA/Silverlight projects +Generated_Code/ + +# Backup & report files from converting an old project file +# to a newer Visual Studio version. Backup files are not needed, +# because we have git ;-) +_UpgradeReport_Files/ +Backup*/ +UpgradeLog*.XML +UpgradeLog*.htm +ServiceFabricBackup/ +*.rptproj.bak + +# SQL Server files +*.mdf +*.ldf +*.ndf + +# Business Intelligence projects +*.rdl.data +*.bim.layout +*.bim_*.settings +*.rptproj.rsuser +*- [Bb]ackup.rdl +*- [Bb]ackup ([0-9]).rdl +*- [Bb]ackup ([0-9][0-9]).rdl + +# Microsoft Fakes +FakesAssemblies/ + +# GhostDoc plugin setting file +*.GhostDoc.xml + +# Node.js Tools for Visual Studio +.ntvs_analysis.dat +node_modules/ + +# Visual Studio 6 build log +*.plg + +# Visual Studio 6 workspace options file +*.opt + +# Visual Studio 6 auto-generated workspace file (contains which files were open etc.) +*.vbw + +# Visual Studio LightSwitch build output +**/*.HTMLClient/GeneratedArtifacts +**/*.DesktopClient/GeneratedArtifacts +**/*.DesktopClient/ModelManifest.xml +**/*.Server/GeneratedArtifacts +**/*.Server/ModelManifest.xml +_Pvt_Extensions + +# Paket dependency manager +.paket/paket.exe +paket-files/ + +# FAKE - F# Make +.fake/ + +# CodeRush personal settings +.cr/personal + +# Python Tools for Visual Studio (PTVS) +__pycache__/ +*.pyc + +# Cake - Uncomment if you are using it +# tools/** +# !tools/packages.config + +# Tabs Studio +*.tss + +# Telerik's JustMock configuration file +*.jmconfig + +# BizTalk build output +*.btp.cs +*.btm.cs +*.odx.cs +*.xsd.cs + +# OpenCover UI analysis results +OpenCover/ + +# Azure Stream Analytics local run output +ASALocalRun/ + +# MSBuild Binary and Structured Log +*.binlog + +# NVidia Nsight GPU debugger configuration file +*.nvuser + +# MFractors (Xamarin productivity tool) working folder +.mfractor/ + +# Local History for Visual Studio +.localhistory/ + +# BeatPulse healthcheck temp database +healthchecksdb + +# Backup folder for Package Reference Convert tool in Visual Studio 2017 +MigrationBackup/ + +# Ionide (cross platform F# VS Code tools) working folder +.ionide/ + +# Fody - auto-generated XML schema +FodyWeavers.xsd + +build*/ +third_party/flexiv_rdk +install/cpp_wrapper +install/rdk_install +bin*/ +obj*/ \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt new file mode 100644 index 0000000..17506b3 --- /dev/null +++ b/CMakeLists.txt @@ -0,0 +1,20 @@ +cmake_minimum_required(VERSION 3.16) +project(FlexivRdkCSharp LANGUAGES C CXX) + +set(CMAKE_CXX_STANDARD 17) +set(CMAKE_CXX_STANDARD_REQUIRED ON) + +list(APPEND CMAKE_PREFIX_PATH "${CMAKE_SOURCE_DIR}/install/rdk_install") +find_package(flexiv_rdk REQUIRED) + +include(GNUInstallDirs) + +set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/lib" CACHE PATH "Archive output dir.") +set(CMAKE_LIBRARY_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/lib" CACHE PATH "Library output dir.") +set(CMAKE_PDB_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin" CACHE PATH "PDB (MSVC debug symbol)output dir.") +set(CMAKE_RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin" CACHE PATH "Executable/dll output dir.") + +if(CMAKE_INSTALL_PREFIX_INITIALIZED_TO_DEFAULT) + set(CMAKE_INSTALL_PREFIX "${CMAKE_SOURCE_DIR}/install" CACHE PATH "Default install path" FORCE) +endif() +add_subdirectory(cpp_wrapper) \ No newline at end of file diff --git a/LICENSE b/LICENSE new file mode 100644 index 0000000..261eeb9 --- /dev/null +++ b/LICENSE @@ -0,0 +1,201 @@ + Apache License + Version 2.0, January 2004 + http://www.apache.org/licenses/ + + TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION + + 1. Definitions. + + "License" shall mean the terms and conditions for use, reproduction, + and distribution as defined by Sections 1 through 9 of this document. + + "Licensor" shall mean the copyright owner or entity authorized by + the copyright owner that is granting the License. + + "Legal Entity" shall mean the union of the acting entity and all + other entities that control, are controlled by, or are under common + control with that entity. For the purposes of this definition, + "control" means (i) the power, direct or indirect, to cause the + direction or management of such entity, whether by contract or + otherwise, or (ii) ownership of fifty percent (50%) or more of the + outstanding shares, or (iii) beneficial ownership of such entity. + + "You" (or "Your") shall mean an individual or Legal Entity + exercising permissions granted by this License. + + "Source" form shall mean the preferred form for making modifications, + including but not limited to software source code, documentation + source, and configuration files. + + "Object" form shall mean any form resulting from mechanical + transformation or translation of a Source form, including but + not limited to compiled object code, generated documentation, + and conversions to other media types. + + "Work" shall mean the work of authorship, whether in Source or + Object form, made available under the License, as indicated by a + copyright notice that is included in or attached to the work + (an example is provided in the Appendix below). + + "Derivative Works" shall mean any work, whether in Source or Object + form, that is based on (or derived from) the Work and for which the + editorial revisions, annotations, elaborations, or other modifications + represent, as a whole, an original work of authorship. For the purposes + of this License, Derivative Works shall not include works that remain + separable from, or merely link (or bind by name) to the interfaces of, + the Work and Derivative Works thereof. + + "Contribution" shall mean any work of authorship, including + the original version of the Work and any modifications or additions + to that Work or Derivative Works thereof, that is intentionally + submitted to Licensor for inclusion in the Work by the copyright owner + or by an individual or Legal Entity authorized to submit on behalf of + the copyright owner. For the purposes of this definition, "submitted" + means any form of electronic, verbal, or written communication sent + to the Licensor or its representatives, including but not limited to + communication on electronic mailing lists, source code control systems, + and issue tracking systems that are managed by, or on behalf of, the + Licensor for the purpose of discussing and improving the Work, but + excluding communication that is conspicuously marked or otherwise + designated in writing by the copyright owner as "Not a Contribution." + + "Contributor" shall mean Licensor and any individual or Legal Entity + on behalf of whom a Contribution has been received by Licensor and + subsequently incorporated within the Work. + + 2. Grant of Copyright License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + copyright license to reproduce, prepare Derivative Works of, + publicly display, publicly perform, sublicense, and distribute the + Work and such Derivative Works in Source or Object form. + + 3. Grant of Patent License. Subject to the terms and conditions of + this License, each Contributor hereby grants to You a perpetual, + worldwide, non-exclusive, no-charge, royalty-free, irrevocable + (except as stated in this section) patent license to make, have made, + use, offer to sell, sell, import, and otherwise transfer the Work, + where such license applies only to those patent claims licensable + by such Contributor that are necessarily infringed by their + Contribution(s) alone or by combination of their Contribution(s) + with the Work to which such Contribution(s) was submitted. If You + institute patent litigation against any entity (including a + cross-claim or counterclaim in a lawsuit) alleging that the Work + or a Contribution incorporated within the Work constitutes direct + or contributory patent infringement, then any patent licenses + granted to You under this License for that Work shall terminate + as of the date such litigation is filed. + + 4. Redistribution. You may reproduce and distribute copies of the + Work or Derivative Works thereof in any medium, with or without + modifications, and in Source or Object form, provided that You + meet the following conditions: + + (a) You must give any other recipients of the Work or + Derivative Works a copy of this License; and + + (b) You must cause any modified files to carry prominent notices + stating that You changed the files; and + + (c) You must retain, in the Source form of any Derivative Works + that You distribute, all copyright, patent, trademark, and + attribution notices from the Source form of the Work, + excluding those notices that do not pertain to any part of + the Derivative Works; and + + (d) If the Work includes a "NOTICE" text file as part of its + distribution, then any Derivative Works that You distribute must + include a readable copy of the attribution notices contained + within such NOTICE file, excluding those notices that do not + pertain to any part of the Derivative Works, in at least one + of the following places: within a NOTICE text file distributed + as part of the Derivative Works; within the Source form or + documentation, if provided along with the Derivative Works; or, + within a display generated by the Derivative Works, if and + wherever such third-party notices normally appear. The contents + of the NOTICE file are for informational purposes only and + do not modify the License. You may add Your own attribution + notices within Derivative Works that You distribute, alongside + or as an addendum to the NOTICE text from the Work, provided + that such additional attribution notices cannot be construed + as modifying the License. + + You may add Your own copyright statement to Your modifications and + may provide additional or different license terms and conditions + for use, reproduction, or distribution of Your modifications, or + for any such Derivative Works as a whole, provided Your use, + reproduction, and distribution of the Work otherwise complies with + the conditions stated in this License. + + 5. Submission of Contributions. Unless You explicitly state otherwise, + any Contribution intentionally submitted for inclusion in the Work + by You to the Licensor shall be under the terms and conditions of + this License, without any additional terms or conditions. + Notwithstanding the above, nothing herein shall supersede or modify + the terms of any separate license agreement you may have executed + with Licensor regarding such Contributions. + + 6. Trademarks. This License does not grant permission to use the trade + names, trademarks, service marks, or product names of the Licensor, + except as required for reasonable and customary use in describing the + origin of the Work and reproducing the content of the NOTICE file. + + 7. Disclaimer of Warranty. Unless required by applicable law or + agreed to in writing, Licensor provides the Work (and each + Contributor provides its Contributions) on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or + implied, including, without limitation, any warranties or conditions + of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A + PARTICULAR PURPOSE. You are solely responsible for determining the + appropriateness of using or redistributing the Work and assume any + risks associated with Your exercise of permissions under this License. + + 8. Limitation of Liability. In no event and under no legal theory, + whether in tort (including negligence), contract, or otherwise, + unless required by applicable law (such as deliberate and grossly + negligent acts) or agreed to in writing, shall any Contributor be + liable to You for damages, including any direct, indirect, special, + incidental, or consequential damages of any character arising as a + result of this License or out of the use or inability to use the + Work (including but not limited to damages for loss of goodwill, + work stoppage, computer failure or malfunction, or any and all + other commercial damages or losses), even if such Contributor + has been advised of the possibility of such damages. + + 9. Accepting Warranty or Additional Liability. While redistributing + the Work or Derivative Works thereof, You may choose to offer, + and charge a fee for, acceptance of support, warranty, indemnity, + or other liability obligations and/or rights consistent with this + License. However, in accepting such obligations, You may act only + on Your own behalf and on Your sole responsibility, not on behalf + of any other Contributor, and only if You agree to indemnify, + defend, and hold each Contributor harmless for any liability + incurred by, or claims asserted against, such Contributor by reason + of your accepting any such warranty or additional liability. + + END OF TERMS AND CONDITIONS + + APPENDIX: How to apply the Apache License to your work. + + To apply the Apache License to your work, attach the following + boilerplate notice, with the fields enclosed by brackets "[]" + replaced with your own identifying information. (Don't include + the brackets!) The text should be enclosed in the appropriate + comment syntax for the file format. We also recommend that a + file or class name and description of purpose be included on the + same "printed page" as the copyright notice for easier + identification within third-party archives. + + Copyright [yyyy] [name of copyright owner] + + Licensed under the Apache License, Version 2.0 (the "License"); + you may not use this file except in compliance with the License. + You may obtain a copy of the License at + + http://www.apache.org/licenses/LICENSE-2.0 + + Unless required by applicable law or agreed to in writing, software + distributed under the License is distributed on an "AS IS" BASIS, + WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + See the License for the specific language governing permissions and + limitations under the License. diff --git a/README.md b/README.md index f335f4b..c57df5a 100644 --- a/README.md +++ b/README.md @@ -1 +1,83 @@ -# flexiv_rdk_csharp \ No newline at end of file +# Flexiv RDK CSharp + +[![License](https://img.shields.io/badge/License-Apache%202.0-blue.svg)](https://www.apache.org/licenses/LICENSE-2.0.html) + +**Flexiv RDK CSharp** provides C# developers with an easy way to work with [**Flexiv RDK**](https://github.com/flexivrobotics/flexiv_rdk). It uses [**P/Invoke**](https://learn.microsoft.com/en-us/dotnet/standard/native-interop/pinvoke) to call most of the functions from the RDK C++ interface, excluding *flexiv::rdk::Model* and *flexiv::rdk::Scheduler*. + +## Reference + +For detailed usage instructions and API documentation, refer to the [Flexiv RDK Home Page](https://www.flexiv.com/software/rdk). + +## Compatibility + +| **Language** | **Supported OS** | **Platform** | **Compiler / Runtime** | **Notes** | +| ------------ | ---------------- | ------------ | ---------------------- | -------------------------------- | +| **C++** | Windows 10+ | x64 | MSVC v14.2+ (VS 2019+) | Builds dynamic library (`.dll`) | +| **C#** | Windows 10+ | x64 | .NET 5.0 or later | Uses `DllImport` to call C++ DLL | + +## Project Structure + +It calls the C++ interfaces from [flexiv_rdk](https://github.com/flexivrobotics/flexiv_rdk) via P/Invoke and wraps them with C# interfaces. + +- **csharp/**: C# project containing the wrapper and usage examples. + - **FlexivRdk/**: C# wrapper classes calling functions from the native DLL. + - **Examples/**: Example programs demonstrating usage of the C# wrappers. + - `Program.cs`: Entry point, runs selected example programs. +- **cpp_wrapper/**: C++ project wrapping **flexiv_rdk** C++ interfaces and generating a dynamic library (`.dll`). +- **install/**: Installs flexiv_rdk dependencies and C++ wrapper dynamic libraries to custom output directories. +- **released_dll/**: Precompiled dynamic libraries for immediate use. +- **third_party/**:Third-party library folder. + +## Usage + +This repository provides C# bindings for the Flexiv RDK. You can either directly use the existing interfaces, or extend the native C++ wrapper and rebuild the dynamic libraries as needed. + +### Option:1 Direct Use (Run Existing Examples) + +If you simply want to run the C# examples using the provided native DLLs, follow these steps: + +1. Navigate to the C# project directory: + + cd flexiv_rdk_csharp/csharp + +2. Build the project in Release mode: + + dotnet build csharp.csproj -c Release + + NOTE: During the build process, DLLs from the released_dll directory will be automatically copied to the output directory. + +3. Run the example program: + + dotnet run --project csharp.csproj -c Release + + NOTE: Usage instructions will appear in the command line. Please select a sample program, such as: + + dotnet run --project csharp.csproj basics1_display_robot_states Rizon4-123456 + +4. If you want to use the interface in your own project: + - Include the .cs files from the **csharp/FlexivRdk/** folder. + - Place the dynamic libraries from **released_dll/** in the same directory as your compiled .exe file. + +### Option 2: Extend C++ Interface and Rebuild DLL + +If you want to modify or extend the native C++ wrapper (cpp_wrapper), or rebuild the DLLs from source with latest dependencies: + +1. Navigate to the project root directory: + + cd flexiv_rdk_csharp + +2. Run the build script: + + bash build_and_install_flexiv_rdk_dll.sh + + NOTE: On Windows, if the project involves long file paths, please ensure that Long Path Support is enabled in the system settings to avoid build or runtime errors caused by path length limitations. + + - Download and install flexiv_rdk and third-party dependencies. + - Build the C++ wrapper. + - Generate and install updated DLLs to **install/** directory + + NOTE: After rebuilding, make sure to copy the new DLLs from **install/cpp_wrapper/bin/** into your C# app's output directory (same place as the .exe). + +## License + +This project is licensed under the [Apache License 2.0](https://www.apache.org/licenses/LICENSE-2.0). diff --git a/build_and_install_flexiv_rdk_dll.sh b/build_and_install_flexiv_rdk_dll.sh new file mode 100644 index 0000000..9a804a2 --- /dev/null +++ b/build_and_install_flexiv_rdk_dll.sh @@ -0,0 +1,13 @@ +#!/bin/sh + +CURRSCRIPTPATH="$(dirname $(readlink -f $0))" +bash third_party/build_and_install_flexiv_rdk.sh + +echo ">>> Build and install flexiv rdk dll v1.5.1" +cd $CURRSCRIPTPATH +rm -rf build/ +cmake -S . -B build +cmake --build build --config Release --target install + +echo ">>> Installed successfully: flexiv rdk dll v1.5.1" +echo ">>> Installed path: $CURRSCRIPTPATH/install" \ No newline at end of file diff --git a/cpp_wrapper/CMakeLists.txt b/cpp_wrapper/CMakeLists.txt new file mode 100644 index 0000000..8bbbf5c --- /dev/null +++ b/cpp_wrapper/CMakeLists.txt @@ -0,0 +1,30 @@ +project(cpp_wrapper LANGUAGES CXX) +add_library(${PROJECT_NAME} SHARED src/wrapper_api.cpp) +target_include_directories(${PROJECT_NAME} +PRIVATE + ${CMAKE_SOURCE_DIR}/third_party/nlohmann_json + include/) +target_link_libraries(${PROJECT_NAME} PRIVATE flexiv::flexiv_rdk) + +if (MSVC) + add_compile_definitions(_CRT_SECURE_NO_WARNINGS) + set_target_properties(${PROJECT_NAME} PROPERTIES + LINK_FLAGS "/NOIMPLIB /NOEXP" + ) +endif() + +if(CMAKE_SYSTEM_NAME STREQUAL "Windows") + set(LIB_NAME "flexiv_rdk.win64-vs2019") +else() + set(LIB_NAME "flexiv_rdk.win64-vs2019") +endif() + +set_target_properties(${PROJECT_NAME} PROPERTIES + OUTPUT_NAME ${LIB_NAME} +) + +install(TARGETS ${PROJECT_NAME} + ARCHIVE DESTINATION ${PROJECT_NAME}/lib + RUNTIME DESTINATION ${PROJECT_NAME}/bin + LIBRARY DESTINATION ${PROJECT_NAME}/lib +) \ No newline at end of file diff --git a/cpp_wrapper/include/wrapper_api.hpp b/cpp_wrapper/include/wrapper_api.hpp new file mode 100644 index 0000000..8839a8f --- /dev/null +++ b/cpp_wrapper/include/wrapper_api.hpp @@ -0,0 +1,211 @@ +#ifndef WRAPPER_API_HPP_ +#define WRAPPER_API_HPP_ +#ifdef _WIN32 +#define EXPORT_API extern "C" __declspec(dllexport) +#else +#define EXPORT_API extern "C" +#endif +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include "json.hpp" +using json = nlohmann::json; +using namespace flexiv::rdk; + +struct FlexivError { + int error_code; + char error_msg[512]; +}; + +struct WRobotInfo { + char serial_num[128]; + char software_ver[128]; + char model_name[128]; + char license_type[128]; + int Dof; + double K_x_nom[kCartDoF]; + double K_q_nom[kSerialJointDoF]; + double q_min[kSerialJointDoF]; + double q_max[kSerialJointDoF]; + double dq_max[kSerialJointDoF]; + double tau_max[kSerialJointDoF]; +}; + +struct WRobotState { + double q[kSerialJointDoF]; + double theta[kSerialJointDoF]; + double dq[kSerialJointDoF]; + double dtheta[kSerialJointDoF]; + double tau[kSerialJointDoF]; + double tau_des[kSerialJointDoF]; + double tau_dot[kSerialJointDoF]; + double tau_ext[kSerialJointDoF]; + double q_e[kMaxExtAxes]; + double dq_e[kMaxExtAxes]; + double tau_e[kMaxExtAxes]; + double tcp_pose[kPoseSize]; + double tcp_pose_des[kPoseSize]; + double tcp_vel[kCartDoF]; + double flange_pose[kPoseSize]; + double ft_sensor_raw[kCartDoF]; + double ext_wrench_in_tcp[kCartDoF]; + double ext_wrench_in_world[kCartDoF]; + double ext_wrench_in_tcp_raw[kCartDoF]; + double ext_wrench_in_world_raw[kCartDoF]; +}; + +struct WPlanInfo { + char pt_name[128]; + char node_name[128]; + char node_path[512]; + char node_path_time_period[128]; + char node_path_number[128]; + char assigned_plan_name[128]; + double velocity_scale; + int waiting_for_step; +}; + +struct WToolParams { + double Mass; + double CoM[3]; + double Intertia[6]; + double TcpLocation[kPoseSize]; +}; + +struct WGripperStates { + double width; + double force; + double max_width; +}; + +void CopyExceptionMsg(const std::exception& e, FlexivError* error) { + std::strncpy(error->error_msg, e.what(), sizeof(error->error_msg) - 1); + error->error_msg[sizeof(error->error_msg) - 1] = '\0'; +} + +char* CopyInputString(const char* input) { + if (!input) return nullptr; + size_t len = std::strlen(input); + char* buf = new char[len + 1]; + std::strcpy(buf, input); + return buf; +} + +void CopyMsgSrc2Dst(const char* src, char* dst, size_t dstSize) { + std::strncpy(dst, src, dstSize - 1); + dst[dstSize - 1] = '\0'; +} + +namespace flexiv::rdk { + inline void from_json(const json& j, JPos& pos) { + j.at("q").get_to(pos.q); + j.at("q_e").get_to(pos.q_e); + } + + inline void to_json(json& j, const JPos& pos) { + j = json{ + {"q", pos.q}, + {"q_e", pos.q_e} + }; + } + + inline void from_json(const json& j, Coord& coord) { + j.at("position").get_to(coord.position); + j.at("orientation").get_to(coord.orientation); + j.at("ref_frame").get_to(coord.ref_frame); + j.at("ref_q").get_to(coord.ref_q); + j.at("ref_q_e").get_to(coord.ref_q_e); + } + + inline void to_json(json& j, const Coord& coord) { + j = json{ + {"position", coord.position}, + {"orientation", coord.orientation}, + {"ref_frame", coord.ref_frame}, + {"ref_q", coord.ref_q}, + {"ref_q_e", coord.ref_q_e} + }; + } +} + +using ParserFunc = std::function; +const std::unordered_map kTypeParsers = { + { "Int", [](const json& j) { return j.get(); } }, + { "Double", [](const json& j) { return j.get(); } }, + { "String", [](const json& j) { return j.get(); } }, + { "JPos", [](const json& j) { return j.get(); } }, + { "Coord", [](const json& j) { return j.get(); } }, + { "VectorInt", [](const json& j) { return j.get>(); } }, + { "VectorDouble", [](const json& j) { return j.get>(); } }, + { "VectorString", [](const json& j) { return j.get>(); } }, + { "VectorJPos", [](const json& j) { return j.get>(); } }, + { "VectorCoord", [](const json& j) { return j.get>(); } } +}; + +FlexivDataTypes parseValue(const std::string& type, const json& value) { + auto iter = kTypeParsers.find(type); + if (iter != kTypeParsers.end()) { + return iter->second(value); + } + else { + throw std::runtime_error("Unsupported type: " + type); + } +} + +std::map parseJsonToParams(const char* json_str) { + json json_obj = json::parse(json_str); + std::map params; + for (auto& [key, val] : json_obj.items()) { + std::string type = val.at("type").get(); + FlexivDataTypes data = parseValue(type, val.at("value")); + params[key] = std::move(data); + } + return params; +} + +std::string getTypeName(const FlexivDataTypes& value) { + return std::visit([](auto&& val) -> std::string { + using T = std::decay_t; + if constexpr (std::is_same_v) return "Int"; + else if constexpr (std::is_same_v) return "Double"; + else if constexpr (std::is_same_v) return "String"; + else if constexpr (std::is_same_v) return "JPos"; + else if constexpr (std::is_same_v) return "Coord"; + else if constexpr (std::is_same_v>) return "VectorInt"; + else if constexpr (std::is_same_v>) return "VectorDouble"; + else if constexpr (std::is_same_v>) return "VectorString"; + else if constexpr (std::is_same_v>) return "VectorJPos"; + else if constexpr (std::is_same_v>) return "VectorCoord"; + else return "Unknown"; }, value); +} + +std::string serializeParams(const std::map& params) { + json j; + std::string type_name; + for (const auto& iter : params) { + type_name = getTypeName(iter.second); + std::visit([&](const auto& v) { + j[iter.first] = { + {"type", type_name}, + {"value", v} + }; }, iter.second); + } + return j.dump(); +} + +#endif // !wrapper_api.hpp \ No newline at end of file diff --git a/cpp_wrapper/src/wrapper_api.cpp b/cpp_wrapper/src/wrapper_api.cpp new file mode 100644 index 0000000..e8e8555 --- /dev/null +++ b/cpp_wrapper/src/wrapper_api.cpp @@ -0,0 +1,1093 @@ +#include "wrapper_api.hpp" + +EXPORT_API void FreeString(const char* ptr) { + delete[] ptr; +} + +EXPORT_API void SpdlogInfo(const char* msgs) { + spdlog::info(std::string(msgs)); +} + +EXPORT_API void SpdlogWarn(const char* msgs) { + spdlog::warn(std::string(msgs)); +} + +EXPORT_API void SpdlogError(const char* msgs) { + spdlog::error(std::string(msgs)); +} + +EXPORT_API Robot* CreateFlexivRobot(const char* robot_sn, + const char** interfaces, int interface_count, FlexivError* error) { + std::vector white_list; + for (int i = 0; i < interface_count; ++i) { + white_list.push_back(interfaces[i]); + } + try { + flexiv::rdk::Robot* robot = new flexiv::rdk::Robot(robot_sn, white_list); + error->error_code = 0; + return robot; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } + return nullptr; +} + +EXPORT_API void DeleteFlexivRobot(flexiv::rdk::Robot* robot) { + delete robot; +} + +//========================================= ACCESSORS ========================================== +EXPORT_API int IsConnected(Robot* robot) { + return robot->connected(); +} + +EXPORT_API void GetInfo(Robot* robot, WRobotInfo* info) { + const auto& r_info = robot->info(); + CopyMsgSrc2Dst(r_info.serial_num.c_str(), info->serial_num, sizeof(info->serial_num)); + CopyMsgSrc2Dst(r_info.software_ver.c_str(), info->software_ver, sizeof(info->software_ver)); + CopyMsgSrc2Dst(r_info.model_name.c_str(), info->model_name, sizeof(info->model_name)); + CopyMsgSrc2Dst(r_info.license_type.c_str(), info->license_type, sizeof(info->license_type)); + info->Dof = r_info.DoF; + for (int i = 0; i < kCartDoF; ++i) { + info->K_x_nom[i] = r_info.K_x_nom[i]; + } + for (int i = 0; i < kSerialJointDoF; ++i) { + info->K_q_nom[i] = r_info.K_q_nom[i]; + info->q_min[i] = r_info.q_min[i]; + info->q_max[i] = r_info.q_max[i]; + info->dq_max[i] = r_info.dq_max[i]; + info->tau_max[i] = r_info.tau_max[i]; + } +} + +EXPORT_API int GetMode(Robot* robot) { + switch (robot->mode()) { + case Mode::UNKNOWN: return 0; + case Mode::IDLE: return 1; + case Mode::RT_JOINT_TORQUE: return 2; + case Mode::RT_JOINT_IMPEDANCE: return 3; + case Mode::NRT_JOINT_IMPEDANCE: return 4; + case Mode::RT_JOINT_POSITION: return 5; + case Mode::NRT_JOINT_POSITION: return 6; + case Mode::NRT_PLAN_EXECUTION: return 7; + case Mode::NRT_PRIMITIVE_EXECUTION: return 8; + case Mode::RT_CARTESIAN_MOTION_FORCE: return 9; + case Mode::NRT_CARTESIAN_MOTION_FORCE: return 10; + case Mode::MODES_CNT: return 11; + default: return 0; + } +} + +EXPORT_API void GetStates(Robot* robot, WRobotState* robot_state) { + const RobotStates& states = robot->states(); + for (int i = 0; i < kSerialJointDoF; ++i) { + robot_state->q[i] = states.q[i]; + robot_state->theta[i] = states.theta[i]; + robot_state->dq[i] = states.dq[i]; + robot_state->dtheta[i] = states.dtheta[i]; + robot_state->tau[i] = states.tau[i]; + robot_state->tau_des[i] = states.tau_des[i]; + robot_state->tau_dot[i] = states.tau_dot[i]; + robot_state->tau_ext[i] = states.tau_ext[i]; + } + size_t count = std::min(states.q_e.size(), kMaxExtAxes); + std::copy_n(states.q_e.begin(), count, robot_state->q_e); + count = std::min(states.dq_e.size(), kMaxExtAxes); + std::copy_n(states.dq_e.begin(), count, robot_state->dq_e); + count = std::min(states.tau_e.size(), kMaxExtAxes); + std::copy_n(states.tau_e.begin(), count, robot_state->tau_e); + for (int i = 0; i < kPoseSize; ++i) { + robot_state->tcp_pose[i] = states.tcp_pose[i]; + robot_state->tcp_pose_des[i] = states.tcp_pose_des[i]; + robot_state->flange_pose[i] = states.flange_pose[i]; + } + for (int i = 0; i < kCartDoF; ++i) { + robot_state->tcp_vel[i] = states.tcp_vel[i]; + robot_state->ft_sensor_raw[i] = states.ft_sensor_raw[i]; + robot_state->ext_wrench_in_tcp[i] = states.ext_wrench_in_tcp[i]; + robot_state->ext_wrench_in_world[i] = states.ext_wrench_in_world[i]; + robot_state->ext_wrench_in_tcp_raw[i] = states.ext_wrench_in_tcp_raw[i]; + robot_state->ext_wrench_in_world_raw[i] = states.ext_wrench_in_world_raw[i]; + } +} + +EXPORT_API int IsStopped(Robot* robot) { + return robot->stopped(); +} + +EXPORT_API int IsOperational(Robot* robot, int verbose) { + return robot->operational(verbose); +} + +EXPORT_API int GetOperationalStatus(Robot* robot) { + switch (robot->operational_status()) { + case OperationalStatus::UNKNOWN: return 0; + case OperationalStatus::READY: return 1; + case OperationalStatus::BOOTING: return 2; + case OperationalStatus::ESTOP_NOT_RELEASED: return 3; + case OperationalStatus::NOT_ENABLED: return 4; + case OperationalStatus::RELEASING_BRAKE: return 5; + case OperationalStatus::MINOR_FAULT: return 6; + case OperationalStatus::CRITICAL_FAULT: return 7; + case OperationalStatus::IN_REDUCED_STATE: return 8; + case OperationalStatus::IN_RECOVERY_STATE: return 9; + case OperationalStatus::IN_MANUAL_MODE: return 10; + case OperationalStatus::IN_AUTO_MODE: return 11; + default: return 0; + } +} + +EXPORT_API int IsBusy(Robot* robot) { + return robot->busy(); +} + +EXPORT_API int IsFault(Robot* robot) { + return robot->fault(); +} + +EXPORT_API int IsReduced(Robot* robot) { + return robot->reduced(); +} + +EXPORT_API int IsRecovery(Robot* robot) { + return robot->recovery(); +} + +EXPORT_API int IsEstopReleased(Robot* robot) { + return robot->estop_released(); +} + +EXPORT_API int IsEnablingButtonReleased(Robot* robot) { + return robot->enabling_button_pressed(); +} + +EXPORT_API char* GetMuLog(Robot* robot) { + const auto& mu = robot->mu_log(); + std::map tmp; + tmp["mu_log"] = mu; + std::string json_str = serializeParams(tmp); + return CopyInputString(json_str.c_str()); +} + +//======================================= SYSTEM CONTROL ======================================= +EXPORT_API void Enable(Robot* robot, FlexivError* error) { + try { + robot->Enable(); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void Brake(Robot* robot, int engage, FlexivError* error) { + try { + robot->Brake(engage); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void SwitchMode(Robot* robot, int mode, FlexivError* error) { + static const std::array modeMap = { + Mode::UNKNOWN, Mode::IDLE, Mode::RT_JOINT_TORQUE, Mode::RT_JOINT_IMPEDANCE, + Mode::NRT_JOINT_IMPEDANCE, Mode::RT_JOINT_POSITION, Mode::NRT_JOINT_POSITION, + Mode::NRT_PLAN_EXECUTION, Mode::NRT_PRIMITIVE_EXECUTION, Mode::RT_CARTESIAN_MOTION_FORCE, + Mode::NRT_CARTESIAN_MOTION_FORCE, Mode::MODES_CNT }; + if (mode < 0 || mode >= static_cast(modeMap.size())) { + error->error_code = 1; + CopyExceptionMsg(std::runtime_error("Invalid robot mode index"), error); + return; + } + try { + robot->SwitchMode(modeMap[mode]); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void Stop(Robot* robot, FlexivError* error) { + try { + robot->Stop(); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API int ClearFault(Robot* robot, int timeout_sec, FlexivError* error) { + try { + int flag = robot->ClearFault(timeout_sec); + error->error_code = 0; + return flag; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } + return false; +} + +EXPORT_API void RunAutoRecovery(Robot* robot, FlexivError* error) { + try { + robot->RunAutoRecovery(); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void SetGlobalVariables(Robot* robot, + const char* globalVars, + FlexivError* error) { + try { + auto vars = parseJsonToParams(globalVars); + robot->SetGlobalVariables(vars); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API char* GetGlobalVariables(Robot* robot, FlexivError* error) { + try { + const auto& globalVars = robot->global_variables(); + std::string json_str = serializeParams(globalVars); + return CopyInputString(json_str.c_str()); + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + return nullptr; + } +} + +//======================================= PLAN EXECUTION ======================================= +EXPORT_API void ExecutePlanByIdx(Robot* robot, int idx, int continueExec, + int blockUntilStarted, FlexivError* error) { + try { + robot->ExecutePlan(idx, continueExec, blockUntilStarted); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void ExecutePlanByName(Robot* robot, const char* name, int continueExec, + int blockUntilStarted, FlexivError* error) { + try { + robot->ExecutePlan(std::string(name), continueExec, blockUntilStarted); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void PausePlan(Robot* robot, int pause, FlexivError* error) { + try { + robot->PausePlan(pause); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API char* GetPlanList(Robot* robot, FlexivError* error) { + try { + const auto& plan_list = robot->plan_list(); + error->error_code = 0; + std::map tmp; + tmp["plan_list"] = plan_list; + std::string json_str = serializeParams(tmp); + return CopyInputString(json_str.c_str()); + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } + return nullptr; +} + +EXPORT_API void GetPlanInfo(Robot* robot, WPlanInfo* planInfo, FlexivError* error) { + try { + const auto& info = robot->plan_info(); + CopyMsgSrc2Dst(info.pt_name.c_str(), planInfo->pt_name, sizeof(planInfo->pt_name)); + CopyMsgSrc2Dst(info.node_name.c_str(), planInfo->node_name, sizeof(planInfo->node_name)); + CopyMsgSrc2Dst(info.node_path.c_str(), planInfo->node_path, sizeof(planInfo->node_path)); + CopyMsgSrc2Dst(info.node_path_time_period.c_str(), planInfo->node_path_time_period, sizeof(planInfo->node_path_time_period)); + CopyMsgSrc2Dst(info.node_path_number.c_str(), planInfo->node_path_number, sizeof(planInfo->node_path_number)); + CopyMsgSrc2Dst(info.assigned_plan_name.c_str(), planInfo->assigned_plan_name, sizeof(planInfo->assigned_plan_name)); + planInfo->velocity_scale = info.velocity_scale; + planInfo->waiting_for_step = info.waiting_for_step; + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void SetBreakpointMode(Robot* robot, int IsEnable, FlexivError* error) { + try { + robot->SetBreakpointMode(IsEnable); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void StepBreakpoint(Robot* robot, FlexivError* error) { + try { + robot->StepBreakpoint(); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +//==================================== PRIMITIVE EXECUTION ===================================== +EXPORT_API void ExecutePrimitive(Robot* robot, + const char* primitiveName, + const char* inputParams, + const char* properties, + int blockUntilStarted, + FlexivError* error) { + try { + auto input_params = parseJsonToParams(inputParams); + auto props = parseJsonToParams(properties); + robot->ExecutePrimitive(std::string(primitiveName), input_params, props, blockUntilStarted); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API char* GetPrimitiveStates(Robot* robot, FlexivError* error) { + try { + const auto& primitiveStates = robot->primitive_states(); + std::string json_str = serializeParams(primitiveStates); + return CopyInputString(json_str.c_str()); + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + return nullptr; + } +} + +//==================================== DIRECT JOINT CONTROL ==================================== +EXPORT_API void StreamJointTorque(Robot* robot, const double* pos, int posLen, + int enableGravityComp, int enableSoftLimits, FlexivError* error) { + try { + std::vector positions(pos, pos + posLen); + robot->StreamJointTorque(positions, enableGravityComp, enableSoftLimits); + error->error_code = 0; + } + catch (std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void StreamJointPosition(Robot* robot, const double* pos, int posLen, + const double* vel, int velLen, const double* acc, int accLen, FlexivError* error) { + try { + std::vector positions(pos, pos + posLen); + std::vector velocities(vel, vel + velLen); + std::vector accelerations(acc, acc + accLen); + robot->StreamJointPosition(positions, velocities, accelerations); + error->error_code = 0; + } + catch (std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void SendJointPosition(Robot* robot, const double* pos, int posLen, const double* vel, + int velLen, const double* acc, int accLen, const double* maxVel, int maxVelLen, + const double* maxAcc, int maxAccLen, FlexivError* error) { + try { + std::vector positions(pos, pos + posLen); + std::vector velocities(vel, vel + velLen); + std::vector accelerations(acc, acc + accLen); + std::vector max_vel(maxVel, maxVel + maxVelLen); + std::vector max_acc(maxAcc, maxAcc + maxAccLen); + robot->SendJointPosition(positions, velocities, accelerations, + max_vel, max_acc); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void SetJointImpedance(Robot* robot, const double* Kq, int KqLen, + const double* Zq, int ZqLen, FlexivError* error) { + try { + std::vector K_q(Kq, Kq + KqLen); + std::vector Z_q(Zq, Zq + ZqLen); + robot->SetJointImpedance(K_q, Z_q); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void StreamCartesianMotionForce(Robot* robot, const double* pose, int poseLen, + const double* wrench, int wrenchLen, const double* velocity, int velocityLen, + const double* acceleration, int accelerationLen, FlexivError* error) { + try { + if (poseLen != kPoseSize) + throw std::invalid_argument("StreamCartesianMotionForce pose length must be " + + std::to_string(kPoseSize)); + if (wrenchLen != kCartDoF) + throw std::invalid_argument("StreamCartesianMotionForce wrench length must be " + + std::to_string(kCartDoF)); + if (velocityLen != kCartDoF) + throw std::invalid_argument("StreamCartesianMotionForce velocity length must be " + + std::to_string(kCartDoF)); + if (accelerationLen != kCartDoF) + throw std::invalid_argument("StreamCartesianMotionForce acceleration length must be " + + std::to_string(kCartDoF)); + std::array poseArr; + std::copy(pose, pose + kPoseSize, poseArr.begin()); + std::array wrenchArr{}; + std::copy(wrench, wrench + kCartDoF, wrenchArr.begin()); + std::array velocityArr{}; + std::copy(velocity, velocity + kCartDoF, velocityArr.begin()); + std::array accelerationArr{}; + std::copy(acceleration, acceleration + kCartDoF, accelerationArr.begin()); + robot->StreamCartesianMotionForce(poseArr, wrenchArr, velocityArr, accelerationArr); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void SendCartesianMotionForce(Robot* robot, const double* pose, int poseLen, + const double* wrench, int wrenchLen, double maxLinearVel, double maxAngularVel, + double maxLinearAcc, double maxAngularAcc, FlexivError* error) { + try { + if (poseLen != kPoseSize) + throw std::invalid_argument("SendCartesianMotionForce pose length must be " + + std::to_string(kPoseSize)); + if (wrenchLen != kCartDoF) + throw std::invalid_argument("SendCartesianMotionForce wrench length must be " + + std::to_string(kCartDoF)); + std::array poseArr; + std::copy(pose, pose + kPoseSize, poseArr.begin()); + std::array wrenchArr{}; + std::copy(wrench, wrench + kCartDoF, wrenchArr.begin()); + robot->SendCartesianMotionForce(poseArr, wrenchArr, maxLinearVel, maxAngularVel, + maxLinearAcc, maxAngularAcc); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void SetCartesianImpedance(Robot* robot, const double* Kx, int KxLen, + const double* Zx, int ZxLen, FlexivError* error) { + try { + if (KxLen != kCartDoF) + throw std::invalid_argument("SetCartesianImpedance Kx length must be " + + std::to_string(kCartDoF)); + if (ZxLen != kCartDoF) + throw std::invalid_argument("SetCartesianImpedance Zx length must be " + + std::to_string(kCartDoF)); + std::array KxArr; + std::copy(Kx, Kx + kCartDoF, KxArr.begin()); + std::array ZxArr{}; + std::copy(Zx, Zx + kCartDoF, ZxArr.begin()); + robot->SetCartesianImpedance(KxArr, ZxArr); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void SetMaxContactWrench(Robot* robot, const double* maxWrench, int maxWrenchLen, FlexivError* error) { + try { + if (maxWrenchLen != kCartDoF) + throw std::invalid_argument("SetMaxContactWrench maxWrench length must be " + + std::to_string(kCartDoF)); + std::array maxWrenchArr; + std::copy(maxWrench, maxWrench + maxWrenchLen, maxWrenchArr.begin()); + robot->SetMaxContactWrench(maxWrenchArr); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void SetNullSpacePosture(Robot* robot, const double* refPositions, int refPositionsLen, FlexivError* error) { + try { + std::vector ref_positions(refPositions, refPositions + refPositionsLen); + robot->SetNullSpacePosture(ref_positions); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + + +EXPORT_API void SetNullSpaceObjectives(Robot* robot, double linearManipulability, double angularManipulability, + double refPositionsTracking, FlexivError* error) { + try { + robot->SetNullSpaceObjectives(linearManipulability, angularManipulability, refPositionsTracking); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void SetForceControlAxis(Robot* robot, const int* enabledAxes, int enabledAxesLen, + const double* maxLinearVel, int maxLinearVelLen, FlexivError* error) { + try { + if (enabledAxesLen != kCartDoF) + throw std::invalid_argument("SetForceControlAxis enabledAxes length must be " + + std::to_string(kCartDoF)); + if (maxLinearVelLen != kCartDoF / 2) + throw std::invalid_argument("SetForceControlAxis maxLinearVel length must be " + + std::to_string(kCartDoF / 2)); + std::array enabledAxesArr; + for (int i = 0; i < kCartDoF; ++i) + enabledAxesArr[i] = *(enabledAxes + i); + std::array maxLinearVelArr; + std::copy(maxLinearVel, maxLinearVel + maxLinearVelLen, maxLinearVelArr.begin()); + robot->SetForceControlAxis(enabledAxesArr, maxLinearVelArr); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void SetForceControlFrame(Robot* robot, int rootCoord, const double* TInRobot, int TInRobotLen, FlexivError* error) { + try { + if (TInRobotLen != kPoseSize) + throw std::invalid_argument("SetForceControlFrame TInRobot length must be " + + std::to_string(kPoseSize)); + CoordType coord_type = rootCoord == 0 ? CoordType::WORLD : CoordType::TCP; + std::array T_in_root; + std::copy(TInRobot, TInRobot + TInRobotLen, T_in_root.begin()); + robot->SetForceControlFrame(coord_type, T_in_root); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void SetPassiveForceControl(Robot* robot, int IsEnabled, FlexivError* error) { + try { + robot->SetPassiveForceControl(IsEnabled); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +//======================================== IO CONTROL ======================================== +EXPORT_API void SetDigitalOutput(Robot* robot, int idx, int value, FlexivError* error) { + try { + unsigned int port = idx; + std::vector port_idx{ port }; + std::vector values{ value == 1 }; + robot->SetDigitalOutputs(port_idx, values); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API int GetDigitalOutput(Robot* robot, int idx) { + return robot->digital_inputs()[idx]; +} + +//========================================== TOOL ============================================ +EXPORT_API Tool* CreateTool(Robot* robot, FlexivError* error) { + try { + Tool* tool = new Tool(*robot); + error->error_code = 0; + return tool; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } + return nullptr; +} + +EXPORT_API void DeleteTool(Tool* tool) { + delete tool; +} + +EXPORT_API char* GetToolNames(Tool* tool, FlexivError* error) { + try { + const auto& lst = tool->list(); + error->error_code = 0; + std::map tmp; + tmp["tool_list"] = lst; + std::string json_str = serializeParams(tmp); + return CopyInputString(json_str.c_str()); + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } + return nullptr; +} + +EXPORT_API char* GetToolName(Tool* tool, FlexivError* error) { + try { + std::string name = tool->name(); + error->error_code = 0; + return CopyInputString(name.c_str()); + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } + return nullptr; +} + +EXPORT_API int HasTool(Tool* tool, const char* name, FlexivError* error) { + try { + int flag = tool->exist(std::string(name)); + error->error_code = 0; + return flag; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } + return false; +} + +EXPORT_API void GetToolParams(Tool* tool, WToolParams* toolParams, FlexivError* error) { + try { + const auto& params = tool->params(); + error->error_code = 0; + toolParams->Mass = params.mass; + for (int i = 0; i < 3; ++i) toolParams->CoM[i] = params.CoM[i]; + for (int i = 0; i < 6; ++i) toolParams->Intertia[i] = params.inertia[i]; + for (int i = 0; i < kPoseSize; ++i) toolParams->TcpLocation[i] = params.tcp_location[i]; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void GetToolParamsByName(Tool* tool, const char* name, WToolParams* toolParams, FlexivError* error) { + try { + std::string tool_name(name); + const auto& params = tool->params(tool_name); + error->error_code = 0; + toolParams->Mass = params.mass; + for (int i = 0; i < 3; ++i) toolParams->CoM[i] = params.CoM[i]; + for (int i = 0; i < 6; ++i) toolParams->Intertia[i] = params.inertia[i]; + for (int i = 0; i < kPoseSize; ++i) toolParams->TcpLocation[i] = params.tcp_location[i]; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void AddNewTool(Tool* tool, const char* name, WToolParams* toolParams, FlexivError* error) { + try { + std::string tool_name(name); + ToolParams tool_params; + tool_params.mass = toolParams->Mass; + for (int i = 0; i < 3; ++i) tool_params.CoM[i] = toolParams->CoM[i]; + for (int i = 0; i < 6; ++i) tool_params.inertia[i] = toolParams->Intertia[i]; + for (int i = 0; i < kPoseSize; ++i) tool_params.tcp_location[i] = toolParams->TcpLocation[i]; + tool->Add(tool_name, tool_params); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void SwitchTool(Tool* tool, const char* name, FlexivError* error) { + try { + tool->Switch(name); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void UpdateTool(Tool* tool, const char* name, WToolParams* toolParams, FlexivError* error) { + try { + std::string tool_name(name); + ToolParams tool_params; + tool_params.mass = toolParams->Mass; + for (int i = 0; i < 3; ++i) tool_params.CoM[i] = toolParams->CoM[i]; + for (int i = 0; i < 6; ++i) tool_params.inertia[i] = toolParams->Intertia[i]; + for (int i = 0; i < kPoseSize; ++i) tool_params.tcp_location[i] = toolParams->TcpLocation[i]; + tool->Update(tool_name, tool_params); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void RemoveTool(Tool* tool, const char* name, FlexivError* error) { + try { + tool->Remove(name); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +//======================================= WORK COORD ========================================= +EXPORT_API WorkCoord* CreateWorkCoord(Robot* robot, FlexivError* error) { + try { + WorkCoord* work_coord = new WorkCoord(*robot); + error->error_code = 0; + return work_coord; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } + return nullptr; +} + +EXPORT_API void DeleteWorkCoord(WorkCoord* work_coord) { + delete work_coord; +} + +EXPORT_API char* GetWorkCoordNames(WorkCoord* work_coord, FlexivError* error) { + try { + const auto& lst = work_coord->list(); + error->error_code = 0; + std::map tmp; + tmp["work_coord_list"] = lst; + std::string json_str = serializeParams(tmp); + return CopyInputString(json_str.c_str()); + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } + return nullptr; +} + +EXPORT_API int HasWorkCoord(WorkCoord* work_coord, const char* name, FlexivError* error) { + try { + int flag = work_coord->exist(name); + error->error_code = 0; + return flag; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } + return 0; +} + +EXPORT_API void GetWorkCoordPose(WorkCoord* workCoord, const char* name, double& x, double& y, + double& z, double& qw, double& qx, double& qy, double& qz, FlexivError* error) { + try { + const auto& pose = workCoord->pose(name); + error->error_code = 0; + x = pose[0]; + y = pose[1]; + z = pose[2]; + qw = pose[3]; + qx = pose[4]; + qy = pose[5]; + qz = pose[6]; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void AddWorkCoord(WorkCoord* workCoord, const char* name, double* pose, int poseLen, FlexivError* error) { + try { + if (poseLen != kPoseSize) + throw std::invalid_argument("AddWorkCoord pose length must be " + + std::to_string(kPoseSize)); + std::array poseArr; + std::copy(pose, pose + poseLen, poseArr.begin()); + workCoord->Add(name, poseArr); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void UpdateWorkCoord(WorkCoord* workCoord, const char* name, double* pose, int poseLen, FlexivError* error) { + try { + if (poseLen != kPoseSize) + throw std::invalid_argument("UpdateWorkCoord pose length must be " + + std::to_string(kPoseSize)); + std::array poseArr; + std::copy(pose, pose + poseLen, poseArr.begin()); + workCoord->Update(name, poseArr); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void RemoveWorkCoord(WorkCoord* workCoord, const char* name, FlexivError* error) { + try { + workCoord->Remove(name); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +//======================================== GRIPPER =========================================== +EXPORT_API Gripper* CreateGripper(Robot* robot, FlexivError* error) { + try { + Gripper* gripper = new Gripper(*robot); + error->error_code = 0; + return gripper; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } + return nullptr; +} + +EXPORT_API void DeleteGripper(Gripper* gripper) { + delete gripper; +} + +EXPORT_API void Init(Gripper* gripper, FlexivError* error) { + try { + gripper->Init(); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void Grasp(Gripper* gripper, double force, FlexivError* error) { + try { + gripper->Grasp(force); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void Move(Gripper* gripper, double width, double velocity, double forceLimit, FlexivError* error) { + try { + gripper->Move(width, velocity, forceLimit); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void StopGripper(Gripper* gripper) { + gripper->Stop(); +} + +EXPORT_API int GripperIsMoving(Gripper* gripper) { + return gripper->moving(); +} + +EXPORT_API void GetGripperStates(Gripper* gripper, WGripperStates* states) { + const auto& st = gripper->states(); + states->width = st.width; + states->force = st.force; + states->max_width = st.max_width; +} + +//======================================== FILE IO =========================================== +EXPORT_API FileIO* CreateFileIO(Robot* robot, FlexivError* error) { + try { + FileIO* fileIO = new FileIO(*robot); + error->error_code = 0; + return fileIO; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } + return nullptr; +} + +EXPORT_API void DeleteFileIO(FileIO* fileIO) { + delete fileIO; +} + +EXPORT_API void UploadTrajFile(FileIO* fileIO, const char* fileDir, const char* fileName, FlexivError* error) { + try { + fileIO->UploadTrajFile(fileDir, fileName); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +//========================================= DEVICE =========================================== +EXPORT_API Device* CreateDevice(Robot* robot, FlexivError* error) { + try { + Device* device = new Device(*robot); + error->error_code = 0; + return device; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } + return nullptr; +} + +EXPORT_API void DeleteDevice(Device* device) { + delete device; +} + +EXPORT_API char* GetDevicesList(Device* device, FlexivError* error) { + try { + const auto& devices_list = device->list(); + std::string json_str = json(devices_list).dump(); + return CopyInputString(json_str.c_str()); + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + return nullptr; + } +} + +EXPORT_API int HasDevice(Device* device, const char* name, FlexivError* error) { + try { + int flag = device->exist(name); + error->error_code = 0; + return flag; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + return 0; + } +} + +EXPORT_API void EnableDevice(Device* device, const char* name, FlexivError* error) { + try { + device->Enable(name); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void DisableDevice(Device* device, const char* name, FlexivError* error) { + try { + device->Disable(name); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} + +EXPORT_API void SendCommands(Device* device, const char* name, const char* cmds, FlexivError* error) { + try { + json json_obj = json::parse(cmds); + std::map> device_cmds; + for (auto& [key, value] : json_obj.items()) { + if (value.is_number_integer()) { + device_cmds[key] = value.get(); + } + else if (value.is_number_float()) { + device_cmds[key] = value.get(); + } + } + device->Command(name, device_cmds); + error->error_code = 0; + } + catch (const std::exception& e) { + error->error_code = 1; + CopyExceptionMsg(e, error); + } +} \ No newline at end of file diff --git a/csharp/Examples/Basics1DisplayRobotStates.cs b/csharp/Examples/Basics1DisplayRobotStates.cs new file mode 100644 index 0000000..1952632 --- /dev/null +++ b/csharp/Examples/Basics1DisplayRobotStates.cs @@ -0,0 +1,78 @@ +using System; +using System.Threading; +using FlexivRdkCSharp.FlexivRdk; + +namespace FlexivRdkCSharp.Examples +{ + class Basics1DisplayRobotStates : IExample + { + public string Name => "basics1_display_robot_states"; + public string Description => "This tutorial checks connection with the robot and continuously prints its states."; + public string Usage => +@" +Usage: + basics1_display_robot_states +Description: + Check connection with the robot and continuously print its states. +Required arguments: + Serial number of the robot to connect to. + Remove any space. For example: Rizon4s-123456 +Optional arguments: + (none) +"; + static void PrintRobotStates(Robot robot) + { + while (true) + { + Utility.SpdlogInfo("Current robot states:"); + Console.WriteLine(robot.GetStates().ToString()); + Thread.Sleep(1000); + } + } + + public void Run(string[] args) + { + if (args.Length < 1) + { + Console.WriteLine(Usage); + return; + } + Utility.SpdlogInfo(">>> Tutorial description <<<\nThis tutorial does the very first thing: check connection " + + "with the robot server and print received robot states.\n"); + string robotSN = args[0]; + try + { + // Instantiate robot interface + var robot = new Robot(robotSN); + // Clear fault on the connected robot if any + if (robot.IsFault()) + { + Utility.SpdlogWarn("Fault occurred on the connected robot, trying to clear ..."); + // Try to clear the fault + if (!robot.ClearFault()) + { + Utility.SpdlogError("Fault cannot be cleared, exiting ..."); + return; + } + Utility.SpdlogInfo("Fault on the connected robot is cleared"); + } + // Enable the robot, make sure the E-stop is released before enabling + Utility.SpdlogInfo("Enabling robot ..."); + robot.Enable(); + // Wait for the robot to become operational + while (!robot.IsOperational()) + { + Thread.Sleep(1000); + } + Utility.SpdlogInfo("Robot is now operational"); + Thread printThread = new(() => PrintRobotStates(robot)); + printThread.Start(); + printThread.Join(); + } + catch (Exception ex) + { + Utility.SpdlogError(ex.Message); + } + } + } +} diff --git a/csharp/Examples/Basics2ClearFault.cs b/csharp/Examples/Basics2ClearFault.cs new file mode 100644 index 0000000..fb64986 --- /dev/null +++ b/csharp/Examples/Basics2ClearFault.cs @@ -0,0 +1,59 @@ +using System; +using FlexivRdkCSharp.FlexivRdk; + +namespace FlexivRdkCSharp.Examples +{ + class Basics2ClearFault : IExample + { + public string Name => "basics2_clear_fault"; + public string Description => "This tutorial clears minor or critical faults, if any, of the connected robot."; + public string Usage => +@" +Usage: + basics2_clear_fault +Description: + Clear minor or critial faults, if any, of the connected robot. +Required arguments: + Serial number of the robot to connect to. + Remove any space. For example: Rizon4s-123456 +Optional arguments: + (none) +"; + public void Run(string[] args) + { + if (args.Length < 1) + { + Console.WriteLine(Usage); + return; + } + Utility.SpdlogInfo(">>> Tutorial description <<<\nThis tutorial clears minor or critical faults, if any, of " + + "the connected robot.\n"); + string robotSN = args[0]; + try + { + // Instantiate robot interface + var robot = new Robot(robotSN); + // Clear fault on the connected robot if any + if (robot.IsFault()) + { + Utility.SpdlogWarn("Fault occurred on the connected robot, trying to clear ..."); + // Try to clear the fault + if (!robot.ClearFault()) + { + Utility.SpdlogError("Fault cannot be cleared, exiting ..."); + return; + } + Utility.SpdlogInfo("Fault on the connected robot is cleared"); + } + else + { + Utility.SpdlogInfo("No fault on the connected robot"); + } + } + catch (Exception ex) + { + Utility.SpdlogError(ex.Message); + } + } + } +} diff --git a/csharp/Examples/Basics3PrimitiveExecution.cs b/csharp/Examples/Basics3PrimitiveExecution.cs new file mode 100644 index 0000000..13add3c --- /dev/null +++ b/csharp/Examples/Basics3PrimitiveExecution.cs @@ -0,0 +1,133 @@ +using System; +using System.Threading; +using System.Collections.Generic; +using FlexivRdkCSharp.FlexivRdk; + +namespace FlexivRdkCSharp.Examples +{ + class Basics3PrimitiveExecution : IExample + { + public string Name => "basics3_primitive_execution"; + public string Description => "This tutorial executes several basic robot primitives (unit skills)."; + public string Usage => +@" +Usage: + basics3_primitive_execution +Description: + Execute several basic robot primitives (unit skills). +Required arguments: + Serial number of the robot to connect to. + Remove any space. For example: Rizon4s-123456 +Optional arguments: + (none) +"; + public void Run(string[] args) + { + if (args.Length < 1) + { + Console.WriteLine(Usage); + return; + } + Utility.SpdlogInfo(">>> Tutorial description <<<\nThis tutorial executes several basic robot primitives (unit " + + "skills). For detailed documentation on all available primitives, please see [Flexiv " + + "Primitives](https://www.flexiv.com/primitives/).\n"); + string robotSN = args[0]; + try + { + // Instantiate robot interface + var robot = new Robot(robotSN); + // Clear fault on the connected robot if any + if (robot.IsFault()) + { + Utility.SpdlogWarn("Fault occurred on the connected robot, trying to clear ..."); + // Try to clear the fault + if (!robot.ClearFault()) + { + Utility.SpdlogError("Fault cannot be cleared, exiting ..."); + return; + } + Utility.SpdlogInfo("Fault on the connected robot is cleared"); + } + Utility.SpdlogInfo("Enabling robot ..."); + // Enable the robot, make sure the E-stop is released before enabling + robot.Enable(); + // Wait for the robot to become operational + while (!robot.IsOperational()) + { + Thread.Sleep(1000); + } + Utility.SpdlogInfo("Robot is now operational"); + // Switch to primitive execution mode + robot.SwitchMode(RobotMode.NRT_PRIMITIVE_EXECUTION); + // (1) Go to home pose + Utility.SpdlogInfo("Executing primitive: Home"); + robot.ExecutePrimitive("Home", new Dictionary()); + // Wait for reached target + while (!(FlexivDataUtils.TryGet(robot.GetPrimitiveStates(), + "reachedTarget", out var flag) && flag == 1)) + { + Thread.Sleep(1000); + } + // (2) Move robot joints to target positions + Utility.SpdlogInfo("Executing primitive: MoveJ"); + robot.ExecutePrimitive("MoveJ", new Dictionary { + // unit: deg + {"target", new JPos(30, -45, 0, 90, 0, 40, 30, -50, 30) }, + {"waypoints",new List { + new JPos(10, -30, 10, 30, 10, 15, 10, -15, 10), + new JPos(20, -60, -10, 60, -10, 30, 20, -30, 20) + } }, + }, new Dictionary { + {"lockExternalAxes", 0 } + }); + // Wait for reached target + while (!(FlexivDataUtils.TryGet(robot.GetPrimitiveStates(), + "reachedTarget", out var flag) && flag == 1)) + { + Utility.SpdlogInfo("Current primitive states:"); + Console.WriteLine(Utility.FlexivDataDictToString(robot.GetPrimitiveStates())); + Thread.Sleep(1000); + } + // (3) Move robot TCP to a target pose in world (base) frame + Utility.SpdlogInfo("Executing primitive: MoveL"); + robot.ExecutePrimitive("MoveL", new Dictionary { + {"target", new Coord(0.65, -0.3, 0.2, 180, 0, 180) }, // unit: m-deg + {"waypoints", new List + { + // unit: m-deg + new Coord(0.45, 0.1, 0.2, 180, 0, 180), + new Coord(0.45, -0.3, 0.2, 180, 0, 180) + } }, + // unit: m/s + {"vel", 0.6 }, + {"zoneRadius", "Z50" } + }); + while (!(FlexivDataUtils.TryGet(robot.GetPrimitiveStates(), + "reachedTarget", out var flag) && flag == 1)) // Wait for reached target + { + Thread.Sleep(1000); + } + // (4) Another MoveL that uses TCP frame + Utility.SpdlogInfo("Executing primitive: MoveL"); + robot.ExecutePrimitive("MoveL", new Dictionary { + // x y z qw qx qy qz + {"target", new Coord(0.0, 0.0, 0.0, 0.9185587, 0.1767767, 0.3061862, 0.1767767, + "TRAJ", "START") }, + {"vel", 0.2 } + }); + // Wait for reached target + while (!(FlexivDataUtils.TryGet(robot.GetPrimitiveStates(), + "reachedTarget", out var flag) && flag == 1)) + { + Thread.Sleep(1000); + } + // All done, stop robot and put into IDLE mode + robot.Stop(); + } + catch (Exception ex) + { + Utility.SpdlogError(ex.Message); + } + } + } +} diff --git a/csharp/Examples/Basics4PlanExecution.cs b/csharp/Examples/Basics4PlanExecution.cs new file mode 100644 index 0000000..0eeede4 --- /dev/null +++ b/csharp/Examples/Basics4PlanExecution.cs @@ -0,0 +1,127 @@ +using System; +using System.Threading; +using FlexivRdkCSharp.FlexivRdk; + +namespace FlexivRdkCSharp.Examples +{ + class Basics4PlanExecution : IExample + { + public string Name => "basics4_plan_execution"; + public string Description => "This tutorial executes a plan selected by the user from a list of available plans."; + public string Usage => +@" +Usage: + basics4_plan_execution +Description: + Execute a plan selected by the user from a list of available plans. +Required arguments: + Serial number of the robot to connect to. + Remove any space. For example: Rizon4s-123456 +Optional arguments: + (none) +"; + public void Run(string[] args) + { + if (args.Length < 1) + { + Console.WriteLine(Usage); + return; + } + Utility.SpdlogInfo(">>> Tutorial description <<<\nThis tutorial executes a plan selected by the user from a " + + "list of available plans. A plan is a pre-written script to execute a series of robot " + + "primitives with pre-defined transition conditions between 2 adjacent primitives. Users " + + "can use Flexiv Elements to compose their own plan and assign to the robot, which " + + "will appear in the plan list.\n"); + string robotSN = args[0]; + try + { + // Instantiate robot interface + var robot = new Robot(robotSN); + // Clear fault on the connected robot if any + if (robot.IsFault()) + { + Utility.SpdlogWarn("Fault occurred on the connected robot, trying to clear ..."); + // Try to clear the fault + if (!robot.ClearFault()) + { + Utility.SpdlogError("Fault cannot be cleared, exiting ..."); + return; + } + Utility.SpdlogInfo("Fault on the connected robot is cleared"); + } + Utility.SpdlogInfo("Enabling robot ..."); + // Enable the robot, make sure the E-stop is released before enabling + robot.Enable(); + // Wait for the robot to become operational + while (!robot.IsOperational()) + { + Thread.Sleep(1000); + } + Utility.SpdlogInfo("Robot is now operational"); + // Switch to plan execution mode + robot.SwitchMode(RobotMode.NRT_PLAN_EXECUTION); + while (!robot.IsFault()) + { + Utility.SpdlogInfo("Choose an action:"); + Console.WriteLine(" [1] Show available plans"); + Console.WriteLine(" [2] Execute a plan by index"); + Console.WriteLine(" [3] Execute a plan by name"); + Console.WriteLine(" [q] exit"); + string user_input = Console.ReadLine(); + if (user_input.ToLower() == "q") + { + Utility.SpdlogInfo("Exit ..."); + break; + } + int choice; + bool isValid = int.TryParse(user_input, out choice); + if (!isValid || choice < 1 || choice > 3) + { + Utility.SpdlogInfo("Invalid selection, please enter 1 to 3 or 'q' to exit."); + continue; + } + switch (choice) + { + case 1: + var plan_list = robot.GetPlanList(); + for (int i = 0; i < plan_list.Count; i++) + { + Console.WriteLine($"[{i}] {plan_list[i]}"); + } + break; + case 2: + Console.WriteLine("Enter plan index to execute:"); + user_input = Console.ReadLine(); + isValid = int.TryParse(user_input, out choice); + if (!isValid) break; + robot.ExecutePlan(choice, true); + while (robot.IsBusy()) + { + Utility.SpdlogInfo("Current plan info:"); + Console.WriteLine(robot.GetPlanInfo().ToString()); + Thread.Sleep(1000); + } + break; + case 3: + Console.WriteLine("Enter plan name to execute:"); + user_input = Console.ReadLine(); + robot.ExecutePlan(user_input, true); + while (robot.IsBusy()) + { + Utility.SpdlogInfo("Current plan info:"); + Console.WriteLine(robot.GetPlanInfo().ToString()); + Thread.Sleep(1000); + } + break; + default: + break; + } + } + } + catch (Exception ex) + { + Utility.SpdlogError(ex.Message); + } + } + } +} diff --git a/csharp/Examples/Basics5ZeroFTSensor.cs b/csharp/Examples/Basics5ZeroFTSensor.cs new file mode 100644 index 0000000..d44b989 --- /dev/null +++ b/csharp/Examples/Basics5ZeroFTSensor.cs @@ -0,0 +1,83 @@ +using System; +using System.Threading; +using System.Collections.Generic; +using FlexivRdkCSharp.FlexivRdk; +using System.Linq; + +namespace FlexivRdkCSharp.Examples +{ + class Basics5ZeroFTSensor : IExample + { + public string Name => "basics5_zero_ft_sensor"; + public string Description => "This tutorial zeros the robot's force and torque sensors."; + public string Usage => +@" +Usage: + basics5_zero_ft_sensor +Description: + Execute several basic robot primitives (unit skills). +Required arguments: + Serial number of the robot to connect to. + Remove any space. For example: Rizon4s-123456 +Optional arguments: + (none) +"; + public void Run(string[] args) + { + if (args.Length < 1) + { + Console.WriteLine(Usage); + return; + } + Utility.SpdlogInfo(">>> Tutorial description <<<\nThis tutorial zeros the robot's force and torque sensors, " + + "which is a recommended (but not mandatory) step before any operations that require " + + "accurate force/torque measurement.\n"); + string robotSN = args[0]; + try + { + // Instantiate robot interface + var robot = new Robot(robotSN); + // Clear fault on the connected robot if any + if (robot.IsFault()) + { + Utility.SpdlogWarn("Fault occurred on the connected robot, trying to clear ..."); + // Try to clear the fault + if (!robot.ClearFault()) + { + Utility.SpdlogError("Fault cannot be cleared, exiting ..."); + return; + } + Utility.SpdlogInfo("Fault on the connected robot is cleared"); + } + Utility.SpdlogInfo("Enabling robot ..."); + // Enable the robot, make sure the E-stop is released before enabling + robot.Enable(); + // Wait for the robot to become operational + while (!robot.IsOperational()) + { + Thread.Sleep(1000); + } + Utility.SpdlogInfo($"TCP force and moment reading in base frame BEFORE sensor zeroing: " + + $"{string.Join(", ", robot.GetStates().ExtWrenchInWorld.Select(x => x.ToString("F3")))} N-Nm"); + // Run the "ZeroFTSensor" primitive to automatically zero force and torque sensors + robot.SwitchMode(RobotMode.NRT_PRIMITIVE_EXECUTION); + robot.ExecutePrimitive("ZeroFTSensor", new Dictionary()); + // WARNING: during the process, the robot must not contact anything, otherwise the result + // will be inaccurate and affect following operations + Utility.SpdlogWarn("Zeroing force/torque sensors, make sure nothing is in contact with the robot"); + // Wait for the primitive completion + while (robot.IsBusy()) + { + Thread.Sleep(1000); + } + Utility.SpdlogInfo("Sensor zeroing complete"); + Utility.SpdlogInfo($"TCP force and moment reading in base frame BEFORE sensor zeroing: " + + $"{string.Join(", ", robot.GetStates().ExtWrenchInWorld.Select(x => x.ToString("F3")))} N-Nm"); + } + catch (Exception ex) + { + Utility.SpdlogError(ex.Message); + } + } + } +} diff --git a/csharp/Examples/Basics6GripperControl.cs b/csharp/Examples/Basics6GripperControl.cs new file mode 100644 index 0000000..3839522 --- /dev/null +++ b/csharp/Examples/Basics6GripperControl.cs @@ -0,0 +1,131 @@ +using System; +using System.Threading; +using FlexivRdkCSharp.FlexivRdk; + +namespace FlexivRdkCSharp.Examples +{ + class Basics6GripperControl : IExample + { + public string Name => "basics6_gripper_control"; + public string Description => "This tutorial does position and force (if available) control of grippers supported by Flexiv."; + public string Usage => +@" +Usage: + basics6_gripper_control +Description: + Execute several basic robot primitives (unit skills). +Required arguments: + Serial number of the robot to connect to. + Remove any space. For example: Rizon4s-123456 +Optional arguments: + (none) +"; + private static int _stopFlag = 0; + static void PrintGripperStates(Gripper gripper) + { + while (Interlocked.CompareExchange(ref _stopFlag, 0, 0) == 0) + { + Utility.SpdlogInfo("Current gripper states:"); + var states = gripper.GetGripperStates(); + Console.WriteLine($" width: {Math.Round(states.Width, 2)}"); + Console.WriteLine($" force: {Math.Round(states.Force, 2)}"); + Console.WriteLine($" max_width: {Math.Round(states.MaxWidth, 2)}"); + Console.WriteLine($" moving: {gripper.IsMoving()}"); + Console.WriteLine(); + Thread.Sleep(1000); + } + } + public void Run(string[] args) + { + if (args.Length < 1) + { + Console.WriteLine(Usage); + return; + } + Utility.SpdlogInfo(">>> Tutorial description <<<\nThis tutorial does position and force (if available) " + + "control of grippers supported by Flexiv.\n"); + string robotSN = args[0]; + try + { + // Instantiate robot interface + var robot = new Robot(robotSN); + // Clear fault on the connected robot if any + if (robot.IsFault()) + { + Utility.SpdlogWarn("Fault occurred on the connected robot, trying to clear ..."); + // Try to clear the fault + if (!robot.ClearFault()) + { + Utility.SpdlogError("Fault cannot be cleared, exiting ..."); + return; + } + Utility.SpdlogInfo("Fault on the connected robot is cleared"); + } + Utility.SpdlogInfo("Enabling robot ..."); + // Enable the robot, make sure the E-stop is released before enabling + robot.Enable(); + // Wait for the robot to become operational + while (!robot.IsOperational()) + { + Thread.Sleep(1000); + } + Utility.SpdlogInfo("Robot is now operational"); + // Gripper control is not available if the robot is in IDLE mode, so switch to some mode + robot.SwitchMode(RobotMode.NRT_PLAN_EXECUTION); + robot.ExecutePlan("PLAN-Home"); + Thread.Sleep(1000); + var gripper = new Gripper(robot); + Utility.SpdlogInfo("Initializing gripper, this process takes about 10 seconds ..."); + gripper.Init(); + Utility.SpdlogInfo("Initialization complete"); + Thread printThread = new Thread(() => PrintGripperStates(gripper)); + printThread.Start(); + // Loop until the printThread activates + while (!printThread.IsAlive) + ; + // Position control + Utility.SpdlogInfo("Closing gripper"); + gripper.Move(0.01, 0.1, 20); + Thread.Sleep(2000); + Utility.SpdlogInfo("Opening gripper"); + gripper.Move(0.09, 0.1, 20); + Thread.Sleep(2000); + // Stop + Utility.SpdlogInfo("Closing gripper"); + gripper.Move(0.01, 0.1, 20); + Thread.Sleep(500); + Utility.SpdlogInfo("Stopping gripper"); + gripper.Stop(); + Thread.Sleep(2000); + Utility.SpdlogInfo("Closing gripper"); + gripper.Move(0.01, 0.1, 20); + Thread.Sleep(2000); + Utility.SpdlogInfo("Opening gripper"); + gripper.Move(0.09, 0.1, 20); + Thread.Sleep(500); + Utility.SpdlogInfo("Stopping gripper"); + gripper.Stop(); + Thread.Sleep(2000); + // Force control, if available (sensed force is not zero) + if (Math.Abs(gripper.GetGripperStates().Force) > double.Epsilon) + { + Utility.SpdlogInfo("Gripper running zero force control"); + gripper.Grasp(0); + // Exit after 10 seconds + Thread.Sleep(10000); + } + // Finished + gripper.Stop(); + Interlocked.Exchange(ref _stopFlag, 1); + Utility.SpdlogInfo("Stopping print thread"); + printThread.Join(); + Utility.SpdlogInfo("Print thread exited"); + Utility.SpdlogInfo("Program finished"); + } + catch (Exception ex) + { + Utility.SpdlogError(ex.Message); + } + } + } +} diff --git a/csharp/Examples/Basics7AutoRecovery.cs b/csharp/Examples/Basics7AutoRecovery.cs new file mode 100644 index 0000000..7bed798 --- /dev/null +++ b/csharp/Examples/Basics7AutoRecovery.cs @@ -0,0 +1,60 @@ +using System; +using System.Threading; +using FlexivRdkCSharp.FlexivRdk; + +namespace FlexivRdkCSharp.Examples +{ + class Basics7AutoRecovery : IExample + { + public string Name => "basics7_auto_recovery"; + public string Description => "This tutorial runs an automatic recovery process if the " + + "robot's safety system is in recovery state."; + public string Usage => +@" +Usage: + basics7_auto_recovery +Description: + Execute several basic robot primitives (unit skills). +Required arguments: + Serial number of the robot to connect to. + Remove any space. For example: Rizon4s-123456 +Optional arguments: + (none) +"; + public void Run(string[] args) + { + if (args.Length < 1) + { + Console.WriteLine(Usage); + return; + } + Utility.SpdlogInfo(">>> Tutorial description <<<\nThis tutorial runs an automatic recovery process if the " + + "robot's safety system is in recovery state. See flexiv::rdk::Robot::recovery() and RDK " + + "manual for more details.\n"); + string robotSN = args[0]; + try + { + // Instantiate robot interface + var robot = new Robot(robotSN); + // Enable the robot, make sure the E-stop is released before enabling + Utility.SpdlogInfo("Enabling robot ..."); + robot.Enable(); + // Run Auto-recovery + // If the system is in recovery state, we can't use isOperational to tell if the enabling + // process is done, so just wait long enough for the process to finish + Thread.Sleep(8000); + // Run automatic recovery if the system is in recovery state, the involved joints will starts + // to move back into allowed position range + if (robot.IsRecovery()) + robot.RunAutoRecovery(); + // Otherwise the system is normal, do nothing + else + Utility.SpdlogInfo("Robot system is not in recovery state, nothing to be done, exiting ..."); + } + catch (Exception ex) + { + Utility.SpdlogError(ex.Message); + } + } + } +} diff --git a/csharp/Examples/Basics8UpdateRobotTool.cs b/csharp/Examples/Basics8UpdateRobotTool.cs new file mode 100644 index 0000000..3ffb4c1 --- /dev/null +++ b/csharp/Examples/Basics8UpdateRobotTool.cs @@ -0,0 +1,119 @@ +using System; +using System.Threading; +using FlexivRdkCSharp.FlexivRdk; + +namespace FlexivRdkCSharp.Examples +{ + class Basics8UpdateRobotTool : IExample + { + public string Name => "basics8_update_robot_tool"; + public string Description => "This tutorial shows how to online update and interact with the robot tools."; + public string Usage => +@" +Usage: + basics8_update_robot_tool +Description: + Execute several basic robot primitives (unit skills). +Required arguments: + Serial number of the robot to connect to. + Remove any space. For example: Rizon4s-123456 +Optional arguments: + (none) +"; + public void Run(string[] args) + { + if (args.Length < 1) + { + Console.WriteLine(Usage); + return; + } + Utility.SpdlogInfo(">>> Tutorial description <<<\nThis tutorial shows how to online update and interact with " + + "the robot tools. All changes made to the robot tool system will take effect immediately " + + "without needing to reboot. However, the robot must be put into IDLE mode when making these changes.\n"); + string robotSN = args[0]; + try + { + // Instantiate robot interface + var robot = new Robot(robotSN); + // Clear fault on the connected robot if any + if (robot.IsFault()) + { + Utility.SpdlogWarn("Fault occurred on the connected robot, trying to clear ..."); + // Try to clear the fault + if (!robot.ClearFault()) + { + Utility.SpdlogError("Fault cannot be cleared, exiting ..."); + return; + } + Utility.SpdlogInfo("Fault on the connected robot is cleared"); + } + Utility.SpdlogInfo("Enabling robot ..."); + // Enable the robot, make sure the E-stop is released before enabling + robot.Enable(); + // Wait for the robot to become operational + while (!robot.IsOperational()) + { + Thread.Sleep(1000); + } + Utility.SpdlogInfo("Robot is now operational"); + // Update Robot Tool, make sure the robot is in IDLE mode + robot.SwitchMode(RobotMode.IDLE); + // Instantiate tool interface + var tool = new Tool(robot); + // Get and print a list of already configured tools currently in the robot's tools pool + Utility.SpdlogInfo("All configured tools:"); + var toolList = tool.GetToolNames(); + for (int i = 0; i < toolList.Count; i++) + { + Console.WriteLine($"[{i}] {toolList[i]}"); + } + Console.WriteLine(); + // Get and print the current active tool + Utility.SpdlogInfo($"Current active tool: [{tool.GetToolName()}]"); + // Set name and parameters for a new tool + string newToolName = "ExampleTool1"; + ToolParams newToolParams = new(); + newToolParams.Mass = 0.9; + newToolParams.CoM = new double[] { 0.0, 0.0, 0.057 }; + newToolParams.Inertia = new double[] { 2.768e-03, 3.149e-03, 5.64e-04, 0.0, 0.0, 0.0 }; + newToolParams.TcpLocation = new double[] { 0.0, -0.207, 0.09, 0.7071068, 0.7071068, 0.0, 0.0 }; + // If there's already a tool with the same name in the robot's tools pool, then remove it + // first, because duplicate tool names are not allowed + if (tool.HasTool(newToolName)) + { + Utility.SpdlogWarn($"Tool with the same name [{newToolName}] already exists, removing it now"); + // Switch to other tool or no tool (Flange) before removing the current tool + tool.SwitchTool("Flange"); + tool.RemoveTool(newToolName); + } + // Add the new tool + Utility.SpdlogInfo($"Adding new tool [{newToolName}] to the robot"); + tool.AddNewTool(newToolName, newToolParams); + // Get and print the tools list again, the new tool should appear at the end + Utility.SpdlogInfo("All configured tools:"); + toolList = tool.GetToolNames(); + for (int i = 0; i < toolList.Count; i++) + { + Console.WriteLine($"[{i}] {toolList[i]}"); + } + Console.WriteLine(); + // Switch to the newly added tool, i.e. set it as the active tool + Utility.SpdlogInfo($"Switch to tool [{newToolName}]"); + tool.SwitchTool(newToolName); + // Get and print the current active tool again, should be the new tool + Utility.SpdlogInfo($"Current active tool: [{tool.GetToolName()}]"); + // Switch to other tool or no tool (Flange) before removing the current tool + tool.SwitchTool("Flange"); + // Clean up by removing the new tool + Thread.Sleep(2000); + Utility.SpdlogInfo($"Removing tool [{newToolName}]"); + tool.RemoveTool(newToolName); + Utility.SpdlogInfo("Program finished"); + } + catch (Exception ex) + { + Utility.SpdlogError(ex.Message); + } + } + } +} diff --git a/csharp/Examples/Basics9GlobalVariables.cs b/csharp/Examples/Basics9GlobalVariables.cs new file mode 100644 index 0000000..cfea58d --- /dev/null +++ b/csharp/Examples/Basics9GlobalVariables.cs @@ -0,0 +1,111 @@ +using System; +using System.Collections.Generic; +using System.Threading; +using FlexivRdkCSharp.FlexivRdk; + +namespace FlexivRdkCSharp.Examples +{ + class Basics9GlobalVariables : IExample + { + public string Name => "basics9_global_variables"; + public string Description => "This tutorial shows how to get and set global variables."; + public string Usage => +@" +Usage: + basics9_global_variables +Description: + Execute several basic robot primitives (unit skills). +Required arguments: + Serial number of the robot to connect to. + Remove any space. For example: Rizon4s-123456 +Optional arguments: + (none) +"; + public void Run(string[] args) + { + if (args.Length < 1) + { + Console.WriteLine(Usage); + return; + } + Utility.SpdlogInfo(">>> Tutorial description <<<\nThis tutorial shows how to get and set global variables.\n"); + string robotSN = args[0]; + try + { + // Instantiate robot interface + var robot = new Robot(robotSN); + // Clear fault on the connected robot if any + if (robot.IsFault()) + { + Utility.SpdlogWarn("Fault occurred on the connected robot, trying to clear ..."); + // Try to clear the fault + if (!robot.ClearFault()) + { + Utility.SpdlogError("Fault cannot be cleared, exiting ..."); + return; + } + Utility.SpdlogInfo("Fault on the connected robot is cleared"); + } + Utility.SpdlogInfo("Enabling robot ..."); + // Enable the robot, make sure the E-stop is released before enabling + robot.Enable(); + // Wait for the robot to become operational + while (!robot.IsOperational()) + { + Thread.Sleep(1000); + } + Utility.SpdlogInfo("Robot is now operational"); + // Get existing global variables + var globalVars = robot.GetGlobalVariables(); + if (globalVars.Count == 0) + { + Utility.SpdlogWarn("No global variables available"); + return; + } + else + { + Utility.SpdlogInfo("Existing global variables and their original values:"); + Console.WriteLine(Utility.FlexivDataDictToString(globalVars)); + } + // Set global variables + // WARNING: These specified global variables need to be created first using Flexiv Elements + Utility.SpdlogInfo("Setting new values to existing global variables"); + robot.SetGlobalVariables(new Dictionary { + {"test_bool", 1}, + {"test_int", 100}, + {"test_double", 100.123}, + {"test_string", "Flexiv"}, + {"test_int_vec", new List{1, 2, 3} }, + {"test_double_vec", new List{1.1, 2.2, 3.3} }, + {"test_string_vec", new List{"Go", "Flexiv", "Go!"}}, + {"test_pose", new List{0.1, -0.2, 0.3, -90, -45, 120}}, + {"test_coord", new Coord(0.1, -0.2, 0.3, -90, -45, 120, "WORK", "WORLD_ORIGIN", + new double[]{1, 2, 3, 4, 5, 6, 7}, new double[]{10, 20, 0, 0, 0, 0}) }, + {"test_coord_array", new List { + new Coord(1, 2, 3, 4, 5, 6, "WORK", "WorkCoord0"), + new Coord(10, 20, 30, 40, 50, 60, "WORLD", "WORLD_ORIGIN", + new double[]{1, 2, 3, 4, 5, 6, 7}, new double[]{10, 20, 0, 0, 0, 0}), + new Coord(3, 2, 1, 180, 0, 180, "WORLD", "WORLD_ORIGIN"), + }}, + }); + // Get updated global variables + globalVars = robot.GetGlobalVariables(); + if (globalVars.Count == 0) + { + Utility.SpdlogWarn("No global variables available"); + return; + } + else + { + Utility.SpdlogInfo("Existing global variables and their original values:"); + Console.WriteLine(Utility.FlexivDataDictToString(globalVars)); + } + Utility.SpdlogInfo("Program finished"); + } + catch (Exception ex) + { + Utility.SpdlogError(ex.Message); + } + } + } +} diff --git a/csharp/Examples/IExample.cs b/csharp/Examples/IExample.cs new file mode 100644 index 0000000..d256278 --- /dev/null +++ b/csharp/Examples/IExample.cs @@ -0,0 +1,10 @@ +namespace FlexivRdkCSharp.Examples +{ + public interface IExample + { + string Name { get; } + string Description { get; } + string Usage { get; } + void Run(string[] args); + } +} diff --git a/csharp/Examples/Intermed1NRTJntPosCtrl.cs b/csharp/Examples/Intermed1NRTJntPosCtrl.cs new file mode 100644 index 0000000..3dd791a --- /dev/null +++ b/csharp/Examples/Intermed1NRTJntPosCtrl.cs @@ -0,0 +1,133 @@ +using System; +using System.Linq; +using System.Threading; +using FlexivRdkCSharp.FlexivRdk; + +namespace FlexivRdkCSharp.Examples +{ + class Intermed1NRTJntPosCtrl : IExample + { + public string Name => "intermed1_nrt_jnt_pos_ctrl"; + + public string Description => "This tutorial runs non-real-time joint position control to hold or sine-sweep all robot joints."; + + public string Usage => +@" +Usage: + intermed1_nrt_jnt_pos_ctrl [--hold] +Description: + Run non-real-time joint position control to hold or sine-sweep all robot joints. +Required arguments: + Serial number of the robot to connect to. + Remove any space. For example: Rizon4s-123456 + Command frequency, 1 to 100 [Hz] +Optional arguments: + --hold Robot holds current joint positions, otherwise do a sine-sweep +"; + public void Run(string[] args) + { + if (args.Length < 2) + { + Console.WriteLine(Usage); + return; + } + if (!int.TryParse(args[1], out int frequency) || frequency < 1 || frequency > 100) + { + Utility.SpdlogError("Invalid input"); + return; + } + bool hold = Array.Exists(args, arg => arg == "--hold"); + Utility.SpdlogInfo(">>> Tutorial description <<<\nThis tutorial runs non-real-time joint position control to " + + "hold or sine-sweep all robot joints.\n"); + string robotSN = args[0]; + try + { + // Instantiate robot interface + var robot = new Robot(robotSN); + // Clear fault on the connected robot if any + if (robot.IsFault()) + { + Utility.SpdlogWarn("Fault occurred on the connected robot, trying to clear ..."); + // Try to clear the fault + if (!robot.ClearFault()) + { + Utility.SpdlogError("Fault cannot be cleared, exiting ..."); + return; + } + Utility.SpdlogInfo("Fault on the connected robot is cleared"); + } + Utility.SpdlogInfo("Enabling robot ..."); + // Enable the robot, make sure the E-stop is released before enabling + robot.Enable(); + // Wait for the robot to become operational + while (!robot.IsOperational()) + { + Thread.Sleep(1000); + } + Utility.SpdlogInfo("Robot is now operational"); + // Move robot to home pose + Utility.SpdlogInfo("Moving to home pose"); + robot.SwitchMode(RobotMode.NRT_PLAN_EXECUTION); + robot.ExecutePlan("PLAN-Home"); + // Wait for the plan to finish + while (robot.IsBusy()) + { + Thread.Sleep(1000); + } + // Switch to non-real-time joint position control mode + robot.SwitchMode(RobotMode.NRT_JOINT_POSITION); + double period = 1.0 / frequency; + double loopTime = 0.0; + Utility.SpdlogInfo($"Sending command to robot at {frequency} Hz, or {period} seconds interval"); + // Use current robot joint positions as initial positions + double[] initPos = (double[])robot.GetStates().Q.Clone(); + Utility.SpdlogInfo("Initial positions set to: " + string.Join(", ", initPos.Select(v => v.ToString("F6")))); + // Robot joint degrees of freedom + int dof = robot.GetInfo().DoF; + // Initialize target vectors + double[] targetPos = (double[])initPos.Clone(); + double[] targetVel = new double[dof]; + double[] targetAcc = new double[dof]; + // Joint motion constraints + double[] maxVel = new double[dof]; + double[] maxAcc = new double[dof]; + for (int i = 0; i < dof; ++i) + { + targetVel[i] = 0.0; + targetAcc[i] = 0.0; + maxVel[i] = 2.0; + maxAcc[i] = 3.0; + } + // Joint sine-sweep amplitude [rad] + const double SWING_AMP = 0.1; + // TCP sine-sweep frequency [Hz] + const double SWING_FREQ = 0.3; + int time = (int)(period * 1000); + // Send command periodically at user-specified frequency + while (true) + { + // Use sleep to control loop period + Thread.Sleep(time); + if (robot.IsFault()) + { + Utility.SpdlogError("Fault occurred on the connected robot, exiting ..."); + return; + } + if (!hold) + { + for (int i = 0; i < dof; ++i) + { + targetPos[i] = initPos[i] + SWING_AMP * Math.Sin(2 * Math.PI * SWING_FREQ * loopTime); + } + } + robot.SendJointPosition(targetPos, targetVel, targetAcc, maxVel, maxAcc); + loopTime += period; + } + } + catch (Exception ex) + { + Utility.SpdlogError(ex.Message); + } + } + } +} \ No newline at end of file diff --git a/csharp/Examples/Intermed2NRTJntImpCtrl.cs b/csharp/Examples/Intermed2NRTJntImpCtrl.cs new file mode 100644 index 0000000..f448edf --- /dev/null +++ b/csharp/Examples/Intermed2NRTJntImpCtrl.cs @@ -0,0 +1,150 @@ +using System; +using System.Linq; +using System.Threading; +using FlexivRdkCSharp.FlexivRdk; + +namespace FlexivRdkCSharp.Examples +{ + class Intermed2NRTJntImpCtrl : IExample + { + public string Name => "intermed2_nrt_jnt_imp_ctrl"; + + public string Description => "This tutorial runs non-real-time joint impedance control to hold or sine-sweep all robot joints."; + + public string Usage => +@" +Usage: + intermed2_nrt_jnt_imp_ctrl [--hold] +Description: + Run non-real-time joint impedance control to hold or sine-sweep all robot joints. +Required arguments: + Serial number of the robot to connect to. + Remove any space. For example: Rizon4s-123456 + Command frequency, 1 to 100 [Hz] +Optional arguments: + --hold Robot holds current joint positions, otherwise do a sine-sweep +"; + public void Run(string[] args) + { + if (args.Length < 2) + { + Console.WriteLine(Usage); + return; + } + if (!int.TryParse(args[1], out int frequency) || frequency < 1 || frequency > 100) + { + Utility.SpdlogError("Invalid input"); + return; + } + bool hold = Array.Exists(args, arg => arg == "--hold"); + Utility.SpdlogInfo(">>> Tutorial description <<<\nThis tutorial runs non-real-time joint impedance control to " + + "hold or sine-sweep all robot joints.\n"); + string robotSN = args[0]; + try + { + // Instantiate robot interface + var robot = new Robot(robotSN); + // Clear fault on the connected robot if any + if (robot.IsFault()) + { + Utility.SpdlogWarn("Fault occurred on the connected robot, trying to clear ..."); + // Try to clear the fault + if (!robot.ClearFault()) + { + Utility.SpdlogError("Fault cannot be cleared, exiting ..."); + return; + } + Utility.SpdlogInfo("Fault on the connected robot is cleared"); + } + Utility.SpdlogInfo("Enabling robot ..."); + // Enable the robot, make sure the E-stop is released before enabling + robot.Enable(); + // Wait for the robot to become operational + while (!robot.IsOperational()) + { + Thread.Sleep(1000); + } + Utility.SpdlogInfo("Robot is now operational"); + // Move robot to home pose + Utility.SpdlogInfo("Moving to home pose"); + robot.SwitchMode(RobotMode.NRT_PLAN_EXECUTION); + robot.ExecutePlan("PLAN-Home"); + // Wait for the plan to finish + while (robot.IsBusy()) + { + Thread.Sleep(1000); + } + // Switch to non-real-time joint position control mode + robot.SwitchMode(RobotMode.NRT_JOINT_IMPEDANCE); + double period = 1.0 / frequency; + int loopCounter = 0; + Utility.SpdlogInfo($"Sending command to robot at {frequency} Hz, or {period} seconds interval"); + // Use current robot joint positions as initial positions + double[] initPos = (double[])robot.GetStates().Q.Clone(); + Utility.SpdlogInfo("Initial positions set to: " + string.Join(", ", initPos.Select(v => v.ToString("F6")))); + // Robot joint degrees of freedom + int dof = robot.GetInfo().DoF; + // Initialize target vectors + double[] targetPos = (double[])initPos.Clone(); + double[] targetVel = new double[dof]; + double[] targetAcc = new double[dof]; + // Joint motion constraints + double[] maxVel = new double[dof]; + double[] maxAcc = new double[dof]; + for (int i = 0; i < dof; ++i) + { + targetVel[i] = 0.0; + targetAcc[i] = 0.0; + maxVel[i] = 2.0; + maxAcc[i] = 3.0; + } + // Joint sine-sweep amplitude [rad] + const double SWING_AMP = 0.1; + // TCP sine-sweep frequency [Hz] + const double SWING_FREQ = 0.3; + int time = (int)(period * 1000); + // Send command periodically at user-specified frequency + while (true) + { + // Use sleep to control loop period + Thread.Sleep(time); + if (robot.IsFault()) + { + Utility.SpdlogError("Fault occurred on the connected robot, exiting ..."); + return; + } + // Sine-sweep all joints + if (!hold) + { + for (int i = 0; i < dof; ++i) + { + targetPos[i] = initPos[i] + SWING_AMP * Math.Sin(2 * Math.PI * SWING_FREQ * loopCounter * period); + } + } + // Otherwise all joints will hold at initial positions + // Reduce stiffness to half of nominal values after 5 seconds + if (loopCounter == (int)(5 / period)) + { + double[] newKq = robot.GetInfo().KqNom.Select(k => k * 0.5).ToArray(); + robot.SetJointImpedance(newKq); + Utility.SpdlogInfo("Joint stiffness set to: " + string.Join(", ", newKq.Select(v => v.ToString("F6")))); + } + // Reset impedance properties to nominal values after another 5 seconds + if (loopCounter == (int)(10 / period)) + { + robot.SetJointImpedance(robot.GetInfo().KqNom); + Utility.SpdlogInfo("Joint stiffness reset to nominal."); + } + // Send commands + robot.SendJointPosition(targetPos, targetVel, targetAcc, maxVel, maxAcc); + // Increment loop counter + loopCounter += 1; + } + } + catch (Exception ex) + { + Utility.SpdlogError(ex.Message); + } + } + } +} diff --git a/csharp/Examples/Intermed3NRTCartPureMotionCtrl.cs b/csharp/Examples/Intermed3NRTCartPureMotionCtrl.cs new file mode 100644 index 0000000..9f5fc7c --- /dev/null +++ b/csharp/Examples/Intermed3NRTCartPureMotionCtrl.cs @@ -0,0 +1,226 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Text; +using System.Threading; +using FlexivRdkCSharp.FlexivRdk; + +namespace FlexivRdkCSharp.Examples +{ + class Intermed3NRTCartPureMotionCtrl : IExample + { + public string Name => "intermed3_nrt_cart_pure_motion_ctrl"; + public string Description => "This tutorial runs non-real-time Cartesian-space pure motion control to hold or sine-sweep the robot TCP. "; + public string Usage => + @" +Usage: + intermed3_cart_nrt_pure_motion_ctrl [--hold] [--collision] +Description: + Run Cartesian pure motion control. Use --hold to hold current TCP position or sine sweep otherwise. +Required arguments: + Serial number of the robot to connect to. + Remove any space. For example: Rizon4s-123456 + Command frequency, 1 to 100 [Hz] +Optional arguments: + --hold Robot holds current TCP pose instead of moving + --collision Enable collision detection +"; + // Constants + // TCP sine-sweep amplitude [m] + const double SWING_AMP = 0.1; + // TCP sine-sweep frequency [Hz] + const double SWING_FREQ = 0.3; + // External TCP force threshold for collision detection, value is only for demo purpose [N] + const double EXT_FORCE_THRESHOLD = 10.0; + // External joint torque threshold for collision detection, value is only for demo purpose [Nm] + const double EXT_TORQUE_THRESHOLD = 5.0; + + public void Run(string[] args) + { + if (args.Length < 2) + { + Console.WriteLine(Usage); + return; + } + if (!int.TryParse(args[1], out int frequency) || frequency < 1 || frequency > 100) + { + Utility.SpdlogError("Invalid input"); + return; + } + bool hold = Array.Exists(args, arg => arg == "--hold"); + bool collision = Array.Exists(args, arg => arg == "--collision"); + // Print description + Utility.SpdlogInfo(">>> Tutorial description <<<\nThis tutorial runs non-real-time Cartesian-space pure " + + "motion control to hold or sine-sweep the robot TCP. A simple collision detection is also " + + "included.\n"); + // Print based on arguments + if (hold) Utility.SpdlogInfo("Robot holding current TCP pose"); + else Utility.SpdlogInfo("Robot running TCP sine-sweep"); + + if (collision) Utility.SpdlogInfo("Collision detection enabled"); + else Utility.SpdlogInfo("Collision detection disabled"); + string robotSN = args[0]; + try + { + // Instantiate robot interface + var robot = new Robot(robotSN); + // Clear fault on the connected robot if any + if (robot.IsFault()) + { + Utility.SpdlogWarn("Fault occurred on the connected robot, trying to clear ..."); + // Try to clear the fault + if (!robot.ClearFault()) + { + Utility.SpdlogError("Fault cannot be cleared, exiting ..."); + return; + } + Utility.SpdlogInfo("Fault on the connected robot is cleared"); + } + Utility.SpdlogInfo("Enabling robot ..."); + // Enable the robot, make sure the E-stop is released before enabling + robot.Enable(); + // Wait for the robot to become operational + while (!robot.IsOperational()) + { + Thread.Sleep(1000); + } + Utility.SpdlogInfo("Robot is now operational"); + // Move robot to home pose + Utility.SpdlogInfo("Moving to home pose"); + robot.SwitchMode(RobotMode.NRT_PLAN_EXECUTION); + robot.ExecutePlan("PLAN-Home"); + // Wait for the plan to finish + while (robot.IsBusy()) + { + Thread.Sleep(1000); + } + // Zero Force-torque Sensor + robot.SwitchMode(RobotMode.NRT_PRIMITIVE_EXECUTION); + // IMPORTANT: must zero force/torque sensor offset for accurate force/torque measurement + robot.ExecutePrimitive("ZeroFTSensor", new Dictionary { }); + // WARNING: during the process, the robot must not contact anything, otherwise the result + // will be inaccurate and affect following operations + Utility.SpdlogWarn("Zeroing force/torque sensors, make sure nothing is in contact with the robot"); + // Wait for primitive completion + while (robot.IsBusy()) + { + Thread.Sleep(1000); + } + Utility.SpdlogInfo("Sensor zeroing complete"); + // Switch to non-real-time mode for discrete motion control + robot.SwitchMode(RobotMode.NRT_CARTESIAN_MOTION_FORCE); + // Set initial pose to current TCP pose + var initPose = (double[])robot.GetStates().TcpPose.Clone(); + // Save initial joint positions + var initQ = (double[])robot.GetStates().Q.Clone(); + // Periodic Task, set loop period + double period = 1.0 / frequency; + int loopCounter = 0; + Utility.SpdlogInfo($"Sending command to robot at {frequency} Hz, or {period} seconds interval"); + int time = (int)(period * 1000); + // Send command periodically at user-specified frequency + while (true) + { + // Use sleep to control loop period + Thread.Sleep(time); + // Monitor fault on the connected robot + if (robot.IsFault()) + { + Utility.SpdlogError("Fault occurred on the connected robot, exiting ..."); + return; + } + // Initialize target pose to initial pose + var targetPose = (double[])initPose.Clone(); + // Sine-sweep TCP along Y axis + if (!hold) + { + targetPose[1] = initPose[1] + SWING_AMP * + Math.Sin(2 * Math.PI * SWING_FREQ * loopCounter * period); + } + // Otherwise robot TCP will hold at initial pose + // Send command. Calling this method with only target pose input results in pure motion control + robot.SendCartesianMotionForce(targetPose); + // Do the following operations in sequence for every 20 seconds + double timeElapsed = loopCounter * period; + // Online change reference joint positions at 3 seconds + if ((int)timeElapsed % 20 == 3) + { + var preferredJntPos = new double[] { 0.938, -1.108, -1.254, 1.464, 1.073, 0.278, -0.658 }; + robot.SetNullSpacePosture(preferredJntPos); + Utility.SpdlogInfo("Reference joint positions set to: " + string.Join(", ", preferredJntPos.Select(v => v.ToString("F6")))); + } + // Online change stiffness to half of nominal at 6 seconds + else if ((int)timeElapsed % 20 == 6) + { + var newK = robot.GetInfo().KxNom.Select(k => k * 0.5).ToArray(); + robot.SetCartesianImpedance(newK); + Utility.SpdlogInfo($"Cartesian stiffness set to: " + string.Join(", ", newK.Select(v => v.ToString("F6")))); + } + // Online change to another reference joint positions at 9 seconds + else if ((int)timeElapsed % 20 == 9) + { + var preferredJntPos = new double[] { -0.938, -1.108, 1.254, 1.464, -1.073, 0.278, 0.658 }; + robot.SetNullSpacePosture(preferredJntPos); + Utility.SpdlogInfo("Reference joint positions set to: " + string.Join(", ", preferredJntPos.Select(v => v.ToString("F6")))); + } + // Online reset impedance properties to nominal at 12 seconds + else if ((int)timeElapsed % 20 == 12) + { + robot.SetCartesianImpedance(robot.GetInfo().KxNom); + Utility.SpdlogInfo("Cartesian impedance properties are reset"); + } + // Online reset reference joint positions to nominal at 14 seconds + else if ((int)timeElapsed % 20 == 14) + { + robot.SetNullSpacePosture(initQ); + Utility.SpdlogInfo("Reference joint positions are reset"); + } + // Online enable max contact wrench regulation at 16 seconds + else if ((int)timeElapsed % 20 == 16) + { + var maxWrench = new double[] { 10, 10, 10, 2, 2, 2 }; + robot.SetMaxContactWrench(maxWrench); + Utility.SpdlogInfo("Max contact wrench set to " + string.Join(", ", maxWrench.Select(v => v.ToString("F6")))); + } + // Disable max contact wrench regulation at 19 seconds + else if ((int)timeElapsed % 20 == 19) + { + robot.SetMaxContactWrench(new double[] { + double.PositiveInfinity, double.PositiveInfinity, double.PositiveInfinity, + double.PositiveInfinity, double.PositiveInfinity, double.PositiveInfinity }); + Utility.SpdlogInfo("Max contact wrench regulation disabled"); + } + // Simple collision detection: stop robot if collision is detected at end-effector + if (collision) + { + bool collisionDetected = false; + var f = robot.GetStates().ExtWrenchInWorld; + var forceNorm = Math.Sqrt(f[0] * f[0] + f[1] * f[1] + f[2] * f[2]); + if (forceNorm > EXT_FORCE_THRESHOLD) + collisionDetected = true; + foreach (var tau in robot.GetStates().TauExt) + { + if (Math.Abs(tau) > EXT_TORQUE_THRESHOLD) + { + collisionDetected = true; + break; + } + } + if (collisionDetected) + { + robot.Stop(); + Utility.SpdlogWarn("Collision detected, stopping robot and exit program ..."); + return; + } + } + // Increment loop counter + loopCounter += 1; + } + } + catch (Exception ex) + { + Utility.SpdlogError(ex.Message); + } + } + } +} diff --git a/csharp/Examples/Intermed4NRTCartMotionForceCtrl.cs b/csharp/Examples/Intermed4NRTCartMotionForceCtrl.cs new file mode 100644 index 0000000..ac60ae3 --- /dev/null +++ b/csharp/Examples/Intermed4NRTCartMotionForceCtrl.cs @@ -0,0 +1,236 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Threading; +using FlexivRdkCSharp.FlexivRdk; + +namespace FlexivRdkCSharp.Examples +{ + public class Intermed4NRTCartMotionForceCtrl : IExample + { + public string Name => "intermed4_nrt_cart_motion_force_ctrl"; + public string Description => "This tutorial runs non-real-time Cartesian-space unified motion-force control."; + public string Usage => + @" +Usage: + intermed4_nrt_cart_motion_force_ctrl [--TCP] [--polish] +Description: + Run Cartesian pure motion control. Use --hold to hold current TCP position or sine sweep otherwise. +Required arguments: + Serial number of the robot to connect to. + Remove any space. For example: Rizon4s-123456 + Command frequency, 1 to 100 [Hz] +Optional arguments: + --TCP Use TCP frame as reference frame for force control, + otherwise use world frame + --polish Run a simple polish motion along XY plane in world frame, + otherwise hold robot motion in non-force-control axes +"; + // Constants + // TCP sine-sweep amplitude [m] + const double SWING_AMP = 0.1; + // TCP sine-sweep frequency [Hz] + const double SWING_FREQ = 0.3; + // Pressing force to apply during the unified motion-force control [N] + const double PRESSING_FORCE = 5.0; + // Cartesian linear velocity used to search for contact [m/s] + const double SEARCH_VELOCITY = 0.02; + // Maximum distance to travel when searching for contact [m] + const double SEARCH_DISTANCE = 1.0; + // Maximum contact wrench during contact search for soft contact + static readonly double[] MAX_WRENCH_FOR_CONTACT_SEARCH = { 10.0, 10.0, 10.0, 3.0, 3.0, 3.0 }; + + public void Run(string[] args) + { + if (args.Length < 2) + { + Console.WriteLine(Usage); + return; + } + if (!int.TryParse(args[1], out int frequency) || frequency < 1 || frequency > 100) + { + Utility.SpdlogError("Invalid input"); + return; + } + bool tcp = Array.Exists(args, arg => arg == "--TCP"); + bool polish = Array.Exists(args, arg => arg == "--polish"); + // Print description + Utility.SpdlogInfo(">>> Tutorial description <<<\nThis tutorial runs non-real-time Cartesian-space unified " + + "motion-force control. The Z axis of the chosen reference frame will be activated for " + + "explicit force control, while the rest axes in the same reference frame will stay motion " + + "controlled.\n"); + // The reference frame to use, see Robot::SendCartesianMotionForce() for more details + var forceCtrlFrame = CoordType.WORLD; + if (tcp) + { + Utility.SpdlogInfo("Reference frame used for force control: robot TCP frame"); + forceCtrlFrame = CoordType.TCP; + } + else + { + Utility.SpdlogInfo("Reference frame used for force control: robot world frame"); + } + // Whether to enable polish motion + if (polish) Utility.SpdlogInfo("Robot will run a polish motion along XY plane in robot world frame"); + else Utility.SpdlogInfo("Robot will hold its motion in all non-force-controlled axes"); + string robotSN = args[0]; + try + { + // Instantiate robot interface + var robot = new Robot(robotSN); + // Clear fault on the connected robot if any + if (robot.IsFault()) + { + Utility.SpdlogWarn("Fault occurred on the connected robot, trying to clear ..."); + // Try to clear the fault + if (!robot.ClearFault()) + { + Utility.SpdlogError("Fault cannot be cleared, exiting ..."); + return; + } + Utility.SpdlogInfo("Fault on the connected robot is cleared"); + } + Utility.SpdlogInfo("Enabling robot ..."); + // Enable the robot, make sure the E-stop is released before enabling + robot.Enable(); + // Wait for the robot to become operational + while (!robot.IsOperational()) + { + Thread.Sleep(1000); + } + Utility.SpdlogInfo("Robot is now operational"); + // Move robot to home pose + Utility.SpdlogInfo("Moving to home pose"); + robot.SwitchMode(RobotMode.NRT_PLAN_EXECUTION); + robot.ExecutePlan("PLAN-Home"); + // Wait for the plan to finish + while (robot.IsBusy()) + { + Thread.Sleep(1000); + } + + // Zero Force-torque Sensor + robot.SwitchMode(RobotMode.NRT_PRIMITIVE_EXECUTION); + // IMPORTANT: must zero force/torque sensor offset for accurate force/torque measurement + robot.ExecutePrimitive("ZeroFTSensor", new Dictionary { }); + // WARNING: during the process, the robot must not contact anything, otherwise the result + // will be inaccurate and affect following operations + Utility.SpdlogWarn("Zeroing force/torque sensors, make sure nothing is in contact with the robot"); + // Wait for primitive completion + while (robot.IsBusy()) + { + Thread.Sleep(1000); + } + Utility.SpdlogInfo("Sensor zeroing complete"); + + // Search for Contact + // NOTE: there are several ways to do contact search, such as using primitives, or real-time + // and non-real-time direct motion controls, etc. Here we use non-real-time direct Cartesian + // control for example. + Utility.SpdlogInfo("Searching for contact ..."); + // Set initial pose to current TCP pose + var initPose = (double[])robot.GetStates().TcpPose.Clone(); + Utility.SpdlogInfo("Initial TCP pose set to: " + string.Join(", ", initPose.Select(v => v.ToString("F6"))) + + " (position 3x1, rotation (quaternion) 4x1"); + // Use non-real-time mode to make the robot go to a set point with its own motion generator + robot.SwitchMode(RobotMode.NRT_CARTESIAN_MOTION_FORCE); + // Search for contact with max contact wrench set to a small value for making soft contact + robot.SetMaxContactWrench(MAX_WRENCH_FOR_CONTACT_SEARCH); + // Set target point along -Z direction and expect contact to happen during the travel + var targetPose = (double[])initPose.Clone(); + targetPose[2] -= SEARCH_DISTANCE; + // Send target point to robot to start searching for contact and limit the velocity. Keep + // target wrench 0 at this stage since we are not doing force control yet + robot.SendCartesianMotionForce(targetPose, new double[] { 0, 0, 0, 0, 0, 0 }, SEARCH_VELOCITY); + // Use a while loop to poll robot states and check if a contact is made + bool IsContacted = false; + while (!IsContacted) + { + // Compute norm of sensed external force applied on robot TCP + var f = robot.GetStates().ExtWrenchInWorld; + var forceNorm = Math.Sqrt(f[0] * f[0] + f[1] * f[1] + f[2] * f[2]); + // Contact is considered to be made if sensed TCP force exceeds the threshold + if (forceNorm > PRESSING_FORCE) + { + IsContacted = true; + Utility.SpdlogInfo("Contact detected at robot TCP"); + } + // Check at 1ms interval + Thread.Sleep(1); + } + // Configure Force Control + // The force control configurations can only be updated when the robot is in IDLE mode + robot.Stop(); + // Set force control reference frame based on program argument. See function doc for more details + robot.SetForceControlFrame(forceCtrlFrame); + // Set which Cartesian axis(s) to activate for force control. See function doc for more details. Here we only active Z axis + robot.SetForceControlAxis(new bool[] { false, false, true, false, false, false }); + // Uncomment the following line to enable passive force control, otherwise active force + // control is used by default. See function doc for more details robot.setPassiveForceControl(True) + // NOTE: motion control always uses robot world frame, while force control can use either world or TCP frame as reference frame + + // Start Unified Motion Force Control + // Switch to non-real-time mode for discrete motion force control + robot.SwitchMode(RobotMode.NRT_CARTESIAN_MOTION_FORCE); + + // Disable max contact wrench regulation. Need to do this AFTER the force control in Z axis + // is activated (i.e. motion control disabled in Z axis) and the motion force control mode + // is entered, this way the contact force along Z axis is explicitly regulated and will not + // spike after the max contact wrench regulation for motion control is disabled + robot.SetMaxContactWrench(new double[] { + double.PositiveInfinity, double.PositiveInfinity, double.PositiveInfinity, + double.PositiveInfinity, double.PositiveInfinity, double.PositiveInfinity }); + // Update initial pose to current TCP pose + initPose = (double[])robot.GetStates().TcpPose.Clone(); + Utility.SpdlogInfo("Initial TCP pose set to: " + string.Join(", ", initPose.Select(v => v.ToString("F6"))) + + " (position 3x1, rotation (quaternion) 4x1"); + + // Periodic Task + double period = 1.0 / frequency; + Utility.SpdlogInfo($"Sending command to robot at {frequency} Hz, or {period} seconds interval"); + int loopCounter = 0; + int time = (int)(period * 1000); + // Send command periodically at user-specified frequency + while (true) + { + // Use sleep to control loop period + Thread.Sleep(time); + // Monitor fault on the connected robot + if (robot.IsFault()) + { + Utility.SpdlogError("Fault occurred on the connected robot, exiting ..."); + return; + } + // Initialize target pose to initial pose + targetPose = (double[])initPose.Clone(); + // Set Fz according to reference frame to achieve a "pressing down" behavior + double Fz = 0.0; + if (forceCtrlFrame == CoordType.WORLD) Fz = PRESSING_FORCE; + else if (forceCtrlFrame == CoordType.TCP) Fz = -PRESSING_FORCE; + double[] targetWrench = new double[] { 0.0, 0.0, Fz, 0.0, 0.0, 0.0 }; + // Apply constant force along Z axis of chosen reference frame, and do a simple polish + // motion along XY plane in robot world frame + if (polish) + { + // Create motion command to sine-sweep along Y direction + targetPose[1] = initPose[1] + SWING_AMP * Math.Sin( + 2 * Math.PI * SWING_FREQ * loopCounter * period); + // Command target pose and target wrench + robot.SendCartesianMotionForce(targetPose, targetWrench); + } + else // Apply constant force along Z axis of chosen reference frame, and hold motions in all other axes + { + // Command initial pose and target wrench + robot.SendCartesianMotionForce(initPose, targetWrench); + } + // Increment loop counter + loopCounter += 1; + } + } + catch (Exception ex) + { + Utility.SpdlogError(ex.Message); + } + } + } +} diff --git a/csharp/FlexivRdk/Data.cs b/csharp/FlexivRdk/Data.cs new file mode 100644 index 0000000..b7d5873 --- /dev/null +++ b/csharp/FlexivRdk/Data.cs @@ -0,0 +1,540 @@ +using System; +using System.Collections.Generic; +using System.Linq; +using System.Runtime.InteropServices; +using System.Text; +using System.Text.Json; +using System.Text.Json.Serialization; + +namespace FlexivRdkCSharp.FlexivRdk +{ + public static class FlexivConstants + { + public const int kCartDoF = 6; + public const int kSerialJointDoF = 7; + public const int kPoseSize = 7; + public const int kIOPorts = 18; + public const int kMaxExtAxes = 6; + } + + public enum FlexivDataType + { + Int, Double, String, JPos, Coord, VectorInt, VectorDouble, + VectorString, VectorJPos, VectorCoord + } + + public class FlexivData + { + public FlexivDataType Type { get; set; } + public object Value { get; set; } + public FlexivData() { } + public FlexivData(FlexivDataType type, object value) + { + Type = type; + Value = value; + } + public static FlexivData Create(T value) where T : notnull + { + var type = MapType(typeof(T)); + return new FlexivData(type, value); + } + public T As() + { + if (Value is T typedValue && MapType(typeof(T)) == Type) + return typedValue; + throw new InvalidCastException($"Cannot convert {Type} to {typeof(T).Name}"); + } + private static readonly Dictionary TypeMap = new() + { + { typeof(int), FlexivDataType.Int }, + { typeof(double), FlexivDataType.Double }, + { typeof(string), FlexivDataType.String }, + { typeof(JPos), FlexivDataType.JPos }, + { typeof(Coord), FlexivDataType.Coord }, + { typeof(List), FlexivDataType.VectorInt }, + { typeof(List), FlexivDataType.VectorDouble }, + { typeof(List), FlexivDataType.VectorString }, + { typeof(List), FlexivDataType.VectorJPos }, + { typeof(List), FlexivDataType.VectorCoord } + }; + private static FlexivDataType MapType(Type t) + { + if (TypeMap.TryGetValue(t, out var result)) + return result; + throw new NotSupportedException($"Unsupported type: {t.FullName}"); + } + + public static implicit operator FlexivData(int value) => Create(value); + public static implicit operator FlexivData(double value) => Create(value); + public static implicit operator FlexivData(string value) => Create(value); + public static implicit operator FlexivData(JPos value) => Create(value); + public static implicit operator FlexivData(Coord value) => Create(value); + public static implicit operator FlexivData(List value) => Create(value); + public static implicit operator FlexivData(List value) => Create(value); + public static implicit operator FlexivData(List value) => Create(value); + public static implicit operator FlexivData(List value) => Create(value); + public static implicit operator FlexivData(List value) => Create(value); + + public static explicit operator int(FlexivData d) => d.As(); + public static explicit operator double(FlexivData d) => d.As(); + public static explicit operator string(FlexivData d) => d.As(); + public static explicit operator JPos(FlexivData d) => d.As(); + public static explicit operator Coord(FlexivData d) => d.As(); + public static explicit operator List(FlexivData d) => d.As>(); + public static explicit operator List(FlexivData d) => d.As>(); + public static explicit operator List(FlexivData d) => d.As>(); + public static explicit operator List(FlexivData d) => d.As>(); + public static explicit operator List(FlexivData d) => d.As>(); + + public override string ToString() + { + string valueStr; + switch (Type) + { + case FlexivDataType.VectorInt: + valueStr = string.Join(", ", As>()); + break; + case FlexivDataType.VectorDouble: + valueStr = string.Join(", ", As>().Select(v => v.ToString("F3"))); + break; + case FlexivDataType.VectorString: + valueStr = string.Join(", ", As>()); + break; + case FlexivDataType.VectorJPos: + valueStr = string.Join("\n ", As>()); + break; + case FlexivDataType.VectorCoord: + valueStr = string.Join("\n ", As>()); + break; + default: + valueStr = Value?.ToString() ?? "null"; + break; + } + return $"({Type}) {valueStr}"; + } + + } + + public static class FlexivDataUtils + { + public static T Get(Dictionary dict, string key) + { + if (!dict.TryGetValue(key, out var data)) + throw new KeyNotFoundException($"Parameter '{key}' is missing."); + try + { + return data.As(); + } + catch (InvalidCastException e) + { + throw new InvalidCastException($"Parameter '{key}' expected type {typeof(T).Name}, but got {data.Type}.", e); + } + } + + public static bool TryGet(Dictionary dict, string key, out T result) + { + if (dict.TryGetValue(key, out var data)) + { + try + { + result = data.As(); + return true; + } + catch + { } + } + result = default!; + return false; + } + } + + public class FlexivDataJsonConverter : JsonConverter + { + public override FlexivData Read(ref Utf8JsonReader reader, Type typeToConvert, JsonSerializerOptions options) + { + using var doc = JsonDocument.ParseValue(ref reader); + var root = doc.RootElement; + var typeStr = root.GetProperty("type").GetString(); + if (!Enum.TryParse(typeStr, out var type)) + throw new JsonException($"Unknown FlexivDataType: {typeStr}"); + var valueElem = root.GetProperty("value"); + object value = type switch + { + FlexivDataType.Int => valueElem.GetInt32(), + FlexivDataType.Double => valueElem.GetDouble(), + FlexivDataType.String => valueElem.GetString()!, + FlexivDataType.JPos => JsonSerializer.Deserialize(valueElem.GetRawText(), options)!, + FlexivDataType.Coord => JsonSerializer.Deserialize(valueElem.GetRawText(), options)!, + FlexivDataType.VectorInt => JsonSerializer.Deserialize>(valueElem.GetRawText(), options)!, + FlexivDataType.VectorDouble => JsonSerializer.Deserialize>(valueElem.GetRawText(), options)!, + FlexivDataType.VectorString => JsonSerializer.Deserialize>(valueElem.GetRawText(), options)!, + FlexivDataType.VectorJPos => JsonSerializer.Deserialize>(valueElem.GetRawText(), options)!, + FlexivDataType.VectorCoord => JsonSerializer.Deserialize>(valueElem.GetRawText(), options)!, + _ => throw new JsonException($"Unsupported type: {type}") + }; + return new FlexivData(type, value); + } + + public override void Write(Utf8JsonWriter writer, FlexivData value, JsonSerializerOptions options) + { + writer.WriteStartObject(); + writer.WriteString("type", value.Type.ToString()); + writer.WritePropertyName("value"); + JsonSerializer.Serialize(writer, value.Value, options); + writer.WriteEndObject(); + } + } + + public class Coord + { + [JsonPropertyName("position")] + public double[] Position { get; set; } = new double[FlexivConstants.kCartDoF / 2]; + [JsonPropertyName("orientation")] + public double[] Orientation { get; set; } = new double[FlexivConstants.kCartDoF / 2]; + [JsonPropertyName("ref_frame")] + public string[] RefFrame { get; set; } = new string[2] { "WORLD", "WORLD_ORIGIN" }; + [JsonPropertyName("ref_q")] + public double[] RefQ { get; set; } = new double[FlexivConstants.kSerialJointDoF]; + [JsonPropertyName("ref_q_e")] + public double[] RefQE { get; set; } = new double[FlexivConstants.kMaxExtAxes]; + public Coord() { } + public Coord(double[] position, double[] orientation, string[] refFrame, + double[] refQ = null, double[] refQE = null) + { + if (position != null && position.Length != FlexivConstants.kCartDoF / 2) + throw new ArgumentException($"Position must have length {FlexivConstants.kCartDoF / 2}", nameof(position)); + if (orientation != null && orientation.Length != FlexivConstants.kCartDoF / 2) + throw new ArgumentException($"Orientation must have length {FlexivConstants.kCartDoF / 2}", nameof(orientation)); + if (refFrame != null && refFrame.Length != 2) + throw new ArgumentException("RefFrame must have length 2", nameof(refFrame)); + if (refQ != null && refQ.Length != FlexivConstants.kSerialJointDoF) + throw new ArgumentException($"RefQ must have length {FlexivConstants.kSerialJointDoF}", nameof(refQ)); + if (refQE != null && refQE.Length != FlexivConstants.kMaxExtAxes) + throw new ArgumentException($"RefQE must have length {FlexivConstants.kMaxExtAxes}", nameof(refQE)); + Position = position ?? new double[FlexivConstants.kCartDoF / 2]; + Orientation = orientation ?? new double[FlexivConstants.kCartDoF / 2]; + RefFrame = refFrame ?? new string[2] { "WORLD", "WORLD_ORIGIN" }; + RefQ = refQ ?? new double[FlexivConstants.kSerialJointDoF]; + RefQE = refQE ?? new double[FlexivConstants.kMaxExtAxes]; + } + public Coord(double x, double y, double z, double rx, double ry, double rz, + string coordType = "WORLD", string coordName = "WORLD_ORIGIN", + double[] refQ = null, double[] refQE = null) + { + if (refQ != null && refQ.Length != FlexivConstants.kSerialJointDoF) + throw new ArgumentException($"RefQ must have length {FlexivConstants.kSerialJointDoF}", nameof(refQ)); + if (refQE != null && refQE.Length != FlexivConstants.kMaxExtAxes) + throw new ArgumentException($"RefQE must have length {FlexivConstants.kMaxExtAxes}", nameof(refQE)); + Position = new double[] { x, y, z }; + Orientation = new double[] { rx, ry, rz }; + RefFrame = new string[] { coordType, coordName }; + RefQ = refQ ?? new double[FlexivConstants.kSerialJointDoF]; + RefQE = refQE ?? new double[FlexivConstants.kMaxExtAxes]; + } + public Coord(double x, double y, double z, double qw, double qx, double qy, double qz, + string coordType = "WORLD", string coordName = "WORLD_ORIGIN", + double[] refQ = null, double[] refQE = null) + { + if (refQ != null && refQ.Length != FlexivConstants.kSerialJointDoF) + throw new ArgumentException($"RefQ must have length {FlexivConstants.kSerialJointDoF}", nameof(refQ)); + if (refQE != null && refQE.Length != FlexivConstants.kMaxExtAxes) + throw new ArgumentException($"RefQE must have length {FlexivConstants.kMaxExtAxes}", nameof(refQE)); + Position = new double[] { x, y, z }; + double yaw = 0, pitch = 0, roll = 0; + Utility.Quat2EulerZYX(qw, qx, qy, qz, ref yaw, ref pitch, ref roll); + Orientation = new double[] { Utility.Rad2Deg(roll), Utility.Rad2Deg(pitch), Utility.Rad2Deg(yaw) }; + RefFrame = new string[] { coordType, coordName }; + RefQ = refQ ?? new double[FlexivConstants.kSerialJointDoF]; + RefQE = refQE ?? new double[FlexivConstants.kMaxExtAxes]; + } + + public static Coord FromJson(string json) + { + return JsonSerializer.Deserialize(json); + } + public override string ToString() + { + string FormatArray(double[] arr, int decimals = 5) + { + if (arr == null) return "null"; + string formatStr = $"F{decimals}"; + return string.Join(", ", arr.Select(v => v.ToString(formatStr))); + } + string pos = FormatArray(Position); + string ori = FormatArray(Orientation); + string refQ = FormatArray(RefQ); + string refQE = FormatArray(RefQE); + return $"Coord {{ Position: [{pos}], Orientation: [{ori}], RefFrame: \"{RefFrame}\", RefQ: [{refQ}], RefQE: [{refQE}] }}"; + } + + } + + public class JPos + { + [JsonPropertyName("q")] + public double[] Q { get; set; } = new double[FlexivConstants.kSerialJointDoF]; + [JsonPropertyName("q_e")] + public double[] QE { get; set; } = new double[FlexivConstants.kMaxExtAxes]; + public JPos() { } + public JPos(double[] q, double[] q_e = null) + { + if (q != null && q.Length != FlexivConstants.kSerialJointDoF) + throw new ArgumentException($"Q must have {FlexivConstants.kSerialJointDoF} elements."); + if (q_e != null && q_e.Length != FlexivConstants.kMaxExtAxes) + throw new ArgumentException($"Qe must have at most {FlexivConstants.kMaxExtAxes} elements."); + Q = q ?? new double[FlexivConstants.kSerialJointDoF]; + QE = q_e ?? new double[FlexivConstants.kMaxExtAxes]; + } + public JPos(double j1, double j2, double j3, double j4, double j5, double j6, double j7, + double e1 = 0, double e2 = 0, double e3 = 0, double e4 = 0, double e5 = 0, double e6 = 0) + { + Q = new double[] { j1, j2, j3, j4, j5, j6, j7 }; + QE = new double[] { e1, e2, e3, e4, e5, e6 }; + } + public static JPos FromJson(string json) + { + return JsonSerializer.Deserialize(json); + } + public override string ToString() + { + string FormatArray(double[] arr, int decimals = 5) + { + if (arr == null) return "null"; + string formatStr = $"F{decimals}"; + return string.Join(", ", arr.Select(v => v.ToString(formatStr))); + } + var qStr = FormatArray(Q); + var qeStr = FormatArray(QE); + return $"JPos {{ Q: [{qStr}], QE: [{qeStr}] }}"; + } + } + + [StructLayout(LayoutKind.Sequential)] + public struct FlexivError + { + public int error_code; + [MarshalAs(UnmanagedType.ByValTStr, SizeConst = 512)] + public string error_msg; + } + + public enum RobotMode : int + { + UNKNOWN = 0, + IDLE = 1, + RT_JOINT_TORQUE = 2, + RT_JOINT_IMPEDANCE = 3, + NRT_JOINT_IMPEDANCE = 4, + RT_JOINT_POSITION = 5, + NRT_JOINT_POSITION = 6, + NRT_PLAN_EXECUTION = 7, + NRT_PRIMITIVE_EXECUTION = 8, + RT_CARTESIAN_MOTION_FORCE = 9, + NRT_CARTESIAN_MOTION_FORCE = 10, + MODES_CNT = 11 + } + + public enum OperationalStatus : int + { + UNKNOWN = 0, + READY = 1, + BOOTING = 2, + ESTOP_NOT_RELEASED = 3, + NOT_ENABLED = 4, + RELEASING_BRAKE = 5, + MINOR_FAULT = 6, + CRITICAL_FAULT = 7, + IN_REDUCED_STATE = 8, + IN_RECOVERY_STATE = 9, + IN_MANUAL_MODE = 10, + IN_AUTO_MODE = 11 + } + + public enum CoordType : int + { + WORLD = 0, + TCP = 1, + } + + [StructLayout(LayoutKind.Sequential)] + public struct RobotState + { + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kSerialJointDoF)] + public double[] Q; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kSerialJointDoF)] + public double[] Theta; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kSerialJointDoF)] + public double[] DQ; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kSerialJointDoF)] + public double[] DTheta; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kSerialJointDoF)] + public double[] Tau; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kSerialJointDoF)] + public double[] TauDes; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kSerialJointDoF)] + public double[] TauDot; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kSerialJointDoF)] + public double[] TauExt; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kMaxExtAxes)] + public double[] QE; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kMaxExtAxes)] + public double[] DQE; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kMaxExtAxes)] + public double[] TauE; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kPoseSize)] + public double[] TcpPose; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kPoseSize)] + public double[] TcpPoseDes; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kCartDoF)] + public double[] TcpVel; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kPoseSize)] + public double[] FlangePose; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kCartDoF)] + public double[] FtSensorRaw; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kCartDoF)] + public double[] ExtWrenchInTcp; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kCartDoF)] + public double[] ExtWrenchInWorld; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kCartDoF)] + public double[] ExtWrenchInTcpRaw; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kCartDoF)] + public double[] ExtWrenchInWorldRaw; + + public override string ToString() + { + var sb = new System.Text.StringBuilder(); + void AppendArray(string name, double[] arr, int decimals = 5) + { + if (arr == null || arr.Length == 0) + { + sb.AppendLine($"{name}: "); + return; + } + string formatStr = $"F{decimals}"; + var formattedValues = arr.Select(v => v.ToString(formatStr)); + sb.AppendLine($"{name}: {string.Join(", ", formattedValues)}"); + } + AppendArray(nameof(Q), Q); + AppendArray(nameof(Theta), Theta); + AppendArray(nameof(DQ), DQ); + AppendArray(nameof(DTheta), DTheta); + AppendArray(nameof(Tau), Tau); + AppendArray(nameof(TauDes), TauDes); + AppendArray(nameof(TauDot), TauDot); + AppendArray(nameof(TauExt), TauExt); + AppendArray(nameof(QE), QE); + AppendArray(nameof(DQE), DQE); + AppendArray(nameof(TauE), TauE); + AppendArray(nameof(TcpPose), TcpPose); + AppendArray(nameof(TcpPoseDes), TcpPoseDes); + AppendArray(nameof(TcpVel), TcpVel); + AppendArray(nameof(FlangePose), FlangePose); + AppendArray(nameof(FtSensorRaw), FtSensorRaw); + AppendArray(nameof(ExtWrenchInTcp), ExtWrenchInTcp); + AppendArray(nameof(ExtWrenchInWorld), ExtWrenchInWorld); + AppendArray(nameof(ExtWrenchInTcpRaw), ExtWrenchInTcpRaw); + AppendArray(nameof(ExtWrenchInWorldRaw), ExtWrenchInWorldRaw); + return sb.ToString(); + } + } + + [StructLayout(LayoutKind.Sequential)] + public struct PlanInfo + { + [MarshalAs(UnmanagedType.ByValTStr, SizeConst = 128)] + public string PTName; + [MarshalAs(UnmanagedType.ByValTStr, SizeConst = 128)] + public string NodeName; + [MarshalAs(UnmanagedType.ByValTStr, SizeConst = 512)] + public string NodePath; + [MarshalAs(UnmanagedType.ByValTStr, SizeConst = 128)] + public string NodePathTimePeriod; + [MarshalAs(UnmanagedType.ByValTStr, SizeConst = 128)] + public string NodePathNumber; + [MarshalAs(UnmanagedType.ByValTStr, SizeConst = 128)] + public string AssignedPlanName; + public double VelocityScale; + public int WaitingForStep; + + public override string ToString() + { + return $" pt_name: {PTName}\n" + + $" node_name: {NodeName}\n" + + $" node_path: {NodePath}\n" + + $" node_path_time_period: {NodePathTimePeriod}\n" + + $" node_path_number: {NodePathNumber}\n" + + $" assigned_plan_name: {AssignedPlanName}\n" + + $" velocity_scale: {VelocityScale}\n" + + $" waiting_for_step: {WaitingForStep}"; + } + } + + [StructLayout(LayoutKind.Sequential)] + public struct RobotInfo + { + [MarshalAs(UnmanagedType.ByValTStr, SizeConst = 128)] + public string SerialNum; + [MarshalAs(UnmanagedType.ByValTStr, SizeConst = 128)] + public string SoftwareVer; + [MarshalAs(UnmanagedType.ByValTStr, SizeConst = 128)] + public string ModelName; + [MarshalAs(UnmanagedType.ByValTStr, SizeConst = 128)] + public string LicenseType; + public int DoF; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kCartDoF)] + public double[] KxNom; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kSerialJointDoF)] + public double[] KqNom; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kSerialJointDoF)] + public double[] QMin; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kSerialJointDoF)] + public double[] QMax; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kSerialJointDoF)] + public double[] DqMax; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kSerialJointDoF)] + public double[] TauMax; + + public override string ToString() + { + var sb = new StringBuilder(); + string FormatArray(double[] arr, int decimals = 5) + { + if (arr == null || arr.Length == 0) + return ""; + string formatStr = $"F{decimals}"; + return string.Join(", ", arr.Select(v => v.ToString(formatStr))); + } + sb.AppendLine($"SerialNum: {SerialNum}"); + sb.AppendLine($"SoftwareVer: {SoftwareVer}"); + sb.AppendLine($"ModelName: {ModelName}"); + sb.AppendLine($"LicenseType: {LicenseType}"); + sb.AppendLine($"DoF: {DoF}"); + sb.AppendLine($"KxNom: {FormatArray(KxNom)}"); + sb.AppendLine($"KqNom: {FormatArray(KqNom)}"); + sb.AppendLine($"QMin: {FormatArray(QMin)}"); + sb.AppendLine($"QMax: {FormatArray(QMax)}"); + sb.AppendLine($"DqMax: {FormatArray(DqMax)}"); + sb.AppendLine($"TauMax: {FormatArray(TauMax)}"); + return sb.ToString(); + } + } + + [StructLayout(LayoutKind.Sequential)] + public struct ToolParams + { + public double Mass; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 3)] + public double[] CoM; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = 6)] + public double[] Inertia; + [MarshalAs(UnmanagedType.ByValArray, SizeConst = FlexivConstants.kPoseSize)] + public double[] TcpLocation; + } + + [StructLayout(LayoutKind.Sequential)] + public struct GripperStates + { + public double Width; + public double Force; + public double MaxWidth; + } +} diff --git a/csharp/FlexivRdk/Device.cs b/csharp/FlexivRdk/Device.cs new file mode 100644 index 0000000..cde0ae7 --- /dev/null +++ b/csharp/FlexivRdk/Device.cs @@ -0,0 +1,102 @@ +using System; +using System.Collections.Generic; +using System.Runtime.InteropServices; +using System.Text.Json; + +namespace FlexivRdkCSharp.FlexivRdk +{ + public class Device : IDisposable + { + private IntPtr _devicePtr; + private bool _disposed = false; + private JsonSerializerOptions _options; + + public void Dispose() + { + Dispose(true); + GC.SuppressFinalize(this); + } + + protected virtual void Dispose(bool disposing) + { + if (_disposed) return; + if (disposing) + { + if (_options != null) _options = null; + } + if (_devicePtr != IntPtr.Zero) + { + NativeFlexivRdk.DeleteDevice(_devicePtr); + _devicePtr = IntPtr.Zero; + } + _disposed = true; + } + + private static void ThrowRdkException(FlexivError error) + { + if (error.error_code != 0) + { + string message = error.error_msg?.TrimEnd('\0') ?? "Unknown error"; + throw new Exception($"[Flexiv RDK Error {error.error_code}] {message}"); + } + } + + public Device(Robot robot) + { + if (robot == null) + throw new ArgumentNullException(nameof(robot)); + FlexivError error = new(); + _devicePtr = NativeFlexivRdk.CreateDevice(robot.NativePtr, ref error); + _options = new JsonSerializerOptions + { + WriteIndented = false, + PropertyNamingPolicy = JsonNamingPolicy.CamelCase + }; + ThrowRdkException(error); + } + + ~Device() => Dispose(false); + + public Dictionary GetDevicesList() + { + FlexivError error = new(); + IntPtr ptr = NativeFlexivRdk.GetDevicesList(_devicePtr, ref error); + ThrowRdkException(error); + NativeFlexivRdk.FreeString(ptr); + string str = Marshal.PtrToStringAnsi(ptr); + var tmp = JsonSerializer.Deserialize>(str); + if (tmp == null) tmp = new Dictionary(); + return new Dictionary(tmp); + } + + public bool HasDevice(string deviceName) + { + FlexivError error = new(); + int flag = NativeFlexivRdk.HasDevice(_devicePtr, deviceName, ref error); + ThrowRdkException(error); + return flag != 0; + } + + public void EnableDevice(string deviceName) + { + FlexivError error = new(); + NativeFlexivRdk.EnableDevice(_devicePtr, deviceName, ref error); + ThrowRdkException(error); + } + + public void DisableDevice(string deviceName) + { + FlexivError error = new(); + NativeFlexivRdk.DisableDevice(_devicePtr, deviceName, ref error); + ThrowRdkException(error); + } + + public void SendCommands(string deviceName, Dictionary cmds) + { + FlexivError error = new(); + string str = JsonSerializer.Serialize(cmds, _options); + NativeFlexivRdk.SendCommands(_devicePtr, deviceName, str, ref error); + ThrowRdkException(error); + } + } +} diff --git a/csharp/FlexivRdk/FileIO.cs b/csharp/FlexivRdk/FileIO.cs new file mode 100644 index 0000000..cc69737 --- /dev/null +++ b/csharp/FlexivRdk/FileIO.cs @@ -0,0 +1,53 @@ +using System; + +namespace FlexivRdkCSharp.FlexivRdk +{ + public class FileIO : IDisposable + { + private IntPtr _fileIOPtr; + private bool _disposed = false; + + public void Dispose() + { + Dispose(true); + GC.SuppressFinalize(this); + } + + protected virtual void Dispose(bool disposing) + { + if (_disposed) return; + if (_fileIOPtr != IntPtr.Zero) + { + NativeFlexivRdk.DeleteTool(_fileIOPtr); + _fileIOPtr = IntPtr.Zero; + } + _disposed = true; + } + + private static void ThrowRdkException(FlexivError error) + { + if (error.error_code != 0) + { + string message = error.error_msg?.TrimEnd('\0') ?? "Unknown error"; + throw new Exception($"[Flexiv RDK Error {error.error_code}] {message}"); + } + } + + public FileIO(Robot robot) + { + if (robot == null) + throw new ArgumentNullException(nameof(robot)); + FlexivError error = new(); + _fileIOPtr = NativeFlexivRdk.CreateFileIO(robot.NativePtr, ref error); + } + + ~FileIO() => Dispose(false); + + public void UploadTrajFile(string fileDir, string fileName) + { + FlexivError error = new(); + NativeFlexivRdk.UploadTrajFile(_fileIOPtr, fileDir, fileName, ref error); + ThrowRdkException(error); + } + } +} diff --git a/csharp/FlexivRdk/Gripper.cs b/csharp/FlexivRdk/Gripper.cs new file mode 100644 index 0000000..478abf5 --- /dev/null +++ b/csharp/FlexivRdk/Gripper.cs @@ -0,0 +1,97 @@ +using System; +using System.Text.Json; + +namespace FlexivRdkCSharp.FlexivRdk +{ + public class Gripper : IDisposable + { + private IntPtr _gripperPtr; + private bool _disposed = false; + private JsonSerializerOptions _options; + + public void Dispose() + { + Dispose(true); + GC.SuppressFinalize(this); + } + + protected virtual void Dispose(bool disposing) + { + if (_disposed) return; + if (disposing) + { + if (_options != null) _options = null; + } + if (_gripperPtr != IntPtr.Zero) + { + NativeFlexivRdk.DeleteGripper(_gripperPtr); + _gripperPtr = IntPtr.Zero; + } + _disposed = true; + } + + private static void ThrowRdkException(FlexivError error) + { + if (error.error_code != 0) + { + string message = error.error_msg?.TrimEnd('\0') ?? "Unknown error"; + throw new Exception($"[Flexiv RDK Error {error.error_code}] {message}"); + } + } + + public Gripper(Robot robot) + { + if (robot == null) + throw new ArgumentNullException(nameof(robot)); + FlexivError error = new(); + _gripperPtr = NativeFlexivRdk.CreateTool(robot.NativePtr, ref error); + _options = new JsonSerializerOptions + { + WriteIndented = false, + PropertyNamingPolicy = JsonNamingPolicy.CamelCase, + Converters = { new FlexivDataJsonConverter() } + }; + ThrowRdkException(error); + } + + ~Gripper() => Dispose(false); + + public void Init() + { + FlexivError error = new(); + NativeFlexivRdk.Init(_gripperPtr, ref error); + ThrowRdkException(error); + } + + public void Grasp(double force) + { + FlexivError error = new(); + NativeFlexivRdk.Grasp(_gripperPtr, force, ref error); + ThrowRdkException(error); + } + + public void Move(double width, double velocity, double forceLimit = 0) + { + FlexivError error = new(); + NativeFlexivRdk.Move(_gripperPtr, width, velocity, forceLimit, ref error); + ThrowRdkException(error); + } + + public void Stop() + { + NativeFlexivRdk.StopGripper(_gripperPtr); + } + + public bool IsMoving() + { + return NativeFlexivRdk.GripperIsMoving(_gripperPtr) != 0; + } + + public GripperStates GetGripperStates() + { + GripperStates states = new(); + NativeFlexivRdk.GetGripperStates(_gripperPtr, ref states); + return states; + } + } +} diff --git a/csharp/FlexivRdk/Native.cs b/csharp/FlexivRdk/Native.cs new file mode 100644 index 0000000..8b85811 --- /dev/null +++ b/csharp/FlexivRdk/Native.cs @@ -0,0 +1,308 @@ +using System; +using System.Runtime.InteropServices; + +namespace FlexivRdkCSharp.FlexivRdk +{ + internal static class NativeFlexivRdk + { + private const string k_flexivRdkDll = "flexiv_rdk.win64-vs2019.dll"; + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void FreeString(IntPtr ptr); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SpdlogInfo(string msgs); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SpdlogWarn(string msgs); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SpdlogError(string msgs); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern IntPtr CreateFlexivRobot(string robotSN, + [MarshalAs(UnmanagedType.LPArray, ArraySubType = UnmanagedType.LPStr)] string[] interfaces, + int interfaceCount, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void DeleteFlexivRobot(IntPtr robot); + + //========================================= ACCESSORS ========================================== + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int IsConnected(IntPtr robot); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void GetInfo(IntPtr robot, ref RobotInfo info); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int GetMode(IntPtr robot); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void GetStates(IntPtr robot, ref RobotState robot_state); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int IsStopped(IntPtr robot); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int IsOperational(IntPtr robot, int verbose); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int GetOperationalStatus(IntPtr robot); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int IsBusy(IntPtr robot); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int IsFault(IntPtr robot); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int IsReduced(IntPtr robot); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int IsRecovery(IntPtr robot); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int IsEstopReleased(IntPtr robot); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int IsEnablingButtonReleased(IntPtr robot); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern IntPtr GetMuLog(IntPtr robot); + + //======================================= SYSTEM CONTROL ======================================= + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void Enable(IntPtr robot, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void Brake(IntPtr robot, int engage, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SwitchMode(IntPtr robot, int mode, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void Stop(IntPtr robot, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int ClearFault(IntPtr robot, int timeout_sec, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void RunAutoRecovery(IntPtr robot, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SetGlobalVariables(IntPtr robot, string globalVars, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern IntPtr GetGlobalVariables(IntPtr robot, ref FlexivError error); + + //======================================= PLAN EXECUTION ======================================= + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void ExecutePlanByIdx(IntPtr robot, int idx, int continueExec, + int blockUntilStarted, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void ExecutePlanByName(IntPtr robot, string name, int continueExec, + int blockUntilStarted, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void PausePlan(IntPtr robot, int pause, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern IntPtr GetPlanList(IntPtr robot, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void GetPlanInfo(IntPtr robot, ref PlanInfo planInfo, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SetBreakpointMode(IntPtr robot, int IsEnable, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void StepBreakpoint(IntPtr robot, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SetVelocityScale(IntPtr robot, int velocityScale, ref FlexivError error); + + //==================================== PRIMITIVE EXECUTION ===================================== + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void ExecutePrimitive(IntPtr robot, string primitiveName, string inputParams, + string properties, int blockUntilStarted, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern IntPtr GetPrimitiveStates(IntPtr robot, ref FlexivError error); + + //==================================== DIRECT JOINT CONTROL ==================================== + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void StreamJointTorque(IntPtr robot, double[] torques, int torquesLen, + int enableGravityComp, int enableSoftLimits, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void StreamJointPosition(IntPtr robot, double[] pos, int posLen, + double[] vel, int velLen, double[] acc, int accLen, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SendJointPosition(IntPtr robot, double[] pos, int posLen, double[] vel, + int velLen, double[] acc, int accLen, double[] maxVel, int maxVelLen, double[] maxAcc, + int maxAccLen, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SetJointImpedance(IntPtr robot, double[] Kq, int KqLen, + double[] Zq, int ZqLen, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void StreamCartesianMotionForce(IntPtr robot, double[] pos, int posLen, + double[] wrench, int wrenchLen, double[] vel, int velLen, double[] acc, int accLen, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SendCartesianMotionForce(IntPtr robot, double[] pose, int poseLen, + double[] wrench, int wrenchLen, double maxLinearVel, double maxAngularVel, double maxLinearAcc, + double maxAngularAcc, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SetCartesianImpedance(IntPtr robot, double[] Kx, int KxLen, + double[] Zx, int ZxLen, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SetMaxContactWrench(IntPtr robot, double[] maxWrench, int maxWrenchLen, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SetNullSpacePosture(IntPtr robot, double[] refPositions, int refPositionsLen, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SetNullSpaceObjectives(IntPtr robot, double linearManipulability, + double angularManipulability, double refPositionsTracking, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SetForceControlAxis(IntPtr robot, int[] enabledAxes, int enabledAxesLen, + double[] maxLinearVel, int maxLinearVelLen, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SetForceControlFrame(IntPtr robot, int rootCoord, double[] TInRoot, int TInRootLen, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SetPassiveForceControl(IntPtr robot, int IsEnable, ref FlexivError error); + + //======================================== IO CONTROL ======================================== + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SetDigitalOutput(IntPtr robot, int idx, int value, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int GetDigitalInput(IntPtr robot, int idx); + + //========================================== TOOL ============================================ + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern IntPtr CreateTool(IntPtr robot, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void DeleteTool(IntPtr tool); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern IntPtr GetToolNames(IntPtr tool, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern IntPtr GetToolName(IntPtr tool, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int HasTool(IntPtr tool, string name, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void GetToolParams(IntPtr tool, ref ToolParams toolParams, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void GetToolParamsByName(IntPtr tool, string name, ref ToolParams toolParams, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void AddNewTool(IntPtr tool, string name, ref ToolParams toolParams, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SwitchTool(IntPtr tool, string name, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void UpdateTool(IntPtr tool, string name, ref ToolParams toolParams, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void RemoveTool(IntPtr tool, string name, ref FlexivError error); + + //======================================= WORK COORD ========================================= + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern IntPtr CreateWorkCoord(IntPtr robot, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void DeleteWorkCoord(IntPtr workCoord); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern IntPtr GetWorkCoordNames(IntPtr workCoord, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int HasWorkCoord(IntPtr workCoord, string name, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void GetWorkCoordPose(IntPtr workCoord, string name, ref double x, ref double y, + ref double z, ref double qw, ref double qx, ref double qy, ref double qz, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void AddWorkCoord(IntPtr workCoord, string name, double[] pose, int poseLen, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void UpdateWorkCoord(IntPtr workCoord, string name, double[] pose, int poseLen, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void RemoveWorkCoord(IntPtr workCoord, string name, ref FlexivError error); + + //======================================== GRIPPER =========================================== + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern IntPtr CreateGripper(IntPtr robot, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void DeleteGripper(IntPtr gripper); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void Init(IntPtr gripper, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void Grasp(IntPtr gripper, double force, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void Move(IntPtr gripper, double width, double velocity, double forceLimit, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void StopGripper(IntPtr gripper); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int GripperIsMoving(IntPtr gripper); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void GetGripperStates(IntPtr gripper, ref GripperStates states); + + //======================================== FILE IO =========================================== + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern IntPtr CreateFileIO(IntPtr robot, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void DeleteFileIO(IntPtr fileIO); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void UploadTrajFile(IntPtr fileIO, string fileDir, string fileName, ref FlexivError error); + + //========================================= DEVICE =========================================== + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern IntPtr CreateDevice(IntPtr robot, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void DeleteDevice(IntPtr device); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern IntPtr GetDevicesList(IntPtr device, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern int HasDevice(IntPtr device, string deviceName, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void EnableDevice(IntPtr device, string deviceName, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void DisableDevice(IntPtr device, string deviceName, ref FlexivError error); + + [DllImport(k_flexivRdkDll, CallingConvention = CallingConvention.Cdecl)] + public static extern void SendCommands(IntPtr device, string deviceName, string cmds, ref FlexivError error); + } +} diff --git a/csharp/FlexivRdk/Robot.cs b/csharp/FlexivRdk/Robot.cs new file mode 100644 index 0000000..286550e --- /dev/null +++ b/csharp/FlexivRdk/Robot.cs @@ -0,0 +1,427 @@ +using System; +using System.Collections.Generic; +using System.Runtime.InteropServices; +using System.Text.Json; + +namespace FlexivRdkCSharp.FlexivRdk +{ + public class Robot : IDisposable + { + private bool _disposed = false; + private IntPtr _flexivRobotPtr; + private JsonSerializerOptions _options; + public IntPtr NativePtr => _flexivRobotPtr; + public void Dispose() + { + Dispose(true); + GC.SuppressFinalize(this); + } + + protected virtual void Dispose(bool disposing) + { + if (_disposed) return; + if (disposing) + { + if (_options != null) _options = null; + } + if (_flexivRobotPtr != IntPtr.Zero) + { + NativeFlexivRdk.DeleteFlexivRobot(_flexivRobotPtr); + _flexivRobotPtr = IntPtr.Zero; + } + _disposed = true; + } + + private static void ThrowRdkException(FlexivError error) + { + if (error.error_code != 0) + { + string message = error.error_msg?.TrimEnd('\0') ?? "Unknown error"; + throw new Exception($"[Flexiv RDK Error {error.error_code}] {message}"); + } + } + + public Robot(string robotSN, string[] networkInterfaceWhiteList = null) + { + FlexivError error = new(); + string[] interfaces = networkInterfaceWhiteList ?? Array.Empty(); + _flexivRobotPtr = NativeFlexivRdk.CreateFlexivRobot(robotSN, interfaces, interfaces.Length, ref error); + _options = new JsonSerializerOptions + { + WriteIndented = false, + PropertyNamingPolicy = JsonNamingPolicy.CamelCase, + Converters = { new FlexivDataJsonConverter() } + }; + ThrowRdkException(error); + } + + ~Robot() => Dispose(false); + + //========================================= ACCESSORS ========================================== + public bool IsConnected() + { + return NativeFlexivRdk.IsConnected(_flexivRobotPtr) != 0; + } + + public RobotInfo GetInfo() + { + RobotInfo robotInfo = new(); + NativeFlexivRdk.GetInfo(_flexivRobotPtr, ref robotInfo); + return robotInfo; + } + + public RobotMode GetMode() + { + return (RobotMode)NativeFlexivRdk.GetMode(_flexivRobotPtr); + } + + public RobotState GetStates() + { + RobotState robot_state = new(); + NativeFlexivRdk.GetStates(_flexivRobotPtr, ref robot_state); + return robot_state; + } + + public bool IsStopped() + { + return NativeFlexivRdk.IsStopped(_flexivRobotPtr) != 0; + } + + public bool IsOperational(bool verbose = true) + { + return NativeFlexivRdk.IsOperational(_flexivRobotPtr, verbose ? 1 : 0) != 0; + } + + public OperationalStatus GetOperationalStatus() + { + return (OperationalStatus)NativeFlexivRdk.GetOperationalStatus(_flexivRobotPtr); + } + + public bool IsBusy() + { + return NativeFlexivRdk.IsBusy(_flexivRobotPtr) != 0; + } + + public bool IsFault() + { + return NativeFlexivRdk.IsFault(_flexivRobotPtr) != 0; + } + + public bool IsReduced() + { + return NativeFlexivRdk.IsReduced(_flexivRobotPtr) != 0; + } + + public bool IsRecovery() + { + return NativeFlexivRdk.IsRecovery(_flexivRobotPtr) != 0; + } + + public bool IsEstopReleased() + { + return NativeFlexivRdk.IsEstopReleased(_flexivRobotPtr) != 0; + } + + public bool IsEnablingButtonReleased() + { + return NativeFlexivRdk.IsEnablingButtonReleased(_flexivRobotPtr) != 0; + } + + public List GetMuLog() + { + IntPtr ptr = NativeFlexivRdk.GetMuLog(_flexivRobotPtr); + string str = Marshal.PtrToStringAnsi(ptr); + NativeFlexivRdk.FreeString(ptr); + var tmp = JsonSerializer.Deserialize>(str, _options); + string json = JsonSerializer.Serialize(tmp, _options); + var ret = (List)(tmp["mu_log"]); + return new List(ret); + } + + //======================================= SYSTEM CONTROL ======================================= + public void Enable() + { + FlexivError error = new(); + NativeFlexivRdk.Enable(_flexivRobotPtr, ref error); + ThrowRdkException(error); + } + + public void Brake(bool engage) + { + FlexivError error = new(); + NativeFlexivRdk.Brake(_flexivRobotPtr, engage ? 1 : 0, ref error); + ThrowRdkException(error); + } + + public void SwitchMode(RobotMode mode) + { + FlexivError error = new(); + NativeFlexivRdk.SwitchMode(_flexivRobotPtr, ((int)mode), ref error); + ThrowRdkException(error); + } + + public void Stop() + { + FlexivError error = new(); + NativeFlexivRdk.Stop(_flexivRobotPtr, ref error); + ThrowRdkException(error); + } + + public bool ClearFault(int timeoutSec = 30) + { + FlexivError error = new(); + int flag = NativeFlexivRdk.ClearFault(_flexivRobotPtr, timeoutSec, ref error); + ThrowRdkException(error); + return flag != 0; + } + + public void RunAutoRecovery() + { + FlexivError error = new(); + NativeFlexivRdk.RunAutoRecovery(_flexivRobotPtr, ref error); + ThrowRdkException(error); + } + + public void SetGlobalVariables(Dictionary globalVars) + { + FlexivError error = new(); + string json_str = JsonSerializer.Serialize(globalVars, _options); + NativeFlexivRdk.SetGlobalVariables(_flexivRobotPtr, json_str, ref error); + ThrowRdkException(error); + } + + public Dictionary GetGlobalVariables() + { + FlexivError error = new(); + IntPtr ptr = NativeFlexivRdk.GetGlobalVariables(_flexivRobotPtr, ref error); + ThrowRdkException(error); + NativeFlexivRdk.FreeString(ptr); + string str = Marshal.PtrToStringAnsi(ptr); + var tmp = JsonSerializer.Deserialize>(str, _options); + if (tmp == null) tmp = new Dictionary(); + return new Dictionary(tmp); + } + + //======================================= PLAN EXECUTION ======================================= + public void ExecutePlan(int index, bool continueExec = false, bool blockUntilStarted = true) + { + FlexivError error = new(); + NativeFlexivRdk.ExecutePlanByIdx(_flexivRobotPtr, index, continueExec ? 1 : 0, blockUntilStarted ? 1 : 0, ref error); + ThrowRdkException(error); + } + + public void ExecutePlan(string name, bool continueExec = false, bool blockUntilStarted = true) + { + FlexivError error = new(); + NativeFlexivRdk.ExecutePlanByName(_flexivRobotPtr, name, continueExec ? 1 : 0, blockUntilStarted ? 1 : 0, ref error); + ThrowRdkException(error); + } + + public void PausePlan(bool pause) + { + FlexivError error = new(); + NativeFlexivRdk.PausePlan(_flexivRobotPtr, pause ? 1 : 0, ref error); + ThrowRdkException(error); + } + + public List GetPlanList() + { + FlexivError error = new(); + IntPtr ptr = NativeFlexivRdk.GetPlanList(_flexivRobotPtr, ref error); + ThrowRdkException(error); + string str = Marshal.PtrToStringAnsi(ptr); + NativeFlexivRdk.FreeString(ptr); + Console.WriteLine(str); + var tmp = JsonSerializer.Deserialize>(str, _options); + string json = JsonSerializer.Serialize(tmp, _options); + var ret = (List)(tmp["plan_list"]); + return new List(ret); + } + + public PlanInfo GetPlanInfo() + { + PlanInfo plan_info = new(); + FlexivError error = new FlexivError(); + NativeFlexivRdk.GetPlanInfo(_flexivRobotPtr, ref plan_info, ref error); + ThrowRdkException(error); + return plan_info; + } + + public void SetBreakpointMode(bool IsEnable) + { + FlexivError error = new(); + NativeFlexivRdk.SetBreakpointMode(_flexivRobotPtr, IsEnable ? 1 : 0, ref error); + ThrowRdkException(error); + } + + public void StepBreakpoint() + { + FlexivError error = new(); + NativeFlexivRdk.StepBreakpoint(_flexivRobotPtr, ref error); + ThrowRdkException(error); + } + + public void SetVelocityScale(int velocityScale) + { + FlexivError error = new(); + NativeFlexivRdk.SetVelocityScale(_flexivRobotPtr, velocityScale, ref error); + ThrowRdkException(error); + } + + //==================================== PRIMITIVE EXECUTION ===================================== + public void ExecutePrimitive(string primitiveName, + Dictionary inputParams, + Dictionary properties = null, + bool blockUntilStarted = true) + { + FlexivError error = new(); + string input_params = JsonSerializer.Serialize(inputParams, _options); + string pro = properties != null ? JsonSerializer.Serialize(properties, _options) : "{}"; + NativeFlexivRdk.ExecutePrimitive(_flexivRobotPtr, primitiveName, + input_params, pro, blockUntilStarted ? 1 : 0, ref error); + ThrowRdkException(error); + } + + public Dictionary GetPrimitiveStates() + { + FlexivError error = new(); + IntPtr ptr = NativeFlexivRdk.GetPrimitiveStates(_flexivRobotPtr, ref error); + ThrowRdkException(error); + NativeFlexivRdk.FreeString(ptr); + string str = Marshal.PtrToStringAnsi(ptr); + var tmp = JsonSerializer.Deserialize>(str, _options); + if (tmp == null) tmp = new Dictionary(); + return new Dictionary(tmp); + } + + //==================================== DIRECT JOINT CONTROL ==================================== + public void StreamJointTorque(double[] torques, bool enableGravityComp = true, bool enableSoftLimits = true) + { + FlexivError error = new(); + NativeFlexivRdk.StreamJointTorque(_flexivRobotPtr, torques, torques.Length, + enableGravityComp ? 1 : 0, enableSoftLimits ? 1 : 0, ref error); + ThrowRdkException(error); + } + + public void StreamJointPosition(double[] positions, double[] velocities, double[] accelerations) + { + FlexivError error = new(); + NativeFlexivRdk.StreamJointPosition(_flexivRobotPtr, positions, positions.Length, velocities, velocities.Length, + accelerations, accelerations.Length, ref error); + ThrowRdkException(error); + } + + public void SendJointPosition(double[] positions, double[] velocities, double[] accelerations, + double[] maxVel, double[] maxAcc) + { + FlexivError error = new(); + NativeFlexivRdk.SendJointPosition(_flexivRobotPtr, positions, positions.Length, velocities, + velocities.Length, accelerations, accelerations.Length, maxVel, maxVel.Length, + maxAcc, maxAcc.Length, ref error); + ThrowRdkException(error); + } + + public void SetJointImpedance(double[] Kq, double[] Zq = null) + { + FlexivError error = new(); + if (Zq == null) Zq = new double[] { 0.7, 0.7, 0.7, 0.7, 0.7, 0.7, 0.7 }; + NativeFlexivRdk.SetJointImpedance(_flexivRobotPtr, Kq, Kq.Length, Zq, Zq.Length, ref error); + ThrowRdkException(error); + } + + public void StreamCartesianMotionForce(double[] pose, + double[] wrench = null, double[] velocity = null, double[] acceleration = null) + { + FlexivError error = new(); + if (wrench == null) wrench = new double[] { 0, 0, 0, 0, 0, 0 }; + if (velocity == null) velocity = new double[] { 0, 0, 0, 0, 0, 0 }; + if (acceleration == null) acceleration = new double[] { 0, 0, 0, 0, 0, 0 }; + NativeFlexivRdk.StreamCartesianMotionForce(_flexivRobotPtr, pose, pose.Length, + wrench, wrench.Length, velocity, velocity.Length, acceleration, acceleration.Length, ref error); + ThrowRdkException(error); + } + + public void SendCartesianMotionForce(double[] pose, double[] wrench = null, double maxLinearVel = 0.5, + double maxAngularVel = 1.0, double maxLinearAcc = 2.0, double maxAngularAcc = 5.0) + { + FlexivError error = new(); + if (wrench == null) wrench = new double[] { 0, 0, 0, 0, 0, 0 }; + NativeFlexivRdk.SendCartesianMotionForce(_flexivRobotPtr, pose, pose.Length, wrench, wrench.Length, + maxLinearVel, maxAngularVel, maxLinearAcc, maxAngularAcc, ref error); + ThrowRdkException(error); + } + + public void SetCartesianImpedance(double[] Kx, double[] Zx = null) + { + FlexivError error = new(); + if (Zx == null) Zx = new double[] { 0.7, 0.7, 0.7, 0.7, 0.7, 0.7 }; + NativeFlexivRdk.SetCartesianImpedance(_flexivRobotPtr, Kx, Kx.Length, Zx, Zx.Length, ref error); + ThrowRdkException(error); + } + + public void SetMaxContactWrench(double[] maxWrench) + { + FlexivError error = new(); + NativeFlexivRdk.SetMaxContactWrench(_flexivRobotPtr, maxWrench, maxWrench.Length, ref error); + ThrowRdkException(error); + } + + public void SetNullSpacePosture(double[] refPositions) + { + FlexivError error = new(); + NativeFlexivRdk.SetNullSpacePosture(_flexivRobotPtr, refPositions, refPositions.Length, ref error); + ThrowRdkException(error); + } + + public void SetNullSpaceObjectives(double linearManipulability = 0.0, double angularManipulability = 0.0, double refPositionsTracking = 0.5) + { + FlexivError error = new(); + NativeFlexivRdk.SetNullSpaceObjectives(_flexivRobotPtr, linearManipulability, angularManipulability, refPositionsTracking, ref error); + ThrowRdkException(error); + } + + public void SetForceControlAxis(bool[] enabledAxes, double[] maxLinearVel = null) + { + if (maxLinearVel == null) maxLinearVel = new double[] { 1.0, 1.0, 1.0 }; + int[] intArray = new int[enabledAxes.Length]; + for (int i = 0; i < enabledAxes.Length; ++i) + intArray[i] = enabledAxes[i] ? 1 : 0; + FlexivError error = new(); + NativeFlexivRdk.SetForceControlAxis(_flexivRobotPtr, intArray, intArray.Length, maxLinearVel, maxLinearVel.Length, ref error); + ThrowRdkException(error); + } + + public void SetForceControlFrame(CoordType rootCoord, double[] TInRoot = null) + { + if (TInRoot == null) TInRoot = new double[] { 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0 }; + FlexivError error = new(); + NativeFlexivRdk.SetForceControlFrame(_flexivRobotPtr, (int)rootCoord, TInRoot, TInRoot.Length, ref error); + ThrowRdkException(error); + } + + public void SetPassiveForceControl(bool IsEnabled) + { + FlexivError error = new(); + NativeFlexivRdk.SetPassiveForceControl(_flexivRobotPtr, IsEnabled ? 1 : 0, ref error); + ThrowRdkException(error); + } + + //======================================== IO CONTROL ======================================== + public void SetDigitalOutput(int idx, bool value) + { + if (idx < 0 || idx >= FlexivConstants.kIOPorts) + throw new ArgumentOutOfRangeException(nameof(idx), $"Index must be in range [0, {FlexivConstants.kIOPorts - 1}]"); + FlexivError error = new(); + NativeFlexivRdk.SetDigitalOutput(_flexivRobotPtr, idx, value ? 1 : 0, ref error); + ThrowRdkException(error); + } + + public bool GetDigitalInput(int idx) + { + if (idx < 0 || idx >= FlexivConstants.kIOPorts) + throw new ArgumentOutOfRangeException(nameof(idx), $"Index must be in range [0, {FlexivConstants.kIOPorts - 1}]"); + int flag = NativeFlexivRdk.GetDigitalInput(_flexivRobotPtr, idx); + return flag != 0; + } + } +} diff --git a/csharp/FlexivRdk/Tool.cs b/csharp/FlexivRdk/Tool.cs new file mode 100644 index 0000000..2fbabe3 --- /dev/null +++ b/csharp/FlexivRdk/Tool.cs @@ -0,0 +1,138 @@ +using System; +using System.Collections.Generic; +using System.Runtime.InteropServices; +using System.Text.Json; + +namespace FlexivRdkCSharp.FlexivRdk +{ + public class Tool : IDisposable + { + private IntPtr _toolPtr; + private bool _disposed = false; + private JsonSerializerOptions _options; + + public void Dispose() + { + Dispose(true); + GC.SuppressFinalize(this); + } + + protected virtual void Dispose(bool disposing) + { + if (_disposed) return; + if (disposing) + { + if (_options != null) _options = null; + } + if (_toolPtr != IntPtr.Zero) + { + NativeFlexivRdk.DeleteTool(_toolPtr); + _toolPtr = IntPtr.Zero; + } + _disposed = true; + } + + private static void ThrowRdkException(FlexivError error) + { + if (error.error_code != 0) + { + string message = error.error_msg?.TrimEnd('\0') ?? "Unknown error"; + throw new Exception($"[Flexiv RDK Error {error.error_code}] {message}"); + } + } + + public Tool(Robot robot) + { + if (robot == null) + throw new ArgumentNullException(nameof(robot)); + FlexivError error = new(); + _toolPtr = NativeFlexivRdk.CreateTool(robot.NativePtr, ref error); + _options = new JsonSerializerOptions + { + WriteIndented = false, + PropertyNamingPolicy = JsonNamingPolicy.CamelCase, + Converters = { new FlexivDataJsonConverter() } + }; + ThrowRdkException(error); + } + + ~Tool() => Dispose(false); + + public List GetToolNames() + { + FlexivError error = new(); + IntPtr ptr = NativeFlexivRdk.GetToolNames(_toolPtr, ref error); + ThrowRdkException(error); + string str = Marshal.PtrToStringAnsi(ptr); + NativeFlexivRdk.FreeString(ptr); + var tmp = JsonSerializer.Deserialize>(str, _options); + string json = JsonSerializer.Serialize(tmp, _options); + var ret = (List)tmp["tool_list"]; + return new List(ret); + } + + public string GetToolName() + { + FlexivError error = new(); + IntPtr ptr = NativeFlexivRdk.GetToolName(_toolPtr, ref error); + ThrowRdkException(error); + string str = Marshal.PtrToStringAnsi(ptr); + NativeFlexivRdk.FreeString(ptr); + return str; + } + + public bool HasTool(string toolName) + { + FlexivError error = new(); + int flag = NativeFlexivRdk.HasTool(_toolPtr, toolName, ref error); + ThrowRdkException(error); + return flag != 0; + } + + public ToolParams GetToolParams() + { + FlexivError error = new(); + ToolParams toolParams = new(); + NativeFlexivRdk.GetToolParams(_toolPtr, ref toolParams, ref error); + ThrowRdkException(error); + return toolParams; + } + + public ToolParams GetToolParams(string toolName) + { + FlexivError error = new(); + ToolParams toolParams = new(); + NativeFlexivRdk.GetToolParamsByName(_toolPtr, toolName, ref toolParams, ref error); + ThrowRdkException(error); + return toolParams; + } + + public void AddNewTool(string toolName, ToolParams toolParams) + { + FlexivError error = new(); + NativeFlexivRdk.AddNewTool(_toolPtr, toolName, ref toolParams, ref error); + ThrowRdkException(error); + } + + public void SwitchTool(string toolName) + { + FlexivError error = new(); + NativeFlexivRdk.SwitchTool(_toolPtr, toolName, ref error); + ThrowRdkException(error); + } + + public void UpdateTool(string toolName, ToolParams toolParams) + { + FlexivError error = new(); + NativeFlexivRdk.UpdateTool(_toolPtr, toolName, ref toolParams, ref error); + ThrowRdkException(error); + } + + public void RemoveTool(string toolName) + { + FlexivError error = new(); + NativeFlexivRdk.RemoveTool(_toolPtr, toolName, ref error); + ThrowRdkException(error); + } + } +} diff --git a/csharp/FlexivRdk/Utility.cs b/csharp/FlexivRdk/Utility.cs new file mode 100644 index 0000000..71c1dba --- /dev/null +++ b/csharp/FlexivRdk/Utility.cs @@ -0,0 +1,84 @@ +using System; +using System.Collections.Generic; +using System.Text; + +namespace FlexivRdkCSharp.FlexivRdk +{ + public class Utility + { + public static void Quat2EulerZYX(double qw, double qx, double qy, double qz, + ref double x, ref double y, ref double z) + { + z = Math.Atan2(2 * (qw * qz + qx * qy), 1 - 2 * (qy * qy + qz * qz)); + double sinp = 2 * (qw * qy - qz * qx); + if (Math.Abs(sinp) >= 1) + y = Math.CopySign(Math.PI / 2, sinp); + else + y = Math.Asin(sinp); + x = Math.Atan2(2 * (qw * qx + qy * qz), 1 - 2 * (qx * qx + qy * qy)); + } + public static double Rad2Deg(double rad) + { + return rad * 180 / 3.14159265358979323846; + } + public static double Deg2Rad(double deg) + { + return deg * 3.14159265358979323846 / 180; + } + public static void EulerZYX2Quat(double z, double y, double x, + ref double qw, ref double qx, ref double qy, ref double qz) + { + double cy = Math.Cos(z * 0.5); + double sy = Math.Sin(z * 0.5); + double cp = Math.Cos(y * 0.5); + double sp = Math.Sin(y * 0.5); + double cr = Math.Cos(x * 0.5); + double sr = Math.Sin(x * 0.5); + qw = cy * cp * cr + sy * sp * sr; + qx = cy * cp * sr - sy * sp * cr; + qy = sy * cp * sr + cy * sp * cr; + qz = sy * cp * cr - cy * sp * sr; + } + + public static void SpdlogInfo(string msgs) + { + NativeFlexivRdk.SpdlogInfo(msgs); + } + + public static void SpdlogError(string msgs) + { + NativeFlexivRdk.SpdlogError(msgs); + } + + public static void SpdlogWarn(string msgs) + { + NativeFlexivRdk.SpdlogWarn(msgs); + } + + public static string FlexivDataDictToString(Dictionary dict) + { + if (dict == null || dict.Count == 0) + return "{}"; + var sb = new StringBuilder(); + // sb.AppendLine("{"); + foreach (var kvp in dict) + { + string key = kvp.Key; + string valueStr; + try + { + valueStr = kvp.Value?.ToString() ?? "null"; + } + catch (Exception ex) + { + valueStr = $"(error: {ex.Message})"; + } + + sb.AppendLine($" \"{key}\": {valueStr}"); + } + // sb.Append("}"); + return sb.ToString(); + } + + } +} diff --git a/csharp/FlexivRdk/WorkCoord.cs b/csharp/FlexivRdk/WorkCoord.cs new file mode 100644 index 0000000..b8797e6 --- /dev/null +++ b/csharp/FlexivRdk/WorkCoord.cs @@ -0,0 +1,117 @@ +using System; +using System.Collections.Generic; +using System.Runtime.InteropServices; +using System.Text.Json; + +namespace FlexivRdkCSharp.FlexivRdk +{ + public class WorkCoord : IDisposable + { + private IntPtr _workCoordPtr; + private bool _disposed = false; + private JsonSerializerOptions _options; + + public void Dispose() + { + Dispose(true); + GC.SuppressFinalize(this); + } + + protected virtual void Dispose(bool disposing) + { + if (_disposed) return; + if (disposing) + { + if (_options != null) _options = null; + } + if (_workCoordPtr != IntPtr.Zero) + { + NativeFlexivRdk.DeleteTool(_workCoordPtr); + _workCoordPtr = IntPtr.Zero; + } + _disposed = true; + } + + private static void ThrowRdkException(FlexivError error) + { + if (error.error_code != 0) + { + string message = error.error_msg?.TrimEnd('\0') ?? "Unknown error"; + throw new Exception($"[Flexiv RDK Error {error.error_code}] {message}"); + } + } + + public WorkCoord(Robot robot) + { + if (robot == null) + throw new ArgumentNullException(nameof(robot)); + FlexivError error = new(); + _workCoordPtr = NativeFlexivRdk.CreateWorkCoord(robot.NativePtr, ref error); + _options = new JsonSerializerOptions + { + WriteIndented = false, + PropertyNamingPolicy = JsonNamingPolicy.CamelCase, + Converters = { new FlexivDataJsonConverter() } + }; + ThrowRdkException(error); + } + + ~WorkCoord() => Dispose(false); + + public List GetWorkCoordNames() + { + FlexivError error = new(); + IntPtr ptr = NativeFlexivRdk.GetWorkCoordNames(_workCoordPtr, ref error); + ThrowRdkException(error); + string str = Marshal.PtrToStringAnsi(ptr); + NativeFlexivRdk.FreeString(ptr); + var tmp = JsonSerializer.Deserialize>(str, _options); + string json = JsonSerializer.Serialize(tmp, _options); + var ret = (List)tmp["work_coord_list"]; + return new List(ret); + } + + public bool HasWorkCoord(string workCoordName) + { + FlexivError error = new(); + int flag = NativeFlexivRdk.HasWorkCoord(_workCoordPtr, workCoordName, ref error); + ThrowRdkException(error); + return flag != 0; + } + + public double[] GetWorkCoordPose(string workCoordName) + { + FlexivError error = new(); + double x = 0, y = 0, z = 0, qw = 0, qx = 0, qy = 0, qz = 0; + NativeFlexivRdk.GetWorkCoordPose(_workCoordPtr, workCoordName, ref x, ref y, + ref z, ref qw, ref qx, ref qy, ref qz, ref error); + ThrowRdkException(error); + return new double[] { x, y, z, qw, qx, qy, qz }; + } + + public void AddWorkCoord(string workCoordName, double[] pose) + { + if (pose.Length != FlexivConstants.kPoseSize) + throw new ArgumentException("FlexivRdk AddWorkCoord pose length must be 7"); + FlexivError error = new(); + NativeFlexivRdk.AddWorkCoord(_workCoordPtr, workCoordName, pose, pose.Length, ref error); + ThrowRdkException(error); + } + + public void UpdateWorkCoord(string workCoordName, double[] pose) + { + if (pose.Length != FlexivConstants.kPoseSize) + throw new ArgumentException("FlexivRdk UpdateWorkCoord pose length must be 7"); + FlexivError error = new(); + NativeFlexivRdk.UpdateWorkCoord(_workCoordPtr, workCoordName, pose, pose.Length, ref error); + ThrowRdkException(error); + } + + public void RemoveWorkCoord(string workCoordName) + { + FlexivError error = new(); + NativeFlexivRdk.RemoveWorkCoord(_workCoordPtr, workCoordName, ref error); + ThrowRdkException(error); + } + } +} diff --git a/csharp/Program.cs b/csharp/Program.cs new file mode 100644 index 0000000..ac7ec0a --- /dev/null +++ b/csharp/Program.cs @@ -0,0 +1,49 @@ +using System; +using System.Collections.Generic; +using FlexivRdkCSharp.Examples; + +namespace FlexivRdkCSharp +{ + class Program + { + static readonly List Examples = new() + { + new Basics1DisplayRobotStates(), + new Basics2ClearFault(), + new Basics3PrimitiveExecution(), + new Basics4PlanExecution(), + new Basics5ZeroFTSensor(), + new Basics6GripperControl(), + new Basics7AutoRecovery(), + new Basics8UpdateRobotTool(), + new Basics9GlobalVariables(), + new Intermed1NRTJntPosCtrl(), + new Intermed2NRTJntImpCtrl(), + new Intermed3NRTCartPureMotionCtrl(), + new Intermed4NRTCartMotionForceCtrl(), + }; + + static void Main(string[] args) + { + if (args.Length == 0 || args[0] == "--help") + { + Console.WriteLine("Usage: FlexivRdkCSharp [args...]"); + Console.WriteLine("Available examples:"); + foreach (var ex in Examples) + { + Console.WriteLine($" {ex.Name,-40} - {ex.Description}"); + } + Console.WriteLine("\nUse 'FlexivRdkCSharp ' to see detailed usage of a specific example."); + return; + } + string selected = args[0]; + var example = Examples.Find(e => e.Name == selected); + if (example == null) + { + Console.WriteLine($"Unknown example: {selected}"); + return; + } + example.Run(args[1..]); + } + } +} diff --git a/csharp/build.csproj b/csharp/build.csproj new file mode 100644 index 0000000..2b0ef94 --- /dev/null +++ b/csharp/build.csproj @@ -0,0 +1,18 @@ + + + + Exe + net8.0 + x64 + + + + + ..\released_dll + + + + + + + diff --git a/csharp/csharp.csproj b/csharp/csharp.csproj new file mode 100644 index 0000000..666643c --- /dev/null +++ b/csharp/csharp.csproj @@ -0,0 +1,18 @@ + + + + Exe + net5.0 + x64 + + + + + ..\released_dll + + + + + + + diff --git a/released_dll/flexiv_rdk.win64-vs2019.dll b/released_dll/flexiv_rdk.win64-vs2019.dll new file mode 100644 index 0000000..f5f8a95 Binary files /dev/null and b/released_dll/flexiv_rdk.win64-vs2019.dll differ diff --git a/third_party/build_and_install_flexiv_rdk.sh b/third_party/build_and_install_flexiv_rdk.sh new file mode 100644 index 0000000..661ef77 --- /dev/null +++ b/third_party/build_and_install_flexiv_rdk.sh @@ -0,0 +1,29 @@ +#!/bin/sh +echo ">>> Installing components: flexiv_rdk" +SCRIPTPATH="$(dirname $(readlink -f $0))" + +set -e +INSTALL_DIR="$SCRIPTPATH/../install" +NUM_JOBS=4 + +if [ ! -d "$SCRIPTPATH/flexiv_rdk" ] || [ -z "$(ls -A $SCRIPTPATH/flexiv_rdk)" ]; then + echo ">>> Cloning flexiv_rdk repo..." + git clone https://github.com/flexivrobotics/flexiv_rdk.git "$SCRIPTPATH/flexiv_rdk" +else + echo ">>> flexiv_rdk already exists and is not empty" +fi + +cd $SCRIPTPATH/flexiv_rdk +# Use specific version +git fetch -p +git checkout v1.5.1 +# git submodule update --init --recursive +# Build and install dependencies +cd thirdparty +bash build_and_install_dependencies.sh $INSTALL_DIR/rdk_install +cd .. +# Configure CMake +cmake -B build -DCMAKE_PREFIX_PATH=$INSTALL_DIR/rdk_install +# Build and install +cmake --build build --target install --config release -j $NUM_JOBS +echo ">>> Installed components: flexiv rdk" \ No newline at end of file diff --git a/third_party/nlohmann_json/json.hpp b/third_party/nlohmann_json/json.hpp new file mode 100644 index 0000000..82d69f7 --- /dev/null +++ b/third_party/nlohmann_json/json.hpp @@ -0,0 +1,25526 @@ +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + +/****************************************************************************\ + * Note on documentation: The source files contain links to the online * + * documentation of the public API at https://json.nlohmann.me. This URL * + * contains the most recent documentation and should also be applicable to * + * previous versions; documentation for deprecated functions is not * + * removed, but marked deprecated. See "Generate documentation" section in * + * file docs/README.md. * +\****************************************************************************/ + +#ifndef INCLUDE_NLOHMANN_JSON_HPP_ +#define INCLUDE_NLOHMANN_JSON_HPP_ + +#include // all_of, find, for_each +#include // nullptr_t, ptrdiff_t, size_t +#include // hash, less +#include // initializer_list +#ifndef JSON_NO_IO + #include // istream, ostream +#endif // JSON_NO_IO +#include // random_access_iterator_tag +#include // unique_ptr +#include // string, stoi, to_string +#include // declval, forward, move, pair, swap +#include // vector + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +// This file contains all macro definitions affecting or depending on the ABI + +#ifndef JSON_SKIP_LIBRARY_VERSION_CHECK + #if defined(NLOHMANN_JSON_VERSION_MAJOR) && defined(NLOHMANN_JSON_VERSION_MINOR) && defined(NLOHMANN_JSON_VERSION_PATCH) + #if NLOHMANN_JSON_VERSION_MAJOR != 3 || NLOHMANN_JSON_VERSION_MINOR != 12 || NLOHMANN_JSON_VERSION_PATCH != 0 + #warning "Already included a different version of the library!" + #endif + #endif +#endif + +#define NLOHMANN_JSON_VERSION_MAJOR 3 // NOLINT(modernize-macro-to-enum) +#define NLOHMANN_JSON_VERSION_MINOR 12 // NOLINT(modernize-macro-to-enum) +#define NLOHMANN_JSON_VERSION_PATCH 0 // NOLINT(modernize-macro-to-enum) + +#ifndef JSON_DIAGNOSTICS + #define JSON_DIAGNOSTICS 0 +#endif + +#ifndef JSON_DIAGNOSTIC_POSITIONS + #define JSON_DIAGNOSTIC_POSITIONS 0 +#endif + +#ifndef JSON_USE_LEGACY_DISCARDED_VALUE_COMPARISON + #define JSON_USE_LEGACY_DISCARDED_VALUE_COMPARISON 0 +#endif + +#if JSON_DIAGNOSTICS + #define NLOHMANN_JSON_ABI_TAG_DIAGNOSTICS _diag +#else + #define NLOHMANN_JSON_ABI_TAG_DIAGNOSTICS +#endif + +#if JSON_DIAGNOSTIC_POSITIONS + #define NLOHMANN_JSON_ABI_TAG_DIAGNOSTIC_POSITIONS _dp +#else + #define NLOHMANN_JSON_ABI_TAG_DIAGNOSTIC_POSITIONS +#endif + +#if JSON_USE_LEGACY_DISCARDED_VALUE_COMPARISON + #define NLOHMANN_JSON_ABI_TAG_LEGACY_DISCARDED_VALUE_COMPARISON _ldvcmp +#else + #define NLOHMANN_JSON_ABI_TAG_LEGACY_DISCARDED_VALUE_COMPARISON +#endif + +#ifndef NLOHMANN_JSON_NAMESPACE_NO_VERSION + #define NLOHMANN_JSON_NAMESPACE_NO_VERSION 0 +#endif + +// Construct the namespace ABI tags component +#define NLOHMANN_JSON_ABI_TAGS_CONCAT_EX(a, b, c) json_abi ## a ## b ## c +#define NLOHMANN_JSON_ABI_TAGS_CONCAT(a, b, c) \ + NLOHMANN_JSON_ABI_TAGS_CONCAT_EX(a, b, c) + +#define NLOHMANN_JSON_ABI_TAGS \ + NLOHMANN_JSON_ABI_TAGS_CONCAT( \ + NLOHMANN_JSON_ABI_TAG_DIAGNOSTICS, \ + NLOHMANN_JSON_ABI_TAG_LEGACY_DISCARDED_VALUE_COMPARISON, \ + NLOHMANN_JSON_ABI_TAG_DIAGNOSTIC_POSITIONS) + +// Construct the namespace version component +#define NLOHMANN_JSON_NAMESPACE_VERSION_CONCAT_EX(major, minor, patch) \ + _v ## major ## _ ## minor ## _ ## patch +#define NLOHMANN_JSON_NAMESPACE_VERSION_CONCAT(major, minor, patch) \ + NLOHMANN_JSON_NAMESPACE_VERSION_CONCAT_EX(major, minor, patch) + +#if NLOHMANN_JSON_NAMESPACE_NO_VERSION +#define NLOHMANN_JSON_NAMESPACE_VERSION +#else +#define NLOHMANN_JSON_NAMESPACE_VERSION \ + NLOHMANN_JSON_NAMESPACE_VERSION_CONCAT(NLOHMANN_JSON_VERSION_MAJOR, \ + NLOHMANN_JSON_VERSION_MINOR, \ + NLOHMANN_JSON_VERSION_PATCH) +#endif + +// Combine namespace components +#define NLOHMANN_JSON_NAMESPACE_CONCAT_EX(a, b) a ## b +#define NLOHMANN_JSON_NAMESPACE_CONCAT(a, b) \ + NLOHMANN_JSON_NAMESPACE_CONCAT_EX(a, b) + +#ifndef NLOHMANN_JSON_NAMESPACE +#define NLOHMANN_JSON_NAMESPACE \ + nlohmann::NLOHMANN_JSON_NAMESPACE_CONCAT( \ + NLOHMANN_JSON_ABI_TAGS, \ + NLOHMANN_JSON_NAMESPACE_VERSION) +#endif + +#ifndef NLOHMANN_JSON_NAMESPACE_BEGIN +#define NLOHMANN_JSON_NAMESPACE_BEGIN \ + namespace nlohmann \ + { \ + inline namespace NLOHMANN_JSON_NAMESPACE_CONCAT( \ + NLOHMANN_JSON_ABI_TAGS, \ + NLOHMANN_JSON_NAMESPACE_VERSION) \ + { +#endif + +#ifndef NLOHMANN_JSON_NAMESPACE_END +#define NLOHMANN_JSON_NAMESPACE_END \ + } /* namespace (inline namespace) NOLINT(readability/namespace) */ \ + } // namespace nlohmann +#endif + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include // transform +#include // array +#include // forward_list +#include // inserter, front_inserter, end +#include // map +#ifdef JSON_HAS_CPP_17 + #include // optional +#endif +#include // string +#include // tuple, make_tuple +#include // is_arithmetic, is_same, is_enum, underlying_type, is_convertible +#include // unordered_map +#include // pair, declval +#include // valarray + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include // nullptr_t +#include // exception +#if JSON_DIAGNOSTICS + #include // accumulate +#endif +#include // runtime_error +#include // to_string +#include // vector + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include // array +#include // size_t +#include // uint8_t +#include // string + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include // declval, pair +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +// #include + + +NLOHMANN_JSON_NAMESPACE_BEGIN +namespace detail +{ + +template struct make_void +{ + using type = void; +}; +template using void_t = typename make_void::type; + +} // namespace detail +NLOHMANN_JSON_NAMESPACE_END + + +NLOHMANN_JSON_NAMESPACE_BEGIN +namespace detail +{ + +// https://en.cppreference.com/w/cpp/experimental/is_detected +struct nonesuch +{ + nonesuch() = delete; + ~nonesuch() = delete; + nonesuch(nonesuch const&) = delete; + nonesuch(nonesuch const&&) = delete; + void operator=(nonesuch const&) = delete; + void operator=(nonesuch&&) = delete; +}; + +template class Op, + class... Args> +struct detector +{ + using value_t = std::false_type; + using type = Default; +}; + +template class Op, class... Args> +struct detector>, Op, Args...> +{ + using value_t = std::true_type; + using type = Op; +}; + +template class Op, class... Args> +using is_detected = typename detector::value_t; + +template class Op, class... Args> +struct is_detected_lazy : is_detected { }; + +template class Op, class... Args> +using detected_t = typename detector::type; + +template class Op, class... Args> +using detected_or = detector; + +template class Op, class... Args> +using detected_or_t = typename detected_or::type; + +template class Op, class... Args> +using is_detected_exact = std::is_same>; + +template class Op, class... Args> +using is_detected_convertible = + std::is_convertible, To>; + +} // namespace detail +NLOHMANN_JSON_NAMESPACE_END + +// #include + + +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-FileCopyrightText: 2016 - 2021 Evan Nemerson +// SPDX-License-Identifier: MIT + +/* Hedley - https://nemequ.github.io/hedley + * Created by Evan Nemerson + */ + +#if !defined(JSON_HEDLEY_VERSION) || (JSON_HEDLEY_VERSION < 15) +#if defined(JSON_HEDLEY_VERSION) + #undef JSON_HEDLEY_VERSION +#endif +#define JSON_HEDLEY_VERSION 15 + +#if defined(JSON_HEDLEY_STRINGIFY_EX) + #undef JSON_HEDLEY_STRINGIFY_EX +#endif +#define JSON_HEDLEY_STRINGIFY_EX(x) #x + +#if defined(JSON_HEDLEY_STRINGIFY) + #undef JSON_HEDLEY_STRINGIFY +#endif +#define JSON_HEDLEY_STRINGIFY(x) JSON_HEDLEY_STRINGIFY_EX(x) + +#if defined(JSON_HEDLEY_CONCAT_EX) + #undef JSON_HEDLEY_CONCAT_EX +#endif +#define JSON_HEDLEY_CONCAT_EX(a,b) a##b + +#if defined(JSON_HEDLEY_CONCAT) + #undef JSON_HEDLEY_CONCAT +#endif +#define JSON_HEDLEY_CONCAT(a,b) JSON_HEDLEY_CONCAT_EX(a,b) + +#if defined(JSON_HEDLEY_CONCAT3_EX) + #undef JSON_HEDLEY_CONCAT3_EX +#endif +#define JSON_HEDLEY_CONCAT3_EX(a,b,c) a##b##c + +#if defined(JSON_HEDLEY_CONCAT3) + #undef JSON_HEDLEY_CONCAT3 +#endif +#define JSON_HEDLEY_CONCAT3(a,b,c) JSON_HEDLEY_CONCAT3_EX(a,b,c) + +#if defined(JSON_HEDLEY_VERSION_ENCODE) + #undef JSON_HEDLEY_VERSION_ENCODE +#endif +#define JSON_HEDLEY_VERSION_ENCODE(major,minor,revision) (((major) * 1000000) + ((minor) * 1000) + (revision)) + +#if defined(JSON_HEDLEY_VERSION_DECODE_MAJOR) + #undef JSON_HEDLEY_VERSION_DECODE_MAJOR +#endif +#define JSON_HEDLEY_VERSION_DECODE_MAJOR(version) ((version) / 1000000) + +#if defined(JSON_HEDLEY_VERSION_DECODE_MINOR) + #undef JSON_HEDLEY_VERSION_DECODE_MINOR +#endif +#define JSON_HEDLEY_VERSION_DECODE_MINOR(version) (((version) % 1000000) / 1000) + +#if defined(JSON_HEDLEY_VERSION_DECODE_REVISION) + #undef JSON_HEDLEY_VERSION_DECODE_REVISION +#endif +#define JSON_HEDLEY_VERSION_DECODE_REVISION(version) ((version) % 1000) + +#if defined(JSON_HEDLEY_GNUC_VERSION) + #undef JSON_HEDLEY_GNUC_VERSION +#endif +#if defined(__GNUC__) && defined(__GNUC_PATCHLEVEL__) + #define JSON_HEDLEY_GNUC_VERSION JSON_HEDLEY_VERSION_ENCODE(__GNUC__, __GNUC_MINOR__, __GNUC_PATCHLEVEL__) +#elif defined(__GNUC__) + #define JSON_HEDLEY_GNUC_VERSION JSON_HEDLEY_VERSION_ENCODE(__GNUC__, __GNUC_MINOR__, 0) +#endif + +#if defined(JSON_HEDLEY_GNUC_VERSION_CHECK) + #undef JSON_HEDLEY_GNUC_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_GNUC_VERSION) + #define JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_GNUC_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_MSVC_VERSION) + #undef JSON_HEDLEY_MSVC_VERSION +#endif +#if defined(_MSC_FULL_VER) && (_MSC_FULL_VER >= 140000000) && !defined(__ICL) + #define JSON_HEDLEY_MSVC_VERSION JSON_HEDLEY_VERSION_ENCODE(_MSC_FULL_VER / 10000000, (_MSC_FULL_VER % 10000000) / 100000, (_MSC_FULL_VER % 100000) / 100) +#elif defined(_MSC_FULL_VER) && !defined(__ICL) + #define JSON_HEDLEY_MSVC_VERSION JSON_HEDLEY_VERSION_ENCODE(_MSC_FULL_VER / 1000000, (_MSC_FULL_VER % 1000000) / 10000, (_MSC_FULL_VER % 10000) / 10) +#elif defined(_MSC_VER) && !defined(__ICL) + #define JSON_HEDLEY_MSVC_VERSION JSON_HEDLEY_VERSION_ENCODE(_MSC_VER / 100, _MSC_VER % 100, 0) +#endif + +#if defined(JSON_HEDLEY_MSVC_VERSION_CHECK) + #undef JSON_HEDLEY_MSVC_VERSION_CHECK +#endif +#if !defined(JSON_HEDLEY_MSVC_VERSION) + #define JSON_HEDLEY_MSVC_VERSION_CHECK(major,minor,patch) (0) +#elif defined(_MSC_VER) && (_MSC_VER >= 1400) + #define JSON_HEDLEY_MSVC_VERSION_CHECK(major,minor,patch) (_MSC_FULL_VER >= ((major * 10000000) + (minor * 100000) + (patch))) +#elif defined(_MSC_VER) && (_MSC_VER >= 1200) + #define JSON_HEDLEY_MSVC_VERSION_CHECK(major,minor,patch) (_MSC_FULL_VER >= ((major * 1000000) + (minor * 10000) + (patch))) +#else + #define JSON_HEDLEY_MSVC_VERSION_CHECK(major,minor,patch) (_MSC_VER >= ((major * 100) + (minor))) +#endif + +#if defined(JSON_HEDLEY_INTEL_VERSION) + #undef JSON_HEDLEY_INTEL_VERSION +#endif +#if defined(__INTEL_COMPILER) && defined(__INTEL_COMPILER_UPDATE) && !defined(__ICL) + #define JSON_HEDLEY_INTEL_VERSION JSON_HEDLEY_VERSION_ENCODE(__INTEL_COMPILER / 100, __INTEL_COMPILER % 100, __INTEL_COMPILER_UPDATE) +#elif defined(__INTEL_COMPILER) && !defined(__ICL) + #define JSON_HEDLEY_INTEL_VERSION JSON_HEDLEY_VERSION_ENCODE(__INTEL_COMPILER / 100, __INTEL_COMPILER % 100, 0) +#endif + +#if defined(JSON_HEDLEY_INTEL_VERSION_CHECK) + #undef JSON_HEDLEY_INTEL_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_INTEL_VERSION) + #define JSON_HEDLEY_INTEL_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_INTEL_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_INTEL_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_INTEL_CL_VERSION) + #undef JSON_HEDLEY_INTEL_CL_VERSION +#endif +#if defined(__INTEL_COMPILER) && defined(__INTEL_COMPILER_UPDATE) && defined(__ICL) + #define JSON_HEDLEY_INTEL_CL_VERSION JSON_HEDLEY_VERSION_ENCODE(__INTEL_COMPILER, __INTEL_COMPILER_UPDATE, 0) +#endif + +#if defined(JSON_HEDLEY_INTEL_CL_VERSION_CHECK) + #undef JSON_HEDLEY_INTEL_CL_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_INTEL_CL_VERSION) + #define JSON_HEDLEY_INTEL_CL_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_INTEL_CL_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_INTEL_CL_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_PGI_VERSION) + #undef JSON_HEDLEY_PGI_VERSION +#endif +#if defined(__PGI) && defined(__PGIC__) && defined(__PGIC_MINOR__) && defined(__PGIC_PATCHLEVEL__) + #define JSON_HEDLEY_PGI_VERSION JSON_HEDLEY_VERSION_ENCODE(__PGIC__, __PGIC_MINOR__, __PGIC_PATCHLEVEL__) +#endif + +#if defined(JSON_HEDLEY_PGI_VERSION_CHECK) + #undef JSON_HEDLEY_PGI_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_PGI_VERSION) + #define JSON_HEDLEY_PGI_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_PGI_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_PGI_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_SUNPRO_VERSION) + #undef JSON_HEDLEY_SUNPRO_VERSION +#endif +#if defined(__SUNPRO_C) && (__SUNPRO_C > 0x1000) + #define JSON_HEDLEY_SUNPRO_VERSION JSON_HEDLEY_VERSION_ENCODE((((__SUNPRO_C >> 16) & 0xf) * 10) + ((__SUNPRO_C >> 12) & 0xf), (((__SUNPRO_C >> 8) & 0xf) * 10) + ((__SUNPRO_C >> 4) & 0xf), (__SUNPRO_C & 0xf) * 10) +#elif defined(__SUNPRO_C) + #define JSON_HEDLEY_SUNPRO_VERSION JSON_HEDLEY_VERSION_ENCODE((__SUNPRO_C >> 8) & 0xf, (__SUNPRO_C >> 4) & 0xf, (__SUNPRO_C) & 0xf) +#elif defined(__SUNPRO_CC) && (__SUNPRO_CC > 0x1000) + #define JSON_HEDLEY_SUNPRO_VERSION JSON_HEDLEY_VERSION_ENCODE((((__SUNPRO_CC >> 16) & 0xf) * 10) + ((__SUNPRO_CC >> 12) & 0xf), (((__SUNPRO_CC >> 8) & 0xf) * 10) + ((__SUNPRO_CC >> 4) & 0xf), (__SUNPRO_CC & 0xf) * 10) +#elif defined(__SUNPRO_CC) + #define JSON_HEDLEY_SUNPRO_VERSION JSON_HEDLEY_VERSION_ENCODE((__SUNPRO_CC >> 8) & 0xf, (__SUNPRO_CC >> 4) & 0xf, (__SUNPRO_CC) & 0xf) +#endif + +#if defined(JSON_HEDLEY_SUNPRO_VERSION_CHECK) + #undef JSON_HEDLEY_SUNPRO_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_SUNPRO_VERSION) + #define JSON_HEDLEY_SUNPRO_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_SUNPRO_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_SUNPRO_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_EMSCRIPTEN_VERSION) + #undef JSON_HEDLEY_EMSCRIPTEN_VERSION +#endif +#if defined(__EMSCRIPTEN__) + #define JSON_HEDLEY_EMSCRIPTEN_VERSION JSON_HEDLEY_VERSION_ENCODE(__EMSCRIPTEN_major__, __EMSCRIPTEN_minor__, __EMSCRIPTEN_tiny__) +#endif + +#if defined(JSON_HEDLEY_EMSCRIPTEN_VERSION_CHECK) + #undef JSON_HEDLEY_EMSCRIPTEN_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_EMSCRIPTEN_VERSION) + #define JSON_HEDLEY_EMSCRIPTEN_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_EMSCRIPTEN_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_EMSCRIPTEN_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_ARM_VERSION) + #undef JSON_HEDLEY_ARM_VERSION +#endif +#if defined(__CC_ARM) && defined(__ARMCOMPILER_VERSION) + #define JSON_HEDLEY_ARM_VERSION JSON_HEDLEY_VERSION_ENCODE(__ARMCOMPILER_VERSION / 1000000, (__ARMCOMPILER_VERSION % 1000000) / 10000, (__ARMCOMPILER_VERSION % 10000) / 100) +#elif defined(__CC_ARM) && defined(__ARMCC_VERSION) + #define JSON_HEDLEY_ARM_VERSION JSON_HEDLEY_VERSION_ENCODE(__ARMCC_VERSION / 1000000, (__ARMCC_VERSION % 1000000) / 10000, (__ARMCC_VERSION % 10000) / 100) +#endif + +#if defined(JSON_HEDLEY_ARM_VERSION_CHECK) + #undef JSON_HEDLEY_ARM_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_ARM_VERSION) + #define JSON_HEDLEY_ARM_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_ARM_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_ARM_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_IBM_VERSION) + #undef JSON_HEDLEY_IBM_VERSION +#endif +#if defined(__ibmxl__) + #define JSON_HEDLEY_IBM_VERSION JSON_HEDLEY_VERSION_ENCODE(__ibmxl_version__, __ibmxl_release__, __ibmxl_modification__) +#elif defined(__xlC__) && defined(__xlC_ver__) + #define JSON_HEDLEY_IBM_VERSION JSON_HEDLEY_VERSION_ENCODE(__xlC__ >> 8, __xlC__ & 0xff, (__xlC_ver__ >> 8) & 0xff) +#elif defined(__xlC__) + #define JSON_HEDLEY_IBM_VERSION JSON_HEDLEY_VERSION_ENCODE(__xlC__ >> 8, __xlC__ & 0xff, 0) +#endif + +#if defined(JSON_HEDLEY_IBM_VERSION_CHECK) + #undef JSON_HEDLEY_IBM_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_IBM_VERSION) + #define JSON_HEDLEY_IBM_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_IBM_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_IBM_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TI_VERSION) + #undef JSON_HEDLEY_TI_VERSION +#endif +#if \ + defined(__TI_COMPILER_VERSION__) && \ + ( \ + defined(__TMS470__) || defined(__TI_ARM__) || \ + defined(__MSP430__) || \ + defined(__TMS320C2000__) \ + ) +#if (__TI_COMPILER_VERSION__ >= 16000000) + #define JSON_HEDLEY_TI_VERSION JSON_HEDLEY_VERSION_ENCODE(__TI_COMPILER_VERSION__ / 1000000, (__TI_COMPILER_VERSION__ % 1000000) / 1000, (__TI_COMPILER_VERSION__ % 1000)) +#endif +#endif + +#if defined(JSON_HEDLEY_TI_VERSION_CHECK) + #undef JSON_HEDLEY_TI_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TI_VERSION) + #define JSON_HEDLEY_TI_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TI_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TI_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TI_CL2000_VERSION) + #undef JSON_HEDLEY_TI_CL2000_VERSION +#endif +#if defined(__TI_COMPILER_VERSION__) && defined(__TMS320C2000__) + #define JSON_HEDLEY_TI_CL2000_VERSION JSON_HEDLEY_VERSION_ENCODE(__TI_COMPILER_VERSION__ / 1000000, (__TI_COMPILER_VERSION__ % 1000000) / 1000, (__TI_COMPILER_VERSION__ % 1000)) +#endif + +#if defined(JSON_HEDLEY_TI_CL2000_VERSION_CHECK) + #undef JSON_HEDLEY_TI_CL2000_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TI_CL2000_VERSION) + #define JSON_HEDLEY_TI_CL2000_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TI_CL2000_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TI_CL2000_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TI_CL430_VERSION) + #undef JSON_HEDLEY_TI_CL430_VERSION +#endif +#if defined(__TI_COMPILER_VERSION__) && defined(__MSP430__) + #define JSON_HEDLEY_TI_CL430_VERSION JSON_HEDLEY_VERSION_ENCODE(__TI_COMPILER_VERSION__ / 1000000, (__TI_COMPILER_VERSION__ % 1000000) / 1000, (__TI_COMPILER_VERSION__ % 1000)) +#endif + +#if defined(JSON_HEDLEY_TI_CL430_VERSION_CHECK) + #undef JSON_HEDLEY_TI_CL430_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TI_CL430_VERSION) + #define JSON_HEDLEY_TI_CL430_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TI_CL430_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TI_CL430_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TI_ARMCL_VERSION) + #undef JSON_HEDLEY_TI_ARMCL_VERSION +#endif +#if defined(__TI_COMPILER_VERSION__) && (defined(__TMS470__) || defined(__TI_ARM__)) + #define JSON_HEDLEY_TI_ARMCL_VERSION JSON_HEDLEY_VERSION_ENCODE(__TI_COMPILER_VERSION__ / 1000000, (__TI_COMPILER_VERSION__ % 1000000) / 1000, (__TI_COMPILER_VERSION__ % 1000)) +#endif + +#if defined(JSON_HEDLEY_TI_ARMCL_VERSION_CHECK) + #undef JSON_HEDLEY_TI_ARMCL_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TI_ARMCL_VERSION) + #define JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TI_ARMCL_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TI_CL6X_VERSION) + #undef JSON_HEDLEY_TI_CL6X_VERSION +#endif +#if defined(__TI_COMPILER_VERSION__) && defined(__TMS320C6X__) + #define JSON_HEDLEY_TI_CL6X_VERSION JSON_HEDLEY_VERSION_ENCODE(__TI_COMPILER_VERSION__ / 1000000, (__TI_COMPILER_VERSION__ % 1000000) / 1000, (__TI_COMPILER_VERSION__ % 1000)) +#endif + +#if defined(JSON_HEDLEY_TI_CL6X_VERSION_CHECK) + #undef JSON_HEDLEY_TI_CL6X_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TI_CL6X_VERSION) + #define JSON_HEDLEY_TI_CL6X_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TI_CL6X_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TI_CL6X_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TI_CL7X_VERSION) + #undef JSON_HEDLEY_TI_CL7X_VERSION +#endif +#if defined(__TI_COMPILER_VERSION__) && defined(__C7000__) + #define JSON_HEDLEY_TI_CL7X_VERSION JSON_HEDLEY_VERSION_ENCODE(__TI_COMPILER_VERSION__ / 1000000, (__TI_COMPILER_VERSION__ % 1000000) / 1000, (__TI_COMPILER_VERSION__ % 1000)) +#endif + +#if defined(JSON_HEDLEY_TI_CL7X_VERSION_CHECK) + #undef JSON_HEDLEY_TI_CL7X_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TI_CL7X_VERSION) + #define JSON_HEDLEY_TI_CL7X_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TI_CL7X_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TI_CL7X_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TI_CLPRU_VERSION) + #undef JSON_HEDLEY_TI_CLPRU_VERSION +#endif +#if defined(__TI_COMPILER_VERSION__) && defined(__PRU__) + #define JSON_HEDLEY_TI_CLPRU_VERSION JSON_HEDLEY_VERSION_ENCODE(__TI_COMPILER_VERSION__ / 1000000, (__TI_COMPILER_VERSION__ % 1000000) / 1000, (__TI_COMPILER_VERSION__ % 1000)) +#endif + +#if defined(JSON_HEDLEY_TI_CLPRU_VERSION_CHECK) + #undef JSON_HEDLEY_TI_CLPRU_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TI_CLPRU_VERSION) + #define JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TI_CLPRU_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_CRAY_VERSION) + #undef JSON_HEDLEY_CRAY_VERSION +#endif +#if defined(_CRAYC) + #if defined(_RELEASE_PATCHLEVEL) + #define JSON_HEDLEY_CRAY_VERSION JSON_HEDLEY_VERSION_ENCODE(_RELEASE_MAJOR, _RELEASE_MINOR, _RELEASE_PATCHLEVEL) + #else + #define JSON_HEDLEY_CRAY_VERSION JSON_HEDLEY_VERSION_ENCODE(_RELEASE_MAJOR, _RELEASE_MINOR, 0) + #endif +#endif + +#if defined(JSON_HEDLEY_CRAY_VERSION_CHECK) + #undef JSON_HEDLEY_CRAY_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_CRAY_VERSION) + #define JSON_HEDLEY_CRAY_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_CRAY_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_CRAY_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_IAR_VERSION) + #undef JSON_HEDLEY_IAR_VERSION +#endif +#if defined(__IAR_SYSTEMS_ICC__) + #if __VER__ > 1000 + #define JSON_HEDLEY_IAR_VERSION JSON_HEDLEY_VERSION_ENCODE((__VER__ / 1000000), ((__VER__ / 1000) % 1000), (__VER__ % 1000)) + #else + #define JSON_HEDLEY_IAR_VERSION JSON_HEDLEY_VERSION_ENCODE(__VER__ / 100, __VER__ % 100, 0) + #endif +#endif + +#if defined(JSON_HEDLEY_IAR_VERSION_CHECK) + #undef JSON_HEDLEY_IAR_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_IAR_VERSION) + #define JSON_HEDLEY_IAR_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_IAR_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_IAR_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_TINYC_VERSION) + #undef JSON_HEDLEY_TINYC_VERSION +#endif +#if defined(__TINYC__) + #define JSON_HEDLEY_TINYC_VERSION JSON_HEDLEY_VERSION_ENCODE(__TINYC__ / 1000, (__TINYC__ / 100) % 10, __TINYC__ % 100) +#endif + +#if defined(JSON_HEDLEY_TINYC_VERSION_CHECK) + #undef JSON_HEDLEY_TINYC_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_TINYC_VERSION) + #define JSON_HEDLEY_TINYC_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_TINYC_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_TINYC_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_DMC_VERSION) + #undef JSON_HEDLEY_DMC_VERSION +#endif +#if defined(__DMC__) + #define JSON_HEDLEY_DMC_VERSION JSON_HEDLEY_VERSION_ENCODE(__DMC__ >> 8, (__DMC__ >> 4) & 0xf, __DMC__ & 0xf) +#endif + +#if defined(JSON_HEDLEY_DMC_VERSION_CHECK) + #undef JSON_HEDLEY_DMC_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_DMC_VERSION) + #define JSON_HEDLEY_DMC_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_DMC_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_DMC_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_COMPCERT_VERSION) + #undef JSON_HEDLEY_COMPCERT_VERSION +#endif +#if defined(__COMPCERT_VERSION__) + #define JSON_HEDLEY_COMPCERT_VERSION JSON_HEDLEY_VERSION_ENCODE(__COMPCERT_VERSION__ / 10000, (__COMPCERT_VERSION__ / 100) % 100, __COMPCERT_VERSION__ % 100) +#endif + +#if defined(JSON_HEDLEY_COMPCERT_VERSION_CHECK) + #undef JSON_HEDLEY_COMPCERT_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_COMPCERT_VERSION) + #define JSON_HEDLEY_COMPCERT_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_COMPCERT_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_COMPCERT_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_PELLES_VERSION) + #undef JSON_HEDLEY_PELLES_VERSION +#endif +#if defined(__POCC__) + #define JSON_HEDLEY_PELLES_VERSION JSON_HEDLEY_VERSION_ENCODE(__POCC__ / 100, __POCC__ % 100, 0) +#endif + +#if defined(JSON_HEDLEY_PELLES_VERSION_CHECK) + #undef JSON_HEDLEY_PELLES_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_PELLES_VERSION) + #define JSON_HEDLEY_PELLES_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_PELLES_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_PELLES_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_MCST_LCC_VERSION) + #undef JSON_HEDLEY_MCST_LCC_VERSION +#endif +#if defined(__LCC__) && defined(__LCC_MINOR__) + #define JSON_HEDLEY_MCST_LCC_VERSION JSON_HEDLEY_VERSION_ENCODE(__LCC__ / 100, __LCC__ % 100, __LCC_MINOR__) +#endif + +#if defined(JSON_HEDLEY_MCST_LCC_VERSION_CHECK) + #undef JSON_HEDLEY_MCST_LCC_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_MCST_LCC_VERSION) + #define JSON_HEDLEY_MCST_LCC_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_MCST_LCC_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_MCST_LCC_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_GCC_VERSION) + #undef JSON_HEDLEY_GCC_VERSION +#endif +#if \ + defined(JSON_HEDLEY_GNUC_VERSION) && \ + !defined(__clang__) && \ + !defined(JSON_HEDLEY_INTEL_VERSION) && \ + !defined(JSON_HEDLEY_PGI_VERSION) && \ + !defined(JSON_HEDLEY_ARM_VERSION) && \ + !defined(JSON_HEDLEY_CRAY_VERSION) && \ + !defined(JSON_HEDLEY_TI_VERSION) && \ + !defined(JSON_HEDLEY_TI_ARMCL_VERSION) && \ + !defined(JSON_HEDLEY_TI_CL430_VERSION) && \ + !defined(JSON_HEDLEY_TI_CL2000_VERSION) && \ + !defined(JSON_HEDLEY_TI_CL6X_VERSION) && \ + !defined(JSON_HEDLEY_TI_CL7X_VERSION) && \ + !defined(JSON_HEDLEY_TI_CLPRU_VERSION) && \ + !defined(__COMPCERT__) && \ + !defined(JSON_HEDLEY_MCST_LCC_VERSION) + #define JSON_HEDLEY_GCC_VERSION JSON_HEDLEY_GNUC_VERSION +#endif + +#if defined(JSON_HEDLEY_GCC_VERSION_CHECK) + #undef JSON_HEDLEY_GCC_VERSION_CHECK +#endif +#if defined(JSON_HEDLEY_GCC_VERSION) + #define JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) (JSON_HEDLEY_GCC_VERSION >= JSON_HEDLEY_VERSION_ENCODE(major, minor, patch)) +#else + #define JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) (0) +#endif + +#if defined(JSON_HEDLEY_HAS_ATTRIBUTE) + #undef JSON_HEDLEY_HAS_ATTRIBUTE +#endif +#if \ + defined(__has_attribute) && \ + ( \ + (!defined(JSON_HEDLEY_IAR_VERSION) || JSON_HEDLEY_IAR_VERSION_CHECK(8,5,9)) \ + ) +# define JSON_HEDLEY_HAS_ATTRIBUTE(attribute) __has_attribute(attribute) +#else +# define JSON_HEDLEY_HAS_ATTRIBUTE(attribute) (0) +#endif + +#if defined(JSON_HEDLEY_GNUC_HAS_ATTRIBUTE) + #undef JSON_HEDLEY_GNUC_HAS_ATTRIBUTE +#endif +#if defined(__has_attribute) + #define JSON_HEDLEY_GNUC_HAS_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_HAS_ATTRIBUTE(attribute) +#else + #define JSON_HEDLEY_GNUC_HAS_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_GCC_HAS_ATTRIBUTE) + #undef JSON_HEDLEY_GCC_HAS_ATTRIBUTE +#endif +#if defined(__has_attribute) + #define JSON_HEDLEY_GCC_HAS_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_HAS_ATTRIBUTE(attribute) +#else + #define JSON_HEDLEY_GCC_HAS_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_HAS_CPP_ATTRIBUTE) + #undef JSON_HEDLEY_HAS_CPP_ATTRIBUTE +#endif +#if \ + defined(__has_cpp_attribute) && \ + defined(__cplusplus) && \ + (!defined(JSON_HEDLEY_SUNPRO_VERSION) || JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,15,0)) + #define JSON_HEDLEY_HAS_CPP_ATTRIBUTE(attribute) __has_cpp_attribute(attribute) +#else + #define JSON_HEDLEY_HAS_CPP_ATTRIBUTE(attribute) (0) +#endif + +#if defined(JSON_HEDLEY_HAS_CPP_ATTRIBUTE_NS) + #undef JSON_HEDLEY_HAS_CPP_ATTRIBUTE_NS +#endif +#if !defined(__cplusplus) || !defined(__has_cpp_attribute) + #define JSON_HEDLEY_HAS_CPP_ATTRIBUTE_NS(ns,attribute) (0) +#elif \ + !defined(JSON_HEDLEY_PGI_VERSION) && \ + !defined(JSON_HEDLEY_IAR_VERSION) && \ + (!defined(JSON_HEDLEY_SUNPRO_VERSION) || JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,15,0)) && \ + (!defined(JSON_HEDLEY_MSVC_VERSION) || JSON_HEDLEY_MSVC_VERSION_CHECK(19,20,0)) + #define JSON_HEDLEY_HAS_CPP_ATTRIBUTE_NS(ns,attribute) JSON_HEDLEY_HAS_CPP_ATTRIBUTE(ns::attribute) +#else + #define JSON_HEDLEY_HAS_CPP_ATTRIBUTE_NS(ns,attribute) (0) +#endif + +#if defined(JSON_HEDLEY_GNUC_HAS_CPP_ATTRIBUTE) + #undef JSON_HEDLEY_GNUC_HAS_CPP_ATTRIBUTE +#endif +#if defined(__has_cpp_attribute) && defined(__cplusplus) + #define JSON_HEDLEY_GNUC_HAS_CPP_ATTRIBUTE(attribute,major,minor,patch) __has_cpp_attribute(attribute) +#else + #define JSON_HEDLEY_GNUC_HAS_CPP_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_GCC_HAS_CPP_ATTRIBUTE) + #undef JSON_HEDLEY_GCC_HAS_CPP_ATTRIBUTE +#endif +#if defined(__has_cpp_attribute) && defined(__cplusplus) + #define JSON_HEDLEY_GCC_HAS_CPP_ATTRIBUTE(attribute,major,minor,patch) __has_cpp_attribute(attribute) +#else + #define JSON_HEDLEY_GCC_HAS_CPP_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_HAS_BUILTIN) + #undef JSON_HEDLEY_HAS_BUILTIN +#endif +#if defined(__has_builtin) + #define JSON_HEDLEY_HAS_BUILTIN(builtin) __has_builtin(builtin) +#else + #define JSON_HEDLEY_HAS_BUILTIN(builtin) (0) +#endif + +#if defined(JSON_HEDLEY_GNUC_HAS_BUILTIN) + #undef JSON_HEDLEY_GNUC_HAS_BUILTIN +#endif +#if defined(__has_builtin) + #define JSON_HEDLEY_GNUC_HAS_BUILTIN(builtin,major,minor,patch) __has_builtin(builtin) +#else + #define JSON_HEDLEY_GNUC_HAS_BUILTIN(builtin,major,minor,patch) JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_GCC_HAS_BUILTIN) + #undef JSON_HEDLEY_GCC_HAS_BUILTIN +#endif +#if defined(__has_builtin) + #define JSON_HEDLEY_GCC_HAS_BUILTIN(builtin,major,minor,patch) __has_builtin(builtin) +#else + #define JSON_HEDLEY_GCC_HAS_BUILTIN(builtin,major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_HAS_FEATURE) + #undef JSON_HEDLEY_HAS_FEATURE +#endif +#if defined(__has_feature) + #define JSON_HEDLEY_HAS_FEATURE(feature) __has_feature(feature) +#else + #define JSON_HEDLEY_HAS_FEATURE(feature) (0) +#endif + +#if defined(JSON_HEDLEY_GNUC_HAS_FEATURE) + #undef JSON_HEDLEY_GNUC_HAS_FEATURE +#endif +#if defined(__has_feature) + #define JSON_HEDLEY_GNUC_HAS_FEATURE(feature,major,minor,patch) __has_feature(feature) +#else + #define JSON_HEDLEY_GNUC_HAS_FEATURE(feature,major,minor,patch) JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_GCC_HAS_FEATURE) + #undef JSON_HEDLEY_GCC_HAS_FEATURE +#endif +#if defined(__has_feature) + #define JSON_HEDLEY_GCC_HAS_FEATURE(feature,major,minor,patch) __has_feature(feature) +#else + #define JSON_HEDLEY_GCC_HAS_FEATURE(feature,major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_HAS_EXTENSION) + #undef JSON_HEDLEY_HAS_EXTENSION +#endif +#if defined(__has_extension) + #define JSON_HEDLEY_HAS_EXTENSION(extension) __has_extension(extension) +#else + #define JSON_HEDLEY_HAS_EXTENSION(extension) (0) +#endif + +#if defined(JSON_HEDLEY_GNUC_HAS_EXTENSION) + #undef JSON_HEDLEY_GNUC_HAS_EXTENSION +#endif +#if defined(__has_extension) + #define JSON_HEDLEY_GNUC_HAS_EXTENSION(extension,major,minor,patch) __has_extension(extension) +#else + #define JSON_HEDLEY_GNUC_HAS_EXTENSION(extension,major,minor,patch) JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_GCC_HAS_EXTENSION) + #undef JSON_HEDLEY_GCC_HAS_EXTENSION +#endif +#if defined(__has_extension) + #define JSON_HEDLEY_GCC_HAS_EXTENSION(extension,major,minor,patch) __has_extension(extension) +#else + #define JSON_HEDLEY_GCC_HAS_EXTENSION(extension,major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_HAS_DECLSPEC_ATTRIBUTE) + #undef JSON_HEDLEY_HAS_DECLSPEC_ATTRIBUTE +#endif +#if defined(__has_declspec_attribute) + #define JSON_HEDLEY_HAS_DECLSPEC_ATTRIBUTE(attribute) __has_declspec_attribute(attribute) +#else + #define JSON_HEDLEY_HAS_DECLSPEC_ATTRIBUTE(attribute) (0) +#endif + +#if defined(JSON_HEDLEY_GNUC_HAS_DECLSPEC_ATTRIBUTE) + #undef JSON_HEDLEY_GNUC_HAS_DECLSPEC_ATTRIBUTE +#endif +#if defined(__has_declspec_attribute) + #define JSON_HEDLEY_GNUC_HAS_DECLSPEC_ATTRIBUTE(attribute,major,minor,patch) __has_declspec_attribute(attribute) +#else + #define JSON_HEDLEY_GNUC_HAS_DECLSPEC_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_GCC_HAS_DECLSPEC_ATTRIBUTE) + #undef JSON_HEDLEY_GCC_HAS_DECLSPEC_ATTRIBUTE +#endif +#if defined(__has_declspec_attribute) + #define JSON_HEDLEY_GCC_HAS_DECLSPEC_ATTRIBUTE(attribute,major,minor,patch) __has_declspec_attribute(attribute) +#else + #define JSON_HEDLEY_GCC_HAS_DECLSPEC_ATTRIBUTE(attribute,major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_HAS_WARNING) + #undef JSON_HEDLEY_HAS_WARNING +#endif +#if defined(__has_warning) + #define JSON_HEDLEY_HAS_WARNING(warning) __has_warning(warning) +#else + #define JSON_HEDLEY_HAS_WARNING(warning) (0) +#endif + +#if defined(JSON_HEDLEY_GNUC_HAS_WARNING) + #undef JSON_HEDLEY_GNUC_HAS_WARNING +#endif +#if defined(__has_warning) + #define JSON_HEDLEY_GNUC_HAS_WARNING(warning,major,minor,patch) __has_warning(warning) +#else + #define JSON_HEDLEY_GNUC_HAS_WARNING(warning,major,minor,patch) JSON_HEDLEY_GNUC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_GCC_HAS_WARNING) + #undef JSON_HEDLEY_GCC_HAS_WARNING +#endif +#if defined(__has_warning) + #define JSON_HEDLEY_GCC_HAS_WARNING(warning,major,minor,patch) __has_warning(warning) +#else + #define JSON_HEDLEY_GCC_HAS_WARNING(warning,major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if \ + (defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 199901L)) || \ + defined(__clang__) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,0,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(18,4,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,7,0) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(2,0,1) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,1,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,0,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_CRAY_VERSION_CHECK(5,0,0) || \ + JSON_HEDLEY_TINYC_VERSION_CHECK(0,9,17) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(8,0,0) || \ + (JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) && defined(__C99_PRAGMA_OPERATOR)) + #define JSON_HEDLEY_PRAGMA(value) _Pragma(#value) +#elif JSON_HEDLEY_MSVC_VERSION_CHECK(15,0,0) + #define JSON_HEDLEY_PRAGMA(value) __pragma(value) +#else + #define JSON_HEDLEY_PRAGMA(value) +#endif + +#if defined(JSON_HEDLEY_DIAGNOSTIC_PUSH) + #undef JSON_HEDLEY_DIAGNOSTIC_PUSH +#endif +#if defined(JSON_HEDLEY_DIAGNOSTIC_POP) + #undef JSON_HEDLEY_DIAGNOSTIC_POP +#endif +#if defined(__clang__) + #define JSON_HEDLEY_DIAGNOSTIC_PUSH _Pragma("clang diagnostic push") + #define JSON_HEDLEY_DIAGNOSTIC_POP _Pragma("clang diagnostic pop") +#elif JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_PUSH _Pragma("warning(push)") + #define JSON_HEDLEY_DIAGNOSTIC_POP _Pragma("warning(pop)") +#elif JSON_HEDLEY_GCC_VERSION_CHECK(4,6,0) + #define JSON_HEDLEY_DIAGNOSTIC_PUSH _Pragma("GCC diagnostic push") + #define JSON_HEDLEY_DIAGNOSTIC_POP _Pragma("GCC diagnostic pop") +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(15,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_DIAGNOSTIC_PUSH __pragma(warning(push)) + #define JSON_HEDLEY_DIAGNOSTIC_POP __pragma(warning(pop)) +#elif JSON_HEDLEY_ARM_VERSION_CHECK(5,6,0) + #define JSON_HEDLEY_DIAGNOSTIC_PUSH _Pragma("push") + #define JSON_HEDLEY_DIAGNOSTIC_POP _Pragma("pop") +#elif \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,4,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(8,1,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) + #define JSON_HEDLEY_DIAGNOSTIC_PUSH _Pragma("diag_push") + #define JSON_HEDLEY_DIAGNOSTIC_POP _Pragma("diag_pop") +#elif JSON_HEDLEY_PELLES_VERSION_CHECK(2,90,0) + #define JSON_HEDLEY_DIAGNOSTIC_PUSH _Pragma("warning(push)") + #define JSON_HEDLEY_DIAGNOSTIC_POP _Pragma("warning(pop)") +#else + #define JSON_HEDLEY_DIAGNOSTIC_PUSH + #define JSON_HEDLEY_DIAGNOSTIC_POP +#endif + +/* JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_ is for + HEDLEY INTERNAL USE ONLY. API subject to change without notice. */ +#if defined(JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_) + #undef JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_ +#endif +#if defined(__cplusplus) +# if JSON_HEDLEY_HAS_WARNING("-Wc++98-compat") +# if JSON_HEDLEY_HAS_WARNING("-Wc++17-extensions") +# if JSON_HEDLEY_HAS_WARNING("-Wc++1z-extensions") +# define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_(xpr) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("clang diagnostic ignored \"-Wc++98-compat\"") \ + _Pragma("clang diagnostic ignored \"-Wc++17-extensions\"") \ + _Pragma("clang diagnostic ignored \"-Wc++1z-extensions\"") \ + xpr \ + JSON_HEDLEY_DIAGNOSTIC_POP +# else +# define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_(xpr) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("clang diagnostic ignored \"-Wc++98-compat\"") \ + _Pragma("clang diagnostic ignored \"-Wc++17-extensions\"") \ + xpr \ + JSON_HEDLEY_DIAGNOSTIC_POP +# endif +# else +# define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_(xpr) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("clang diagnostic ignored \"-Wc++98-compat\"") \ + xpr \ + JSON_HEDLEY_DIAGNOSTIC_POP +# endif +# endif +#endif +#if !defined(JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_(x) x +#endif + +#if defined(JSON_HEDLEY_CONST_CAST) + #undef JSON_HEDLEY_CONST_CAST +#endif +#if defined(__cplusplus) +# define JSON_HEDLEY_CONST_CAST(T, expr) (const_cast(expr)) +#elif \ + JSON_HEDLEY_HAS_WARNING("-Wcast-qual") || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,6,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) +# define JSON_HEDLEY_CONST_CAST(T, expr) (__extension__ ({ \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + JSON_HEDLEY_DIAGNOSTIC_DISABLE_CAST_QUAL \ + ((T) (expr)); \ + JSON_HEDLEY_DIAGNOSTIC_POP \ + })) +#else +# define JSON_HEDLEY_CONST_CAST(T, expr) ((T) (expr)) +#endif + +#if defined(JSON_HEDLEY_REINTERPRET_CAST) + #undef JSON_HEDLEY_REINTERPRET_CAST +#endif +#if defined(__cplusplus) + #define JSON_HEDLEY_REINTERPRET_CAST(T, expr) (reinterpret_cast(expr)) +#else + #define JSON_HEDLEY_REINTERPRET_CAST(T, expr) ((T) (expr)) +#endif + +#if defined(JSON_HEDLEY_STATIC_CAST) + #undef JSON_HEDLEY_STATIC_CAST +#endif +#if defined(__cplusplus) + #define JSON_HEDLEY_STATIC_CAST(T, expr) (static_cast(expr)) +#else + #define JSON_HEDLEY_STATIC_CAST(T, expr) ((T) (expr)) +#endif + +#if defined(JSON_HEDLEY_CPP_CAST) + #undef JSON_HEDLEY_CPP_CAST +#endif +#if defined(__cplusplus) +# if JSON_HEDLEY_HAS_WARNING("-Wold-style-cast") +# define JSON_HEDLEY_CPP_CAST(T, expr) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("clang diagnostic ignored \"-Wold-style-cast\"") \ + ((T) (expr)) \ + JSON_HEDLEY_DIAGNOSTIC_POP +# elif JSON_HEDLEY_IAR_VERSION_CHECK(8,3,0) +# define JSON_HEDLEY_CPP_CAST(T, expr) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("diag_suppress=Pe137") \ + JSON_HEDLEY_DIAGNOSTIC_POP +# else +# define JSON_HEDLEY_CPP_CAST(T, expr) ((T) (expr)) +# endif +#else +# define JSON_HEDLEY_CPP_CAST(T, expr) (expr) +#endif + +#if defined(JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED) + #undef JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wdeprecated-declarations") + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("clang diagnostic ignored \"-Wdeprecated-declarations\"") +#elif JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("warning(disable:1478 1786)") +#elif JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED __pragma(warning(disable:1478 1786)) +#elif JSON_HEDLEY_PGI_VERSION_CHECK(20,7,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("diag_suppress 1215,1216,1444,1445") +#elif JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("diag_suppress 1215,1444") +#elif JSON_HEDLEY_GCC_VERSION_CHECK(4,3,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("GCC diagnostic ignored \"-Wdeprecated-declarations\"") +#elif JSON_HEDLEY_MSVC_VERSION_CHECK(15,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED __pragma(warning(disable:4996)) +#elif JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("diag_suppress 1215,1444") +#elif \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("diag_suppress 1291,1718") +#elif JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,13,0) && !defined(__cplusplus) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("error_messages(off,E_DEPRECATED_ATT,E_DEPRECATED_ATT_MESS)") +#elif JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,13,0) && defined(__cplusplus) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("error_messages(off,symdeprecated,symdeprecated2)") +#elif JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("diag_suppress=Pe1444,Pe1215") +#elif JSON_HEDLEY_PELLES_VERSION_CHECK(2,90,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED _Pragma("warn(disable:2241)") +#else + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_DEPRECATED +#endif + +#if defined(JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS) + #undef JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wunknown-pragmas") + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("clang diagnostic ignored \"-Wunknown-pragmas\"") +#elif JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("warning(disable:161)") +#elif JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS __pragma(warning(disable:161)) +#elif JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("diag_suppress 1675") +#elif JSON_HEDLEY_GCC_VERSION_CHECK(4,3,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("GCC diagnostic ignored \"-Wunknown-pragmas\"") +#elif JSON_HEDLEY_MSVC_VERSION_CHECK(15,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS __pragma(warning(disable:4068)) +#elif \ + JSON_HEDLEY_TI_VERSION_CHECK(16,9,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(8,0,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,3,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("diag_suppress 163") +#elif JSON_HEDLEY_TI_CL6X_VERSION_CHECK(8,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("diag_suppress 163") +#elif JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("diag_suppress=Pe161") +#elif JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS _Pragma("diag_suppress 161") +#else + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS +#endif + +#if defined(JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES) + #undef JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wunknown-attributes") + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("clang diagnostic ignored \"-Wunknown-attributes\"") +#elif JSON_HEDLEY_GCC_VERSION_CHECK(4,6,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("GCC diagnostic ignored \"-Wdeprecated-declarations\"") +#elif JSON_HEDLEY_INTEL_VERSION_CHECK(17,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("warning(disable:1292)") +#elif JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES __pragma(warning(disable:1292)) +#elif JSON_HEDLEY_MSVC_VERSION_CHECK(19,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES __pragma(warning(disable:5030)) +#elif JSON_HEDLEY_PGI_VERSION_CHECK(20,7,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("diag_suppress 1097,1098") +#elif JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("diag_suppress 1097") +#elif JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,14,0) && defined(__cplusplus) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("error_messages(off,attrskipunsup)") +#elif \ + JSON_HEDLEY_TI_VERSION_CHECK(18,1,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(8,3,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("diag_suppress 1173") +#elif JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("diag_suppress=Pe1097") +#elif JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES _Pragma("diag_suppress 1097") +#else + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_CPP_ATTRIBUTES +#endif + +#if defined(JSON_HEDLEY_DIAGNOSTIC_DISABLE_CAST_QUAL) + #undef JSON_HEDLEY_DIAGNOSTIC_DISABLE_CAST_QUAL +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wcast-qual") + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CAST_QUAL _Pragma("clang diagnostic ignored \"-Wcast-qual\"") +#elif JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CAST_QUAL _Pragma("warning(disable:2203 2331)") +#elif JSON_HEDLEY_GCC_VERSION_CHECK(3,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CAST_QUAL _Pragma("GCC diagnostic ignored \"-Wcast-qual\"") +#else + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_CAST_QUAL +#endif + +#if defined(JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNUSED_FUNCTION) + #undef JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNUSED_FUNCTION +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wunused-function") + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNUSED_FUNCTION _Pragma("clang diagnostic ignored \"-Wunused-function\"") +#elif JSON_HEDLEY_GCC_VERSION_CHECK(3,4,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNUSED_FUNCTION _Pragma("GCC diagnostic ignored \"-Wunused-function\"") +#elif JSON_HEDLEY_MSVC_VERSION_CHECK(1,0,0) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNUSED_FUNCTION __pragma(warning(disable:4505)) +#elif JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNUSED_FUNCTION _Pragma("diag_suppress 3142") +#else + #define JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNUSED_FUNCTION +#endif + +#if defined(JSON_HEDLEY_DEPRECATED) + #undef JSON_HEDLEY_DEPRECATED +#endif +#if defined(JSON_HEDLEY_DEPRECATED_FOR) + #undef JSON_HEDLEY_DEPRECATED_FOR +#endif +#if \ + JSON_HEDLEY_MSVC_VERSION_CHECK(14,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_DEPRECATED(since) __declspec(deprecated("Since " # since)) + #define JSON_HEDLEY_DEPRECATED_FOR(since, replacement) __declspec(deprecated("Since " #since "; use " #replacement)) +#elif \ + (JSON_HEDLEY_HAS_EXTENSION(attribute_deprecated_with_message) && !defined(JSON_HEDLEY_IAR_VERSION)) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,5,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(5,6,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,13,0) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(18,1,0) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(18,1,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(8,3,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,3,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_DEPRECATED(since) __attribute__((__deprecated__("Since " #since))) + #define JSON_HEDLEY_DEPRECATED_FOR(since, replacement) __attribute__((__deprecated__("Since " #since "; use " #replacement))) +#elif defined(__cplusplus) && (__cplusplus >= 201402L) + #define JSON_HEDLEY_DEPRECATED(since) JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[deprecated("Since " #since)]]) + #define JSON_HEDLEY_DEPRECATED_FOR(since, replacement) JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[deprecated("Since " #since "; use " #replacement)]]) +#elif \ + JSON_HEDLEY_HAS_ATTRIBUTE(deprecated) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,1,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) || \ + JSON_HEDLEY_IAR_VERSION_CHECK(8,10,0) + #define JSON_HEDLEY_DEPRECATED(since) __attribute__((__deprecated__)) + #define JSON_HEDLEY_DEPRECATED_FOR(since, replacement) __attribute__((__deprecated__)) +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(13,10,0) || \ + JSON_HEDLEY_PELLES_VERSION_CHECK(6,50,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_DEPRECATED(since) __declspec(deprecated) + #define JSON_HEDLEY_DEPRECATED_FOR(since, replacement) __declspec(deprecated) +#elif JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) + #define JSON_HEDLEY_DEPRECATED(since) _Pragma("deprecated") + #define JSON_HEDLEY_DEPRECATED_FOR(since, replacement) _Pragma("deprecated") +#else + #define JSON_HEDLEY_DEPRECATED(since) + #define JSON_HEDLEY_DEPRECATED_FOR(since, replacement) +#endif + +#if defined(JSON_HEDLEY_UNAVAILABLE) + #undef JSON_HEDLEY_UNAVAILABLE +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(warning) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,3,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_UNAVAILABLE(available_since) __attribute__((__warning__("Not available until " #available_since))) +#else + #define JSON_HEDLEY_UNAVAILABLE(available_since) +#endif + +#if defined(JSON_HEDLEY_WARN_UNUSED_RESULT) + #undef JSON_HEDLEY_WARN_UNUSED_RESULT +#endif +#if defined(JSON_HEDLEY_WARN_UNUSED_RESULT_MSG) + #undef JSON_HEDLEY_WARN_UNUSED_RESULT_MSG +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(warn_unused_result) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,4,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + (JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,15,0) && defined(__cplusplus)) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_WARN_UNUSED_RESULT __attribute__((__warn_unused_result__)) + #define JSON_HEDLEY_WARN_UNUSED_RESULT_MSG(msg) __attribute__((__warn_unused_result__)) +#elif (JSON_HEDLEY_HAS_CPP_ATTRIBUTE(nodiscard) >= 201907L) + #define JSON_HEDLEY_WARN_UNUSED_RESULT JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[nodiscard]]) + #define JSON_HEDLEY_WARN_UNUSED_RESULT_MSG(msg) JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[nodiscard(msg)]]) +#elif JSON_HEDLEY_HAS_CPP_ATTRIBUTE(nodiscard) + #define JSON_HEDLEY_WARN_UNUSED_RESULT JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[nodiscard]]) + #define JSON_HEDLEY_WARN_UNUSED_RESULT_MSG(msg) JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[nodiscard]]) +#elif defined(_Check_return_) /* SAL */ + #define JSON_HEDLEY_WARN_UNUSED_RESULT _Check_return_ + #define JSON_HEDLEY_WARN_UNUSED_RESULT_MSG(msg) _Check_return_ +#else + #define JSON_HEDLEY_WARN_UNUSED_RESULT + #define JSON_HEDLEY_WARN_UNUSED_RESULT_MSG(msg) +#endif + +#if defined(JSON_HEDLEY_SENTINEL) + #undef JSON_HEDLEY_SENTINEL +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(sentinel) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,0,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(5,4,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_SENTINEL(position) __attribute__((__sentinel__(position))) +#else + #define JSON_HEDLEY_SENTINEL(position) +#endif + +#if defined(JSON_HEDLEY_NO_RETURN) + #undef JSON_HEDLEY_NO_RETURN +#endif +#if JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) + #define JSON_HEDLEY_NO_RETURN __noreturn +#elif \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_NO_RETURN __attribute__((__noreturn__)) +#elif defined(__STDC_VERSION__) && __STDC_VERSION__ >= 201112L + #define JSON_HEDLEY_NO_RETURN _Noreturn +#elif defined(__cplusplus) && (__cplusplus >= 201103L) + #define JSON_HEDLEY_NO_RETURN JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[noreturn]]) +#elif \ + JSON_HEDLEY_HAS_ATTRIBUTE(noreturn) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,2,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,11,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_IAR_VERSION_CHECK(8,10,0) + #define JSON_HEDLEY_NO_RETURN __attribute__((__noreturn__)) +#elif JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,10,0) + #define JSON_HEDLEY_NO_RETURN _Pragma("does_not_return") +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(13,10,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_NO_RETURN __declspec(noreturn) +#elif JSON_HEDLEY_TI_CL6X_VERSION_CHECK(6,0,0) && defined(__cplusplus) + #define JSON_HEDLEY_NO_RETURN _Pragma("FUNC_NEVER_RETURNS;") +#elif JSON_HEDLEY_COMPCERT_VERSION_CHECK(3,2,0) + #define JSON_HEDLEY_NO_RETURN __attribute((noreturn)) +#elif JSON_HEDLEY_PELLES_VERSION_CHECK(9,0,0) + #define JSON_HEDLEY_NO_RETURN __declspec(noreturn) +#else + #define JSON_HEDLEY_NO_RETURN +#endif + +#if defined(JSON_HEDLEY_NO_ESCAPE) + #undef JSON_HEDLEY_NO_ESCAPE +#endif +#if JSON_HEDLEY_HAS_ATTRIBUTE(noescape) + #define JSON_HEDLEY_NO_ESCAPE __attribute__((__noescape__)) +#else + #define JSON_HEDLEY_NO_ESCAPE +#endif + +#if defined(JSON_HEDLEY_UNREACHABLE) + #undef JSON_HEDLEY_UNREACHABLE +#endif +#if defined(JSON_HEDLEY_UNREACHABLE_RETURN) + #undef JSON_HEDLEY_UNREACHABLE_RETURN +#endif +#if defined(JSON_HEDLEY_ASSUME) + #undef JSON_HEDLEY_ASSUME +#endif +#if \ + JSON_HEDLEY_MSVC_VERSION_CHECK(13,10,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_ASSUME(expr) __assume(expr) +#elif JSON_HEDLEY_HAS_BUILTIN(__builtin_assume) + #define JSON_HEDLEY_ASSUME(expr) __builtin_assume(expr) +#elif \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,2,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(4,0,0) + #if defined(__cplusplus) + #define JSON_HEDLEY_ASSUME(expr) std::_nassert(expr) + #else + #define JSON_HEDLEY_ASSUME(expr) _nassert(expr) + #endif +#endif +#if \ + (JSON_HEDLEY_HAS_BUILTIN(__builtin_unreachable) && (!defined(JSON_HEDLEY_ARM_VERSION))) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,5,0) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(18,10,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(13,1,5) || \ + JSON_HEDLEY_CRAY_VERSION_CHECK(10,0,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_UNREACHABLE() __builtin_unreachable() +#elif defined(JSON_HEDLEY_ASSUME) + #define JSON_HEDLEY_UNREACHABLE() JSON_HEDLEY_ASSUME(0) +#endif +#if !defined(JSON_HEDLEY_ASSUME) + #if defined(JSON_HEDLEY_UNREACHABLE) + #define JSON_HEDLEY_ASSUME(expr) JSON_HEDLEY_STATIC_CAST(void, ((expr) ? 1 : (JSON_HEDLEY_UNREACHABLE(), 1))) + #else + #define JSON_HEDLEY_ASSUME(expr) JSON_HEDLEY_STATIC_CAST(void, expr) + #endif +#endif +#if defined(JSON_HEDLEY_UNREACHABLE) + #if \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,2,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(4,0,0) + #define JSON_HEDLEY_UNREACHABLE_RETURN(value) return (JSON_HEDLEY_STATIC_CAST(void, JSON_HEDLEY_ASSUME(0)), (value)) + #else + #define JSON_HEDLEY_UNREACHABLE_RETURN(value) JSON_HEDLEY_UNREACHABLE() + #endif +#else + #define JSON_HEDLEY_UNREACHABLE_RETURN(value) return (value) +#endif +#if !defined(JSON_HEDLEY_UNREACHABLE) + #define JSON_HEDLEY_UNREACHABLE() JSON_HEDLEY_ASSUME(0) +#endif + +JSON_HEDLEY_DIAGNOSTIC_PUSH +#if JSON_HEDLEY_HAS_WARNING("-Wpedantic") + #pragma clang diagnostic ignored "-Wpedantic" +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wc++98-compat-pedantic") && defined(__cplusplus) + #pragma clang diagnostic ignored "-Wc++98-compat-pedantic" +#endif +#if JSON_HEDLEY_GCC_HAS_WARNING("-Wvariadic-macros",4,0,0) + #if defined(__clang__) + #pragma clang diagnostic ignored "-Wvariadic-macros" + #elif defined(JSON_HEDLEY_GCC_VERSION) + #pragma GCC diagnostic ignored "-Wvariadic-macros" + #endif +#endif +#if defined(JSON_HEDLEY_NON_NULL) + #undef JSON_HEDLEY_NON_NULL +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(nonnull) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,3,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) + #define JSON_HEDLEY_NON_NULL(...) __attribute__((__nonnull__(__VA_ARGS__))) +#else + #define JSON_HEDLEY_NON_NULL(...) +#endif +JSON_HEDLEY_DIAGNOSTIC_POP + +#if defined(JSON_HEDLEY_PRINTF_FORMAT) + #undef JSON_HEDLEY_PRINTF_FORMAT +#endif +#if defined(__MINGW32__) && JSON_HEDLEY_GCC_HAS_ATTRIBUTE(format,4,4,0) && !defined(__USE_MINGW_ANSI_STDIO) + #define JSON_HEDLEY_PRINTF_FORMAT(string_idx,first_to_check) __attribute__((__format__(ms_printf, string_idx, first_to_check))) +#elif defined(__MINGW32__) && JSON_HEDLEY_GCC_HAS_ATTRIBUTE(format,4,4,0) && defined(__USE_MINGW_ANSI_STDIO) + #define JSON_HEDLEY_PRINTF_FORMAT(string_idx,first_to_check) __attribute__((__format__(gnu_printf, string_idx, first_to_check))) +#elif \ + JSON_HEDLEY_HAS_ATTRIBUTE(format) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,1,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(5,6,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_PRINTF_FORMAT(string_idx,first_to_check) __attribute__((__format__(__printf__, string_idx, first_to_check))) +#elif JSON_HEDLEY_PELLES_VERSION_CHECK(6,0,0) + #define JSON_HEDLEY_PRINTF_FORMAT(string_idx,first_to_check) __declspec(vaformat(printf,string_idx,first_to_check)) +#else + #define JSON_HEDLEY_PRINTF_FORMAT(string_idx,first_to_check) +#endif + +#if defined(JSON_HEDLEY_CONSTEXPR) + #undef JSON_HEDLEY_CONSTEXPR +#endif +#if defined(__cplusplus) + #if __cplusplus >= 201103L + #define JSON_HEDLEY_CONSTEXPR JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_(constexpr) + #endif +#endif +#if !defined(JSON_HEDLEY_CONSTEXPR) + #define JSON_HEDLEY_CONSTEXPR +#endif + +#if defined(JSON_HEDLEY_PREDICT) + #undef JSON_HEDLEY_PREDICT +#endif +#if defined(JSON_HEDLEY_LIKELY) + #undef JSON_HEDLEY_LIKELY +#endif +#if defined(JSON_HEDLEY_UNLIKELY) + #undef JSON_HEDLEY_UNLIKELY +#endif +#if defined(JSON_HEDLEY_UNPREDICTABLE) + #undef JSON_HEDLEY_UNPREDICTABLE +#endif +#if JSON_HEDLEY_HAS_BUILTIN(__builtin_unpredictable) + #define JSON_HEDLEY_UNPREDICTABLE(expr) __builtin_unpredictable((expr)) +#endif +#if \ + (JSON_HEDLEY_HAS_BUILTIN(__builtin_expect_with_probability) && !defined(JSON_HEDLEY_PGI_VERSION)) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(9,0,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) +# define JSON_HEDLEY_PREDICT(expr, value, probability) __builtin_expect_with_probability( (expr), (value), (probability)) +# define JSON_HEDLEY_PREDICT_TRUE(expr, probability) __builtin_expect_with_probability(!!(expr), 1 , (probability)) +# define JSON_HEDLEY_PREDICT_FALSE(expr, probability) __builtin_expect_with_probability(!!(expr), 0 , (probability)) +# define JSON_HEDLEY_LIKELY(expr) __builtin_expect (!!(expr), 1 ) +# define JSON_HEDLEY_UNLIKELY(expr) __builtin_expect (!!(expr), 0 ) +#elif \ + (JSON_HEDLEY_HAS_BUILTIN(__builtin_expect) && !defined(JSON_HEDLEY_INTEL_CL_VERSION)) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,0,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + (JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,15,0) && defined(__cplusplus)) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,7,0) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(3,1,0) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,1,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(6,1,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_TINYC_VERSION_CHECK(0,9,27) || \ + JSON_HEDLEY_CRAY_VERSION_CHECK(8,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) +# define JSON_HEDLEY_PREDICT(expr, expected, probability) \ + (((probability) >= 0.9) ? __builtin_expect((expr), (expected)) : (JSON_HEDLEY_STATIC_CAST(void, expected), (expr))) +# define JSON_HEDLEY_PREDICT_TRUE(expr, probability) \ + (__extension__ ({ \ + double hedley_probability_ = (probability); \ + ((hedley_probability_ >= 0.9) ? __builtin_expect(!!(expr), 1) : ((hedley_probability_ <= 0.1) ? __builtin_expect(!!(expr), 0) : !!(expr))); \ + })) +# define JSON_HEDLEY_PREDICT_FALSE(expr, probability) \ + (__extension__ ({ \ + double hedley_probability_ = (probability); \ + ((hedley_probability_ >= 0.9) ? __builtin_expect(!!(expr), 0) : ((hedley_probability_ <= 0.1) ? __builtin_expect(!!(expr), 1) : !!(expr))); \ + })) +# define JSON_HEDLEY_LIKELY(expr) __builtin_expect(!!(expr), 1) +# define JSON_HEDLEY_UNLIKELY(expr) __builtin_expect(!!(expr), 0) +#else +# define JSON_HEDLEY_PREDICT(expr, expected, probability) (JSON_HEDLEY_STATIC_CAST(void, expected), (expr)) +# define JSON_HEDLEY_PREDICT_TRUE(expr, probability) (!!(expr)) +# define JSON_HEDLEY_PREDICT_FALSE(expr, probability) (!!(expr)) +# define JSON_HEDLEY_LIKELY(expr) (!!(expr)) +# define JSON_HEDLEY_UNLIKELY(expr) (!!(expr)) +#endif +#if !defined(JSON_HEDLEY_UNPREDICTABLE) + #define JSON_HEDLEY_UNPREDICTABLE(expr) JSON_HEDLEY_PREDICT(expr, 1, 0.5) +#endif + +#if defined(JSON_HEDLEY_MALLOC) + #undef JSON_HEDLEY_MALLOC +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(malloc) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,1,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,11,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(12,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_MALLOC __attribute__((__malloc__)) +#elif JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,10,0) + #define JSON_HEDLEY_MALLOC _Pragma("returns_new_memory") +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(14,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_MALLOC __declspec(restrict) +#else + #define JSON_HEDLEY_MALLOC +#endif + +#if defined(JSON_HEDLEY_PURE) + #undef JSON_HEDLEY_PURE +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(pure) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(2,96,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,11,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) +# define JSON_HEDLEY_PURE __attribute__((__pure__)) +#elif JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,10,0) +# define JSON_HEDLEY_PURE _Pragma("does_not_write_global_data") +#elif defined(__cplusplus) && \ + ( \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(2,0,1) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(4,0,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) \ + ) +# define JSON_HEDLEY_PURE _Pragma("FUNC_IS_PURE;") +#else +# define JSON_HEDLEY_PURE +#endif + +#if defined(JSON_HEDLEY_CONST) + #undef JSON_HEDLEY_CONST +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(const) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(2,5,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,11,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_CONST __attribute__((__const__)) +#elif \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,10,0) + #define JSON_HEDLEY_CONST _Pragma("no_side_effect") +#else + #define JSON_HEDLEY_CONST JSON_HEDLEY_PURE +#endif + +#if defined(JSON_HEDLEY_RESTRICT) + #undef JSON_HEDLEY_RESTRICT +#endif +#if defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 199901L) && !defined(__cplusplus) + #define JSON_HEDLEY_RESTRICT restrict +#elif \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,1,0) || \ + JSON_HEDLEY_MSVC_VERSION_CHECK(14,0,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(17,10,0) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,2,4) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(8,1,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + (JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,14,0) && defined(__cplusplus)) || \ + JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) || \ + defined(__clang__) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_RESTRICT __restrict +#elif JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,3,0) && !defined(__cplusplus) + #define JSON_HEDLEY_RESTRICT _Restrict +#else + #define JSON_HEDLEY_RESTRICT +#endif + +#if defined(JSON_HEDLEY_INLINE) + #undef JSON_HEDLEY_INLINE +#endif +#if \ + (defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 199901L)) || \ + (defined(__cplusplus) && (__cplusplus >= 199711L)) + #define JSON_HEDLEY_INLINE inline +#elif \ + defined(JSON_HEDLEY_GCC_VERSION) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(6,2,0) + #define JSON_HEDLEY_INLINE __inline__ +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(12,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,1,0) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(3,1,0) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,2,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(8,0,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_INLINE __inline +#else + #define JSON_HEDLEY_INLINE +#endif + +#if defined(JSON_HEDLEY_ALWAYS_INLINE) + #undef JSON_HEDLEY_ALWAYS_INLINE +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(always_inline) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,0,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,11,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) || \ + JSON_HEDLEY_IAR_VERSION_CHECK(8,10,0) +# define JSON_HEDLEY_ALWAYS_INLINE __attribute__((__always_inline__)) JSON_HEDLEY_INLINE +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(12,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) +# define JSON_HEDLEY_ALWAYS_INLINE __forceinline +#elif defined(__cplusplus) && \ + ( \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(6,1,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) \ + ) +# define JSON_HEDLEY_ALWAYS_INLINE _Pragma("FUNC_ALWAYS_INLINE;") +#elif JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) +# define JSON_HEDLEY_ALWAYS_INLINE _Pragma("inline=forced") +#else +# define JSON_HEDLEY_ALWAYS_INLINE JSON_HEDLEY_INLINE +#endif + +#if defined(JSON_HEDLEY_NEVER_INLINE) + #undef JSON_HEDLEY_NEVER_INLINE +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(noinline) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,0,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,11,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(10,1,0) || \ + JSON_HEDLEY_TI_VERSION_CHECK(15,12,0) || \ + (JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(4,8,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_ARMCL_VERSION_CHECK(5,2,0) || \ + (JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL2000_VERSION_CHECK(6,4,0) || \ + (JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,0,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(4,3,0) || \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) || \ + JSON_HEDLEY_TI_CL7X_VERSION_CHECK(1,2,0) || \ + JSON_HEDLEY_TI_CLPRU_VERSION_CHECK(2,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) || \ + JSON_HEDLEY_IAR_VERSION_CHECK(8,10,0) + #define JSON_HEDLEY_NEVER_INLINE __attribute__((__noinline__)) +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(13,10,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_NEVER_INLINE __declspec(noinline) +#elif JSON_HEDLEY_PGI_VERSION_CHECK(10,2,0) + #define JSON_HEDLEY_NEVER_INLINE _Pragma("noinline") +#elif JSON_HEDLEY_TI_CL6X_VERSION_CHECK(6,0,0) && defined(__cplusplus) + #define JSON_HEDLEY_NEVER_INLINE _Pragma("FUNC_CANNOT_INLINE;") +#elif JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) + #define JSON_HEDLEY_NEVER_INLINE _Pragma("inline=never") +#elif JSON_HEDLEY_COMPCERT_VERSION_CHECK(3,2,0) + #define JSON_HEDLEY_NEVER_INLINE __attribute((noinline)) +#elif JSON_HEDLEY_PELLES_VERSION_CHECK(9,0,0) + #define JSON_HEDLEY_NEVER_INLINE __declspec(noinline) +#else + #define JSON_HEDLEY_NEVER_INLINE +#endif + +#if defined(JSON_HEDLEY_PRIVATE) + #undef JSON_HEDLEY_PRIVATE +#endif +#if defined(JSON_HEDLEY_PUBLIC) + #undef JSON_HEDLEY_PUBLIC +#endif +#if defined(JSON_HEDLEY_IMPORT) + #undef JSON_HEDLEY_IMPORT +#endif +#if defined(_WIN32) || defined(__CYGWIN__) +# define JSON_HEDLEY_PRIVATE +# define JSON_HEDLEY_PUBLIC __declspec(dllexport) +# define JSON_HEDLEY_IMPORT __declspec(dllimport) +#else +# if \ + JSON_HEDLEY_HAS_ATTRIBUTE(visibility) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,3,0) || \ + JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,11,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(13,1,0) || \ + ( \ + defined(__TI_EABI__) && \ + ( \ + (JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,2,0) && defined(__TI_GNU_ATTRIBUTE_SUPPORT__)) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(7,5,0) \ + ) \ + ) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) +# define JSON_HEDLEY_PRIVATE __attribute__((__visibility__("hidden"))) +# define JSON_HEDLEY_PUBLIC __attribute__((__visibility__("default"))) +# else +# define JSON_HEDLEY_PRIVATE +# define JSON_HEDLEY_PUBLIC +# endif +# define JSON_HEDLEY_IMPORT extern +#endif + +#if defined(JSON_HEDLEY_NO_THROW) + #undef JSON_HEDLEY_NO_THROW +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(nothrow) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,3,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_NO_THROW __attribute__((__nothrow__)) +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(13,1,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) + #define JSON_HEDLEY_NO_THROW __declspec(nothrow) +#else + #define JSON_HEDLEY_NO_THROW +#endif + +#if defined(JSON_HEDLEY_FALL_THROUGH) + #undef JSON_HEDLEY_FALL_THROUGH +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(fallthrough) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(7,0,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_FALL_THROUGH __attribute__((__fallthrough__)) +#elif JSON_HEDLEY_HAS_CPP_ATTRIBUTE_NS(clang,fallthrough) + #define JSON_HEDLEY_FALL_THROUGH JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[clang::fallthrough]]) +#elif JSON_HEDLEY_HAS_CPP_ATTRIBUTE(fallthrough) + #define JSON_HEDLEY_FALL_THROUGH JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_([[fallthrough]]) +#elif defined(__fallthrough) /* SAL */ + #define JSON_HEDLEY_FALL_THROUGH __fallthrough +#else + #define JSON_HEDLEY_FALL_THROUGH +#endif + +#if defined(JSON_HEDLEY_RETURNS_NON_NULL) + #undef JSON_HEDLEY_RETURNS_NON_NULL +#endif +#if \ + JSON_HEDLEY_HAS_ATTRIBUTE(returns_nonnull) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,9,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_RETURNS_NON_NULL __attribute__((__returns_nonnull__)) +#elif defined(_Ret_notnull_) /* SAL */ + #define JSON_HEDLEY_RETURNS_NON_NULL _Ret_notnull_ +#else + #define JSON_HEDLEY_RETURNS_NON_NULL +#endif + +#if defined(JSON_HEDLEY_ARRAY_PARAM) + #undef JSON_HEDLEY_ARRAY_PARAM +#endif +#if \ + defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 199901L) && \ + !defined(__STDC_NO_VLA__) && \ + !defined(__cplusplus) && \ + !defined(JSON_HEDLEY_PGI_VERSION) && \ + !defined(JSON_HEDLEY_TINYC_VERSION) + #define JSON_HEDLEY_ARRAY_PARAM(name) (name) +#else + #define JSON_HEDLEY_ARRAY_PARAM(name) +#endif + +#if defined(JSON_HEDLEY_IS_CONSTANT) + #undef JSON_HEDLEY_IS_CONSTANT +#endif +#if defined(JSON_HEDLEY_REQUIRE_CONSTEXPR) + #undef JSON_HEDLEY_REQUIRE_CONSTEXPR +#endif +/* JSON_HEDLEY_IS_CONSTEXPR_ is for + HEDLEY INTERNAL USE ONLY. API subject to change without notice. */ +#if defined(JSON_HEDLEY_IS_CONSTEXPR_) + #undef JSON_HEDLEY_IS_CONSTEXPR_ +#endif +#if \ + JSON_HEDLEY_HAS_BUILTIN(__builtin_constant_p) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,4,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_TINYC_VERSION_CHECK(0,9,19) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(4,1,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(13,1,0) || \ + JSON_HEDLEY_TI_CL6X_VERSION_CHECK(6,1,0) || \ + (JSON_HEDLEY_SUNPRO_VERSION_CHECK(5,10,0) && !defined(__cplusplus)) || \ + JSON_HEDLEY_CRAY_VERSION_CHECK(8,1,0) || \ + JSON_HEDLEY_MCST_LCC_VERSION_CHECK(1,25,10) + #define JSON_HEDLEY_IS_CONSTANT(expr) __builtin_constant_p(expr) +#endif +#if !defined(__cplusplus) +# if \ + JSON_HEDLEY_HAS_BUILTIN(__builtin_types_compatible_p) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(3,4,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(13,1,0) || \ + JSON_HEDLEY_CRAY_VERSION_CHECK(8,1,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(5,4,0) || \ + JSON_HEDLEY_TINYC_VERSION_CHECK(0,9,24) +#if defined(__INTPTR_TYPE__) + #define JSON_HEDLEY_IS_CONSTEXPR_(expr) __builtin_types_compatible_p(__typeof__((1 ? (void*) ((__INTPTR_TYPE__) ((expr) * 0)) : (int*) 0)), int*) +#else + #include + #define JSON_HEDLEY_IS_CONSTEXPR_(expr) __builtin_types_compatible_p(__typeof__((1 ? (void*) ((intptr_t) ((expr) * 0)) : (int*) 0)), int*) +#endif +# elif \ + ( \ + defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 201112L) && \ + !defined(JSON_HEDLEY_SUNPRO_VERSION) && \ + !defined(JSON_HEDLEY_PGI_VERSION) && \ + !defined(JSON_HEDLEY_IAR_VERSION)) || \ + (JSON_HEDLEY_HAS_EXTENSION(c_generic_selections) && !defined(JSON_HEDLEY_IAR_VERSION)) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,9,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(17,0,0) || \ + JSON_HEDLEY_IBM_VERSION_CHECK(12,1,0) || \ + JSON_HEDLEY_ARM_VERSION_CHECK(5,3,0) +#if defined(__INTPTR_TYPE__) + #define JSON_HEDLEY_IS_CONSTEXPR_(expr) _Generic((1 ? (void*) ((__INTPTR_TYPE__) ((expr) * 0)) : (int*) 0), int*: 1, void*: 0) +#else + #include + #define JSON_HEDLEY_IS_CONSTEXPR_(expr) _Generic((1 ? (void*) ((intptr_t) * 0) : (int*) 0), int*: 1, void*: 0) +#endif +# elif \ + defined(JSON_HEDLEY_GCC_VERSION) || \ + defined(JSON_HEDLEY_INTEL_VERSION) || \ + defined(JSON_HEDLEY_TINYC_VERSION) || \ + defined(JSON_HEDLEY_TI_ARMCL_VERSION) || \ + JSON_HEDLEY_TI_CL430_VERSION_CHECK(18,12,0) || \ + defined(JSON_HEDLEY_TI_CL2000_VERSION) || \ + defined(JSON_HEDLEY_TI_CL6X_VERSION) || \ + defined(JSON_HEDLEY_TI_CL7X_VERSION) || \ + defined(JSON_HEDLEY_TI_CLPRU_VERSION) || \ + defined(__clang__) +# define JSON_HEDLEY_IS_CONSTEXPR_(expr) ( \ + sizeof(void) != \ + sizeof(*( \ + 1 ? \ + ((void*) ((expr) * 0L) ) : \ +((struct { char v[sizeof(void) * 2]; } *) 1) \ + ) \ + ) \ + ) +# endif +#endif +#if defined(JSON_HEDLEY_IS_CONSTEXPR_) + #if !defined(JSON_HEDLEY_IS_CONSTANT) + #define JSON_HEDLEY_IS_CONSTANT(expr) JSON_HEDLEY_IS_CONSTEXPR_(expr) + #endif + #define JSON_HEDLEY_REQUIRE_CONSTEXPR(expr) (JSON_HEDLEY_IS_CONSTEXPR_(expr) ? (expr) : (-1)) +#else + #if !defined(JSON_HEDLEY_IS_CONSTANT) + #define JSON_HEDLEY_IS_CONSTANT(expr) (0) + #endif + #define JSON_HEDLEY_REQUIRE_CONSTEXPR(expr) (expr) +#endif + +#if defined(JSON_HEDLEY_BEGIN_C_DECLS) + #undef JSON_HEDLEY_BEGIN_C_DECLS +#endif +#if defined(JSON_HEDLEY_END_C_DECLS) + #undef JSON_HEDLEY_END_C_DECLS +#endif +#if defined(JSON_HEDLEY_C_DECL) + #undef JSON_HEDLEY_C_DECL +#endif +#if defined(__cplusplus) + #define JSON_HEDLEY_BEGIN_C_DECLS extern "C" { + #define JSON_HEDLEY_END_C_DECLS } + #define JSON_HEDLEY_C_DECL extern "C" +#else + #define JSON_HEDLEY_BEGIN_C_DECLS + #define JSON_HEDLEY_END_C_DECLS + #define JSON_HEDLEY_C_DECL +#endif + +#if defined(JSON_HEDLEY_STATIC_ASSERT) + #undef JSON_HEDLEY_STATIC_ASSERT +#endif +#if \ + !defined(__cplusplus) && ( \ + (defined(__STDC_VERSION__) && (__STDC_VERSION__ >= 201112L)) || \ + (JSON_HEDLEY_HAS_FEATURE(c_static_assert) && !defined(JSON_HEDLEY_INTEL_CL_VERSION)) || \ + JSON_HEDLEY_GCC_VERSION_CHECK(6,0,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) || \ + defined(_Static_assert) \ + ) +# define JSON_HEDLEY_STATIC_ASSERT(expr, message) _Static_assert(expr, message) +#elif \ + (defined(__cplusplus) && (__cplusplus >= 201103L)) || \ + JSON_HEDLEY_MSVC_VERSION_CHECK(16,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) +# define JSON_HEDLEY_STATIC_ASSERT(expr, message) JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_(static_assert(expr, message)) +#else +# define JSON_HEDLEY_STATIC_ASSERT(expr, message) +#endif + +#if defined(JSON_HEDLEY_NULL) + #undef JSON_HEDLEY_NULL +#endif +#if defined(__cplusplus) + #if __cplusplus >= 201103L + #define JSON_HEDLEY_NULL JSON_HEDLEY_DIAGNOSTIC_DISABLE_CPP98_COMPAT_WRAP_(nullptr) + #elif defined(NULL) + #define JSON_HEDLEY_NULL NULL + #else + #define JSON_HEDLEY_NULL JSON_HEDLEY_STATIC_CAST(void*, 0) + #endif +#elif defined(NULL) + #define JSON_HEDLEY_NULL NULL +#else + #define JSON_HEDLEY_NULL ((void*) 0) +#endif + +#if defined(JSON_HEDLEY_MESSAGE) + #undef JSON_HEDLEY_MESSAGE +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wunknown-pragmas") +# define JSON_HEDLEY_MESSAGE(msg) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS \ + JSON_HEDLEY_PRAGMA(message msg) \ + JSON_HEDLEY_DIAGNOSTIC_POP +#elif \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,4,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) +# define JSON_HEDLEY_MESSAGE(msg) JSON_HEDLEY_PRAGMA(message msg) +#elif JSON_HEDLEY_CRAY_VERSION_CHECK(5,0,0) +# define JSON_HEDLEY_MESSAGE(msg) JSON_HEDLEY_PRAGMA(_CRI message msg) +#elif JSON_HEDLEY_IAR_VERSION_CHECK(8,0,0) +# define JSON_HEDLEY_MESSAGE(msg) JSON_HEDLEY_PRAGMA(message(msg)) +#elif JSON_HEDLEY_PELLES_VERSION_CHECK(2,0,0) +# define JSON_HEDLEY_MESSAGE(msg) JSON_HEDLEY_PRAGMA(message(msg)) +#else +# define JSON_HEDLEY_MESSAGE(msg) +#endif + +#if defined(JSON_HEDLEY_WARNING) + #undef JSON_HEDLEY_WARNING +#endif +#if JSON_HEDLEY_HAS_WARNING("-Wunknown-pragmas") +# define JSON_HEDLEY_WARNING(msg) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + JSON_HEDLEY_DIAGNOSTIC_DISABLE_UNKNOWN_PRAGMAS \ + JSON_HEDLEY_PRAGMA(clang warning msg) \ + JSON_HEDLEY_DIAGNOSTIC_POP +#elif \ + JSON_HEDLEY_GCC_VERSION_CHECK(4,8,0) || \ + JSON_HEDLEY_PGI_VERSION_CHECK(18,4,0) || \ + JSON_HEDLEY_INTEL_VERSION_CHECK(13,0,0) +# define JSON_HEDLEY_WARNING(msg) JSON_HEDLEY_PRAGMA(GCC warning msg) +#elif \ + JSON_HEDLEY_MSVC_VERSION_CHECK(15,0,0) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) +# define JSON_HEDLEY_WARNING(msg) JSON_HEDLEY_PRAGMA(message(msg)) +#else +# define JSON_HEDLEY_WARNING(msg) JSON_HEDLEY_MESSAGE(msg) +#endif + +#if defined(JSON_HEDLEY_REQUIRE) + #undef JSON_HEDLEY_REQUIRE +#endif +#if defined(JSON_HEDLEY_REQUIRE_MSG) + #undef JSON_HEDLEY_REQUIRE_MSG +#endif +#if JSON_HEDLEY_HAS_ATTRIBUTE(diagnose_if) +# if JSON_HEDLEY_HAS_WARNING("-Wgcc-compat") +# define JSON_HEDLEY_REQUIRE(expr) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("clang diagnostic ignored \"-Wgcc-compat\"") \ + __attribute__((diagnose_if(!(expr), #expr, "error"))) \ + JSON_HEDLEY_DIAGNOSTIC_POP +# define JSON_HEDLEY_REQUIRE_MSG(expr,msg) \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("clang diagnostic ignored \"-Wgcc-compat\"") \ + __attribute__((diagnose_if(!(expr), msg, "error"))) \ + JSON_HEDLEY_DIAGNOSTIC_POP +# else +# define JSON_HEDLEY_REQUIRE(expr) __attribute__((diagnose_if(!(expr), #expr, "error"))) +# define JSON_HEDLEY_REQUIRE_MSG(expr,msg) __attribute__((diagnose_if(!(expr), msg, "error"))) +# endif +#else +# define JSON_HEDLEY_REQUIRE(expr) +# define JSON_HEDLEY_REQUIRE_MSG(expr,msg) +#endif + +#if defined(JSON_HEDLEY_FLAGS) + #undef JSON_HEDLEY_FLAGS +#endif +#if JSON_HEDLEY_HAS_ATTRIBUTE(flag_enum) && (!defined(__cplusplus) || JSON_HEDLEY_HAS_WARNING("-Wbitfield-enum-conversion")) + #define JSON_HEDLEY_FLAGS __attribute__((__flag_enum__)) +#else + #define JSON_HEDLEY_FLAGS +#endif + +#if defined(JSON_HEDLEY_FLAGS_CAST) + #undef JSON_HEDLEY_FLAGS_CAST +#endif +#if JSON_HEDLEY_INTEL_VERSION_CHECK(19,0,0) +# define JSON_HEDLEY_FLAGS_CAST(T, expr) (__extension__ ({ \ + JSON_HEDLEY_DIAGNOSTIC_PUSH \ + _Pragma("warning(disable:188)") \ + ((T) (expr)); \ + JSON_HEDLEY_DIAGNOSTIC_POP \ + })) +#else +# define JSON_HEDLEY_FLAGS_CAST(T, expr) JSON_HEDLEY_STATIC_CAST(T, expr) +#endif + +#if defined(JSON_HEDLEY_EMPTY_BASES) + #undef JSON_HEDLEY_EMPTY_BASES +#endif +#if \ + (JSON_HEDLEY_MSVC_VERSION_CHECK(19,0,23918) && !JSON_HEDLEY_MSVC_VERSION_CHECK(20,0,0)) || \ + JSON_HEDLEY_INTEL_CL_VERSION_CHECK(2021,1,0) + #define JSON_HEDLEY_EMPTY_BASES __declspec(empty_bases) +#else + #define JSON_HEDLEY_EMPTY_BASES +#endif + +/* Remaining macros are deprecated. */ + +#if defined(JSON_HEDLEY_GCC_NOT_CLANG_VERSION_CHECK) + #undef JSON_HEDLEY_GCC_NOT_CLANG_VERSION_CHECK +#endif +#if defined(__clang__) + #define JSON_HEDLEY_GCC_NOT_CLANG_VERSION_CHECK(major,minor,patch) (0) +#else + #define JSON_HEDLEY_GCC_NOT_CLANG_VERSION_CHECK(major,minor,patch) JSON_HEDLEY_GCC_VERSION_CHECK(major,minor,patch) +#endif + +#if defined(JSON_HEDLEY_CLANG_HAS_ATTRIBUTE) + #undef JSON_HEDLEY_CLANG_HAS_ATTRIBUTE +#endif +#define JSON_HEDLEY_CLANG_HAS_ATTRIBUTE(attribute) JSON_HEDLEY_HAS_ATTRIBUTE(attribute) + +#if defined(JSON_HEDLEY_CLANG_HAS_CPP_ATTRIBUTE) + #undef JSON_HEDLEY_CLANG_HAS_CPP_ATTRIBUTE +#endif +#define JSON_HEDLEY_CLANG_HAS_CPP_ATTRIBUTE(attribute) JSON_HEDLEY_HAS_CPP_ATTRIBUTE(attribute) + +#if defined(JSON_HEDLEY_CLANG_HAS_BUILTIN) + #undef JSON_HEDLEY_CLANG_HAS_BUILTIN +#endif +#define JSON_HEDLEY_CLANG_HAS_BUILTIN(builtin) JSON_HEDLEY_HAS_BUILTIN(builtin) + +#if defined(JSON_HEDLEY_CLANG_HAS_FEATURE) + #undef JSON_HEDLEY_CLANG_HAS_FEATURE +#endif +#define JSON_HEDLEY_CLANG_HAS_FEATURE(feature) JSON_HEDLEY_HAS_FEATURE(feature) + +#if defined(JSON_HEDLEY_CLANG_HAS_EXTENSION) + #undef JSON_HEDLEY_CLANG_HAS_EXTENSION +#endif +#define JSON_HEDLEY_CLANG_HAS_EXTENSION(extension) JSON_HEDLEY_HAS_EXTENSION(extension) + +#if defined(JSON_HEDLEY_CLANG_HAS_DECLSPEC_DECLSPEC_ATTRIBUTE) + #undef JSON_HEDLEY_CLANG_HAS_DECLSPEC_DECLSPEC_ATTRIBUTE +#endif +#define JSON_HEDLEY_CLANG_HAS_DECLSPEC_ATTRIBUTE(attribute) JSON_HEDLEY_HAS_DECLSPEC_ATTRIBUTE(attribute) + +#if defined(JSON_HEDLEY_CLANG_HAS_WARNING) + #undef JSON_HEDLEY_CLANG_HAS_WARNING +#endif +#define JSON_HEDLEY_CLANG_HAS_WARNING(warning) JSON_HEDLEY_HAS_WARNING(warning) + +#endif /* !defined(JSON_HEDLEY_VERSION) || (JSON_HEDLEY_VERSION < X) */ + + +// This file contains all internal macro definitions (except those affecting ABI) +// You MUST include macro_unscope.hpp at the end of json.hpp to undef all of them + +// #include + + +// exclude unsupported compilers +#if !defined(JSON_SKIP_UNSUPPORTED_COMPILER_CHECK) + #if defined(__clang__) + #if (__clang_major__ * 10000 + __clang_minor__ * 100 + __clang_patchlevel__) < 30400 + #error "unsupported Clang version - see https://github.com/nlohmann/json#supported-compilers" + #endif + #elif defined(__GNUC__) && !(defined(__ICC) || defined(__INTEL_COMPILER)) + #if (__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__) < 40800 + #error "unsupported GCC version - see https://github.com/nlohmann/json#supported-compilers" + #endif + #endif +#endif + +// C++ language standard detection +// if the user manually specified the used c++ version this is skipped +#if !defined(JSON_HAS_CPP_23) && !defined(JSON_HAS_CPP_20) && !defined(JSON_HAS_CPP_17) && !defined(JSON_HAS_CPP_14) && !defined(JSON_HAS_CPP_11) + #if (defined(__cplusplus) && __cplusplus > 202002L) || (defined(_MSVC_LANG) && _MSVC_LANG > 202002L) + #define JSON_HAS_CPP_23 + #define JSON_HAS_CPP_20 + #define JSON_HAS_CPP_17 + #define JSON_HAS_CPP_14 + #elif (defined(__cplusplus) && __cplusplus > 201703L) || (defined(_MSVC_LANG) && _MSVC_LANG > 201703L) + #define JSON_HAS_CPP_20 + #define JSON_HAS_CPP_17 + #define JSON_HAS_CPP_14 + #elif (defined(__cplusplus) && __cplusplus > 201402L) || (defined(_HAS_CXX17) && _HAS_CXX17 == 1) // fix for issue #464 + #define JSON_HAS_CPP_17 + #define JSON_HAS_CPP_14 + #elif (defined(__cplusplus) && __cplusplus > 201103L) || (defined(_HAS_CXX14) && _HAS_CXX14 == 1) + #define JSON_HAS_CPP_14 + #endif + // the cpp 11 flag is always specified because it is the minimal required version + #define JSON_HAS_CPP_11 +#endif + +#ifdef __has_include + #if __has_include() + #include + #endif +#endif + +#if !defined(JSON_HAS_FILESYSTEM) && !defined(JSON_HAS_EXPERIMENTAL_FILESYSTEM) + #ifdef JSON_HAS_CPP_17 + #if defined(__cpp_lib_filesystem) + #define JSON_HAS_FILESYSTEM 1 + #elif defined(__cpp_lib_experimental_filesystem) + #define JSON_HAS_EXPERIMENTAL_FILESYSTEM 1 + #elif !defined(__has_include) + #define JSON_HAS_EXPERIMENTAL_FILESYSTEM 1 + #elif __has_include() + #define JSON_HAS_FILESYSTEM 1 + #elif __has_include() + #define JSON_HAS_EXPERIMENTAL_FILESYSTEM 1 + #endif + + // std::filesystem does not work on MinGW GCC 8: https://sourceforge.net/p/mingw-w64/bugs/737/ + #if defined(__MINGW32__) && defined(__GNUC__) && __GNUC__ == 8 + #undef JSON_HAS_FILESYSTEM + #undef JSON_HAS_EXPERIMENTAL_FILESYSTEM + #endif + + // no filesystem support before GCC 8: https://en.cppreference.com/w/cpp/compiler_support + #if defined(__GNUC__) && !defined(__clang__) && __GNUC__ < 8 + #undef JSON_HAS_FILESYSTEM + #undef JSON_HAS_EXPERIMENTAL_FILESYSTEM + #endif + + // no filesystem support before Clang 7: https://en.cppreference.com/w/cpp/compiler_support + #if defined(__clang_major__) && __clang_major__ < 7 + #undef JSON_HAS_FILESYSTEM + #undef JSON_HAS_EXPERIMENTAL_FILESYSTEM + #endif + + // no filesystem support before MSVC 19.14: https://en.cppreference.com/w/cpp/compiler_support + #if defined(_MSC_VER) && _MSC_VER < 1914 + #undef JSON_HAS_FILESYSTEM + #undef JSON_HAS_EXPERIMENTAL_FILESYSTEM + #endif + + // no filesystem support before iOS 13 + #if defined(__IPHONE_OS_VERSION_MIN_REQUIRED) && __IPHONE_OS_VERSION_MIN_REQUIRED < 130000 + #undef JSON_HAS_FILESYSTEM + #undef JSON_HAS_EXPERIMENTAL_FILESYSTEM + #endif + + // no filesystem support before macOS Catalina + #if defined(__MAC_OS_X_VERSION_MIN_REQUIRED) && __MAC_OS_X_VERSION_MIN_REQUIRED < 101500 + #undef JSON_HAS_FILESYSTEM + #undef JSON_HAS_EXPERIMENTAL_FILESYSTEM + #endif + #endif +#endif + +#ifndef JSON_HAS_EXPERIMENTAL_FILESYSTEM + #define JSON_HAS_EXPERIMENTAL_FILESYSTEM 0 +#endif + +#ifndef JSON_HAS_FILESYSTEM + #define JSON_HAS_FILESYSTEM 0 +#endif + +#ifndef JSON_HAS_THREE_WAY_COMPARISON + #if defined(__cpp_impl_three_way_comparison) && __cpp_impl_three_way_comparison >= 201907L \ + && defined(__cpp_lib_three_way_comparison) && __cpp_lib_three_way_comparison >= 201907L + #define JSON_HAS_THREE_WAY_COMPARISON 1 + #else + #define JSON_HAS_THREE_WAY_COMPARISON 0 + #endif +#endif + +#ifndef JSON_HAS_RANGES + // ranges header shipping in GCC 11.1.0 (released 2021-04-27) has syntax error + #if defined(__GLIBCXX__) && __GLIBCXX__ == 20210427 + #define JSON_HAS_RANGES 0 + #elif defined(__cpp_lib_ranges) + #define JSON_HAS_RANGES 1 + #else + #define JSON_HAS_RANGES 0 + #endif +#endif + +#ifndef JSON_HAS_STATIC_RTTI + #if !defined(_HAS_STATIC_RTTI) || _HAS_STATIC_RTTI != 0 + #define JSON_HAS_STATIC_RTTI 1 + #else + #define JSON_HAS_STATIC_RTTI 0 + #endif +#endif + +#ifdef JSON_HAS_CPP_17 + #define JSON_INLINE_VARIABLE inline +#else + #define JSON_INLINE_VARIABLE +#endif + +#if JSON_HEDLEY_HAS_ATTRIBUTE(no_unique_address) + #define JSON_NO_UNIQUE_ADDRESS [[no_unique_address]] +#else + #define JSON_NO_UNIQUE_ADDRESS +#endif + +// disable documentation warnings on clang +#if defined(__clang__) + #pragma clang diagnostic push + #pragma clang diagnostic ignored "-Wdocumentation" + #pragma clang diagnostic ignored "-Wdocumentation-unknown-command" +#endif + +// allow disabling exceptions +#if (defined(__cpp_exceptions) || defined(__EXCEPTIONS) || defined(_CPPUNWIND)) && !defined(JSON_NOEXCEPTION) + #define JSON_THROW(exception) throw exception + #define JSON_TRY try + #define JSON_CATCH(exception) catch(exception) + #define JSON_INTERNAL_CATCH(exception) catch(exception) +#else + #include + #define JSON_THROW(exception) std::abort() + #define JSON_TRY if(true) + #define JSON_CATCH(exception) if(false) + #define JSON_INTERNAL_CATCH(exception) if(false) +#endif + +// override exception macros +#if defined(JSON_THROW_USER) + #undef JSON_THROW + #define JSON_THROW JSON_THROW_USER +#endif +#if defined(JSON_TRY_USER) + #undef JSON_TRY + #define JSON_TRY JSON_TRY_USER +#endif +#if defined(JSON_CATCH_USER) + #undef JSON_CATCH + #define JSON_CATCH JSON_CATCH_USER + #undef JSON_INTERNAL_CATCH + #define JSON_INTERNAL_CATCH JSON_CATCH_USER +#endif +#if defined(JSON_INTERNAL_CATCH_USER) + #undef JSON_INTERNAL_CATCH + #define JSON_INTERNAL_CATCH JSON_INTERNAL_CATCH_USER +#endif + +// allow overriding assert +#if !defined(JSON_ASSERT) + #include // assert + #define JSON_ASSERT(x) assert(x) +#endif + +// allow to access some private functions (needed by the test suite) +#if defined(JSON_TESTS_PRIVATE) + #define JSON_PRIVATE_UNLESS_TESTED public +#else + #define JSON_PRIVATE_UNLESS_TESTED private +#endif + +/*! +@brief macro to briefly define a mapping between an enum and JSON +@def NLOHMANN_JSON_SERIALIZE_ENUM +@since version 3.4.0 +*/ +#define NLOHMANN_JSON_SERIALIZE_ENUM(ENUM_TYPE, ...) \ + template \ + inline void to_json(BasicJsonType& j, const ENUM_TYPE& e) \ + { \ + /* NOLINTNEXTLINE(modernize-type-traits) we use C++11 */ \ + static_assert(std::is_enum::value, #ENUM_TYPE " must be an enum!"); \ + /* NOLINTNEXTLINE(modernize-avoid-c-arrays) we don't want to depend on */ \ + static const std::pair m[] = __VA_ARGS__; \ + auto it = std::find_if(std::begin(m), std::end(m), \ + [e](const std::pair& ej_pair) -> bool \ + { \ + return ej_pair.first == e; \ + }); \ + j = ((it != std::end(m)) ? it : std::begin(m))->second; \ + } \ + template \ + inline void from_json(const BasicJsonType& j, ENUM_TYPE& e) \ + { \ + /* NOLINTNEXTLINE(modernize-type-traits) we use C++11 */ \ + static_assert(std::is_enum::value, #ENUM_TYPE " must be an enum!"); \ + /* NOLINTNEXTLINE(modernize-avoid-c-arrays) we don't want to depend on */ \ + static const std::pair m[] = __VA_ARGS__; \ + auto it = std::find_if(std::begin(m), std::end(m), \ + [&j](const std::pair& ej_pair) -> bool \ + { \ + return ej_pair.second == j; \ + }); \ + e = ((it != std::end(m)) ? it : std::begin(m))->first; \ + } + +// Ugly macros to avoid uglier copy-paste when specializing basic_json. They +// may be removed in the future once the class is split. + +#define NLOHMANN_BASIC_JSON_TPL_DECLARATION \ + template class ObjectType, \ + template class ArrayType, \ + class StringType, class BooleanType, class NumberIntegerType, \ + class NumberUnsignedType, class NumberFloatType, \ + template class AllocatorType, \ + template class JSONSerializer, \ + class BinaryType, \ + class CustomBaseClass> + +#define NLOHMANN_BASIC_JSON_TPL \ + basic_json + +// Macros to simplify conversion from/to types + +#define NLOHMANN_JSON_EXPAND( x ) x +#define NLOHMANN_JSON_GET_MACRO(_1, _2, _3, _4, _5, _6, _7, _8, _9, _10, _11, _12, _13, _14, _15, _16, _17, _18, _19, _20, _21, _22, _23, _24, _25, _26, _27, _28, _29, _30, _31, _32, _33, _34, _35, _36, _37, _38, _39, _40, _41, _42, _43, _44, _45, _46, _47, _48, _49, _50, _51, _52, _53, _54, _55, _56, _57, _58, _59, _60, _61, _62, _63, _64, NAME,...) NAME +#define NLOHMANN_JSON_PASTE(...) NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_GET_MACRO(__VA_ARGS__, \ + NLOHMANN_JSON_PASTE64, \ + NLOHMANN_JSON_PASTE63, \ + NLOHMANN_JSON_PASTE62, \ + NLOHMANN_JSON_PASTE61, \ + NLOHMANN_JSON_PASTE60, \ + NLOHMANN_JSON_PASTE59, \ + NLOHMANN_JSON_PASTE58, \ + NLOHMANN_JSON_PASTE57, \ + NLOHMANN_JSON_PASTE56, \ + NLOHMANN_JSON_PASTE55, \ + NLOHMANN_JSON_PASTE54, \ + NLOHMANN_JSON_PASTE53, \ + NLOHMANN_JSON_PASTE52, \ + NLOHMANN_JSON_PASTE51, \ + NLOHMANN_JSON_PASTE50, \ + NLOHMANN_JSON_PASTE49, \ + NLOHMANN_JSON_PASTE48, \ + NLOHMANN_JSON_PASTE47, \ + NLOHMANN_JSON_PASTE46, \ + NLOHMANN_JSON_PASTE45, \ + NLOHMANN_JSON_PASTE44, \ + NLOHMANN_JSON_PASTE43, \ + NLOHMANN_JSON_PASTE42, \ + NLOHMANN_JSON_PASTE41, \ + NLOHMANN_JSON_PASTE40, \ + NLOHMANN_JSON_PASTE39, \ + NLOHMANN_JSON_PASTE38, \ + NLOHMANN_JSON_PASTE37, \ + NLOHMANN_JSON_PASTE36, \ + NLOHMANN_JSON_PASTE35, \ + NLOHMANN_JSON_PASTE34, \ + NLOHMANN_JSON_PASTE33, \ + NLOHMANN_JSON_PASTE32, \ + NLOHMANN_JSON_PASTE31, \ + NLOHMANN_JSON_PASTE30, \ + NLOHMANN_JSON_PASTE29, \ + NLOHMANN_JSON_PASTE28, \ + NLOHMANN_JSON_PASTE27, \ + NLOHMANN_JSON_PASTE26, \ + NLOHMANN_JSON_PASTE25, \ + NLOHMANN_JSON_PASTE24, \ + NLOHMANN_JSON_PASTE23, \ + NLOHMANN_JSON_PASTE22, \ + NLOHMANN_JSON_PASTE21, \ + NLOHMANN_JSON_PASTE20, \ + NLOHMANN_JSON_PASTE19, \ + NLOHMANN_JSON_PASTE18, \ + NLOHMANN_JSON_PASTE17, \ + NLOHMANN_JSON_PASTE16, \ + NLOHMANN_JSON_PASTE15, \ + NLOHMANN_JSON_PASTE14, \ + NLOHMANN_JSON_PASTE13, \ + NLOHMANN_JSON_PASTE12, \ + NLOHMANN_JSON_PASTE11, \ + NLOHMANN_JSON_PASTE10, \ + NLOHMANN_JSON_PASTE9, \ + NLOHMANN_JSON_PASTE8, \ + NLOHMANN_JSON_PASTE7, \ + NLOHMANN_JSON_PASTE6, \ + NLOHMANN_JSON_PASTE5, \ + NLOHMANN_JSON_PASTE4, \ + NLOHMANN_JSON_PASTE3, \ + NLOHMANN_JSON_PASTE2, \ + NLOHMANN_JSON_PASTE1)(__VA_ARGS__)) +#define NLOHMANN_JSON_PASTE2(func, v1) func(v1) +#define NLOHMANN_JSON_PASTE3(func, v1, v2) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE2(func, v2) +#define NLOHMANN_JSON_PASTE4(func, v1, v2, v3) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE3(func, v2, v3) +#define NLOHMANN_JSON_PASTE5(func, v1, v2, v3, v4) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE4(func, v2, v3, v4) +#define NLOHMANN_JSON_PASTE6(func, v1, v2, v3, v4, v5) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE5(func, v2, v3, v4, v5) +#define NLOHMANN_JSON_PASTE7(func, v1, v2, v3, v4, v5, v6) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE6(func, v2, v3, v4, v5, v6) +#define NLOHMANN_JSON_PASTE8(func, v1, v2, v3, v4, v5, v6, v7) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE7(func, v2, v3, v4, v5, v6, v7) +#define NLOHMANN_JSON_PASTE9(func, v1, v2, v3, v4, v5, v6, v7, v8) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE8(func, v2, v3, v4, v5, v6, v7, v8) +#define NLOHMANN_JSON_PASTE10(func, v1, v2, v3, v4, v5, v6, v7, v8, v9) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE9(func, v2, v3, v4, v5, v6, v7, v8, v9) +#define NLOHMANN_JSON_PASTE11(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE10(func, v2, v3, v4, v5, v6, v7, v8, v9, v10) +#define NLOHMANN_JSON_PASTE12(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE11(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11) +#define NLOHMANN_JSON_PASTE13(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE12(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12) +#define NLOHMANN_JSON_PASTE14(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE13(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13) +#define NLOHMANN_JSON_PASTE15(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE14(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14) +#define NLOHMANN_JSON_PASTE16(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE15(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15) +#define NLOHMANN_JSON_PASTE17(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE16(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16) +#define NLOHMANN_JSON_PASTE18(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE17(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17) +#define NLOHMANN_JSON_PASTE19(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE18(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18) +#define NLOHMANN_JSON_PASTE20(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE19(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19) +#define NLOHMANN_JSON_PASTE21(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE20(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20) +#define NLOHMANN_JSON_PASTE22(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE21(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21) +#define NLOHMANN_JSON_PASTE23(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE22(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22) +#define NLOHMANN_JSON_PASTE24(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE23(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23) +#define NLOHMANN_JSON_PASTE25(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE24(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24) +#define NLOHMANN_JSON_PASTE26(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE25(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25) +#define NLOHMANN_JSON_PASTE27(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE26(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26) +#define NLOHMANN_JSON_PASTE28(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE27(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27) +#define NLOHMANN_JSON_PASTE29(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE28(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28) +#define NLOHMANN_JSON_PASTE30(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE29(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29) +#define NLOHMANN_JSON_PASTE31(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE30(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30) +#define NLOHMANN_JSON_PASTE32(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE31(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31) +#define NLOHMANN_JSON_PASTE33(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE32(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32) +#define NLOHMANN_JSON_PASTE34(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE33(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33) +#define NLOHMANN_JSON_PASTE35(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE34(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34) +#define NLOHMANN_JSON_PASTE36(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE35(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35) +#define NLOHMANN_JSON_PASTE37(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE36(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36) +#define NLOHMANN_JSON_PASTE38(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE37(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37) +#define NLOHMANN_JSON_PASTE39(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE38(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38) +#define NLOHMANN_JSON_PASTE40(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE39(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39) +#define NLOHMANN_JSON_PASTE41(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE40(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40) +#define NLOHMANN_JSON_PASTE42(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE41(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41) +#define NLOHMANN_JSON_PASTE43(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE42(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42) +#define NLOHMANN_JSON_PASTE44(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE43(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43) +#define NLOHMANN_JSON_PASTE45(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE44(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44) +#define NLOHMANN_JSON_PASTE46(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE45(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45) +#define NLOHMANN_JSON_PASTE47(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE46(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46) +#define NLOHMANN_JSON_PASTE48(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE47(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47) +#define NLOHMANN_JSON_PASTE49(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE48(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48) +#define NLOHMANN_JSON_PASTE50(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE49(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49) +#define NLOHMANN_JSON_PASTE51(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE50(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50) +#define NLOHMANN_JSON_PASTE52(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE51(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51) +#define NLOHMANN_JSON_PASTE53(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE52(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52) +#define NLOHMANN_JSON_PASTE54(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE53(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53) +#define NLOHMANN_JSON_PASTE55(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE54(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54) +#define NLOHMANN_JSON_PASTE56(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE55(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55) +#define NLOHMANN_JSON_PASTE57(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE56(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56) +#define NLOHMANN_JSON_PASTE58(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE57(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57) +#define NLOHMANN_JSON_PASTE59(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE58(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58) +#define NLOHMANN_JSON_PASTE60(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE59(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59) +#define NLOHMANN_JSON_PASTE61(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE60(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60) +#define NLOHMANN_JSON_PASTE62(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60, v61) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE61(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60, v61) +#define NLOHMANN_JSON_PASTE63(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60, v61, v62) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE62(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60, v61, v62) +#define NLOHMANN_JSON_PASTE64(func, v1, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60, v61, v62, v63) NLOHMANN_JSON_PASTE2(func, v1) NLOHMANN_JSON_PASTE63(func, v2, v3, v4, v5, v6, v7, v8, v9, v10, v11, v12, v13, v14, v15, v16, v17, v18, v19, v20, v21, v22, v23, v24, v25, v26, v27, v28, v29, v30, v31, v32, v33, v34, v35, v36, v37, v38, v39, v40, v41, v42, v43, v44, v45, v46, v47, v48, v49, v50, v51, v52, v53, v54, v55, v56, v57, v58, v59, v60, v61, v62, v63) + +#define NLOHMANN_JSON_TO(v1) nlohmann_json_j[#v1] = nlohmann_json_t.v1; +#define NLOHMANN_JSON_FROM(v1) nlohmann_json_j.at(#v1).get_to(nlohmann_json_t.v1); +#define NLOHMANN_JSON_FROM_WITH_DEFAULT(v1) nlohmann_json_t.v1 = !nlohmann_json_j.is_null() ? nlohmann_json_j.value(#v1, nlohmann_json_default_obj.v1) : nlohmann_json_default_obj.v1; + +/*! +@brief macro +@def NLOHMANN_DEFINE_TYPE_INTRUSIVE +@since version 3.9.0 +@sa https://json.nlohmann.me/api/macros/nlohmann_define_type_intrusive/ +*/ +#define NLOHMANN_DEFINE_TYPE_INTRUSIVE(Type, ...) \ + template::value, int> = 0> \ + friend void to_json(BasicJsonType& nlohmann_json_j, const Type& nlohmann_json_t) { NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } \ + template::value, int> = 0> \ + friend void from_json(const BasicJsonType& nlohmann_json_j, Type& nlohmann_json_t) { NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_FROM, __VA_ARGS__)) } + +/*! +@brief macro +@def NLOHMANN_DEFINE_TYPE_INTRUSIVE_WITH_DEFAULT +@since version 3.11.0 +@sa https://json.nlohmann.me/api/macros/nlohmann_define_type_intrusive/ +*/ +#define NLOHMANN_DEFINE_TYPE_INTRUSIVE_WITH_DEFAULT(Type, ...) \ + template::value, int> = 0> \ + friend void to_json(BasicJsonType& nlohmann_json_j, const Type& nlohmann_json_t) { NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } \ + template::value, int> = 0> \ + friend void from_json(const BasicJsonType& nlohmann_json_j, Type& nlohmann_json_t) { const Type nlohmann_json_default_obj{}; NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_FROM_WITH_DEFAULT, __VA_ARGS__)) } + +/*! +@brief macro +@def NLOHMANN_DEFINE_TYPE_INTRUSIVE_ONLY_SERIALIZE +@since version 3.11.3 +@sa https://json.nlohmann.me/api/macros/nlohmann_define_type_intrusive/ +*/ +#define NLOHMANN_DEFINE_TYPE_INTRUSIVE_ONLY_SERIALIZE(Type, ...) \ + template::value, int> = 0> \ + friend void to_json(BasicJsonType& nlohmann_json_j, const Type& nlohmann_json_t) { NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } + +/*! +@brief macro +@def NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE +@since version 3.9.0 +@sa https://json.nlohmann.me/api/macros/nlohmann_define_type_non_intrusive/ +*/ +#define NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE(Type, ...) \ + template::value, int> = 0> \ + void to_json(BasicJsonType& nlohmann_json_j, const Type& nlohmann_json_t) { NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } \ + template::value, int> = 0> \ + void from_json(const BasicJsonType& nlohmann_json_j, Type& nlohmann_json_t) { NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_FROM, __VA_ARGS__)) } + +/*! +@brief macro +@def NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE_WITH_DEFAULT +@since version 3.11.0 +@sa https://json.nlohmann.me/api/macros/nlohmann_define_type_non_intrusive/ +*/ +#define NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE_WITH_DEFAULT(Type, ...) \ + template::value, int> = 0> \ + void to_json(BasicJsonType& nlohmann_json_j, const Type& nlohmann_json_t) { NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } \ + template::value, int> = 0> \ + void from_json(const BasicJsonType& nlohmann_json_j, Type& nlohmann_json_t) { const Type nlohmann_json_default_obj{}; NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_FROM_WITH_DEFAULT, __VA_ARGS__)) } + +/*! +@brief macro +@def NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE_ONLY_SERIALIZE +@since version 3.11.3 +@sa https://json.nlohmann.me/api/macros/nlohmann_define_type_non_intrusive/ +*/ +#define NLOHMANN_DEFINE_TYPE_NON_INTRUSIVE_ONLY_SERIALIZE(Type, ...) \ + template::value, int> = 0> \ + void to_json(BasicJsonType& nlohmann_json_j, const Type& nlohmann_json_t) { NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } + +/*! +@brief macro +@def NLOHMANN_DEFINE_DERIVED_TYPE_INTRUSIVE +@since version 3.12.0 +@sa https://json.nlohmann.me/api/macros/nlohmann_define_derived_type/ +*/ +#define NLOHMANN_DEFINE_DERIVED_TYPE_INTRUSIVE(Type, BaseType, ...) \ + template::value, int> = 0> \ + friend void to_json(BasicJsonType& nlohmann_json_j, const Type& nlohmann_json_t) { nlohmann::to_json(nlohmann_json_j, static_cast(nlohmann_json_t)); NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } \ + template::value, int> = 0> \ + friend void from_json(const BasicJsonType& nlohmann_json_j, Type& nlohmann_json_t) { nlohmann::from_json(nlohmann_json_j, static_cast(nlohmann_json_t)); NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_FROM, __VA_ARGS__)) } + +/*! +@brief macro +@def NLOHMANN_DEFINE_DERIVED_TYPE_INTRUSIVE_WITH_DEFAULT +@since version 3.12.0 +@sa https://json.nlohmann.me/api/macros/nlohmann_define_derived_type/ +*/ +#define NLOHMANN_DEFINE_DERIVED_TYPE_INTRUSIVE_WITH_DEFAULT(Type, BaseType, ...) \ + template::value, int> = 0> \ + friend void to_json(BasicJsonType& nlohmann_json_j, const Type& nlohmann_json_t) { nlohmann::to_json(nlohmann_json_j, static_cast(nlohmann_json_t)); NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } \ + template::value, int> = 0> \ + friend void from_json(const BasicJsonType& nlohmann_json_j, Type& nlohmann_json_t) { nlohmann::from_json(nlohmann_json_j, static_cast(nlohmann_json_t)); const Type nlohmann_json_default_obj{}; NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_FROM_WITH_DEFAULT, __VA_ARGS__)) } + +/*! +@brief macro +@def NLOHMANN_DEFINE_DERIVED_TYPE_INTRUSIVE_ONLY_SERIALIZE +@since version 3.12.0 +@sa https://json.nlohmann.me/api/macros/nlohmann_define_derived_type/ +*/ +#define NLOHMANN_DEFINE_DERIVED_TYPE_INTRUSIVE_ONLY_SERIALIZE(Type, BaseType, ...) \ + template::value, int> = 0> \ + friend void to_json(BasicJsonType& nlohmann_json_j, const Type& nlohmann_json_t) { nlohmann::to_json(nlohmann_json_j, static_cast(nlohmann_json_t)); NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } + +/*! +@brief macro +@def NLOHMANN_DEFINE_DERIVED_TYPE_NON_INTRUSIVE +@since version 3.12.0 +@sa https://json.nlohmann.me/api/macros/nlohmann_define_derived_type/ +*/ +#define NLOHMANN_DEFINE_DERIVED_TYPE_NON_INTRUSIVE(Type, BaseType, ...) \ + template::value, int> = 0> \ + void to_json(BasicJsonType& nlohmann_json_j, const Type& nlohmann_json_t) { nlohmann::to_json(nlohmann_json_j, static_cast(nlohmann_json_t)); NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } \ + template::value, int> = 0> \ + void from_json(const BasicJsonType& nlohmann_json_j, Type& nlohmann_json_t) { nlohmann::from_json(nlohmann_json_j, static_cast(nlohmann_json_t)); NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_FROM, __VA_ARGS__)) } + +/*! +@brief macro +@def NLOHMANN_DEFINE_DERIVED_TYPE_NON_INTRUSIVE_WITH_DEFAULT +@since version 3.12.0 +@sa https://json.nlohmann.me/api/macros/nlohmann_define_derived_type/ +*/ +#define NLOHMANN_DEFINE_DERIVED_TYPE_NON_INTRUSIVE_WITH_DEFAULT(Type, BaseType, ...) \ + template::value, int> = 0> \ + void to_json(BasicJsonType& nlohmann_json_j, const Type& nlohmann_json_t) { nlohmann::to_json(nlohmann_json_j, static_cast(nlohmann_json_t)); NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } \ + template::value, int> = 0> \ + void from_json(const BasicJsonType& nlohmann_json_j, Type& nlohmann_json_t) { nlohmann::from_json(nlohmann_json_j, static_cast(nlohmann_json_t)); const Type nlohmann_json_default_obj{}; NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_FROM_WITH_DEFAULT, __VA_ARGS__)) } + +/*! +@brief macro +@def NLOHMANN_DEFINE_DERIVED_TYPE_NON_INTRUSIVE_ONLY_SERIALIZE +@since version 3.12.0 +@sa https://json.nlohmann.me/api/macros/nlohmann_define_derived_type/ +*/ +#define NLOHMANN_DEFINE_DERIVED_TYPE_NON_INTRUSIVE_ONLY_SERIALIZE(Type, BaseType, ...) \ + template::value, int> = 0> \ + void to_json(BasicJsonType& nlohmann_json_j, const Type& nlohmann_json_t) { nlohmann::to_json(nlohmann_json_j, static_cast(nlohmann_json_t)); NLOHMANN_JSON_EXPAND(NLOHMANN_JSON_PASTE(NLOHMANN_JSON_TO, __VA_ARGS__)) } + +// inspired from https://stackoverflow.com/a/26745591 +// allows calling any std function as if (e.g., with begin): +// using std::begin; begin(x); +// +// it allows using the detected idiom to retrieve the return type +// of such an expression +#define NLOHMANN_CAN_CALL_STD_FUNC_IMPL(std_name) \ + namespace detail { \ + using std::std_name; \ + \ + template \ + using result_of_##std_name = decltype(std_name(std::declval()...)); \ + } \ + \ + namespace detail2 { \ + struct std_name##_tag \ + { \ + }; \ + \ + template \ + std_name##_tag std_name(T&&...); \ + \ + template \ + using result_of_##std_name = decltype(std_name(std::declval()...)); \ + \ + template \ + struct would_call_std_##std_name \ + { \ + static constexpr auto const value = ::nlohmann::detail:: \ + is_detected_exact::value; \ + }; \ + } /* namespace detail2 */ \ + \ + template \ + struct would_call_std_##std_name : detail2::would_call_std_##std_name \ + { \ + } + +#ifndef JSON_USE_IMPLICIT_CONVERSIONS + #define JSON_USE_IMPLICIT_CONVERSIONS 1 +#endif + +#if JSON_USE_IMPLICIT_CONVERSIONS + #define JSON_EXPLICIT +#else + #define JSON_EXPLICIT explicit +#endif + +#ifndef JSON_DISABLE_ENUM_SERIALIZATION + #define JSON_DISABLE_ENUM_SERIALIZATION 0 +#endif + +#ifndef JSON_USE_GLOBAL_UDLS + #define JSON_USE_GLOBAL_UDLS 1 +#endif + +#if JSON_HAS_THREE_WAY_COMPARISON + #include // partial_ordering +#endif + +NLOHMANN_JSON_NAMESPACE_BEGIN +namespace detail +{ + +/////////////////////////// +// JSON type enumeration // +/////////////////////////// + +/*! +@brief the JSON type enumeration + +This enumeration collects the different JSON types. It is internally used to +distinguish the stored values, and the functions @ref basic_json::is_null(), +@ref basic_json::is_object(), @ref basic_json::is_array(), +@ref basic_json::is_string(), @ref basic_json::is_boolean(), +@ref basic_json::is_number() (with @ref basic_json::is_number_integer(), +@ref basic_json::is_number_unsigned(), and @ref basic_json::is_number_float()), +@ref basic_json::is_discarded(), @ref basic_json::is_primitive(), and +@ref basic_json::is_structured() rely on it. + +@note There are three enumeration entries (number_integer, number_unsigned, and +number_float), because the library distinguishes these three types for numbers: +@ref basic_json::number_unsigned_t is used for unsigned integers, +@ref basic_json::number_integer_t is used for signed integers, and +@ref basic_json::number_float_t is used for floating-point numbers or to +approximate integers which do not fit in the limits of their respective type. + +@sa see @ref basic_json::basic_json(const value_t value_type) -- create a JSON +value with the default value for a given type + +@since version 1.0.0 +*/ +enum class value_t : std::uint8_t +{ + null, ///< null value + object, ///< object (unordered set of name/value pairs) + array, ///< array (ordered collection of values) + string, ///< string value + boolean, ///< boolean value + number_integer, ///< number value (signed integer) + number_unsigned, ///< number value (unsigned integer) + number_float, ///< number value (floating-point) + binary, ///< binary array (ordered collection of bytes) + discarded ///< discarded by the parser callback function +}; + +/*! +@brief comparison operator for JSON types + +Returns an ordering that is similar to Python: +- order: null < boolean < number < object < array < string < binary +- furthermore, each type is not smaller than itself +- discarded values are not comparable +- binary is represented as a b"" string in python and directly comparable to a + string; however, making a binary array directly comparable with a string would + be surprising behavior in a JSON file. + +@since version 1.0.0 +*/ +#if JSON_HAS_THREE_WAY_COMPARISON + inline std::partial_ordering operator<=>(const value_t lhs, const value_t rhs) noexcept // *NOPAD* +#else + inline bool operator<(const value_t lhs, const value_t rhs) noexcept +#endif +{ + static constexpr std::array order = {{ + 0 /* null */, 3 /* object */, 4 /* array */, 5 /* string */, + 1 /* boolean */, 2 /* integer */, 2 /* unsigned */, 2 /* float */, + 6 /* binary */ + } + }; + + const auto l_index = static_cast(lhs); + const auto r_index = static_cast(rhs); +#if JSON_HAS_THREE_WAY_COMPARISON + if (l_index < order.size() && r_index < order.size()) + { + return order[l_index] <=> order[r_index]; // *NOPAD* + } + return std::partial_ordering::unordered; +#else + return l_index < order.size() && r_index < order.size() && order[l_index] < order[r_index]; +#endif +} + +// GCC selects the built-in operator< over an operator rewritten from +// a user-defined spaceship operator +// Clang, MSVC, and ICC select the rewritten candidate +// (see GCC bug https://gcc.gnu.org/bugzilla/show_bug.cgi?id=105200) +#if JSON_HAS_THREE_WAY_COMPARISON && defined(__GNUC__) +inline bool operator<(const value_t lhs, const value_t rhs) noexcept +{ + return std::is_lt(lhs <=> rhs); // *NOPAD* +} +#endif + +} // namespace detail +NLOHMANN_JSON_NAMESPACE_END + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +// #include + + +NLOHMANN_JSON_NAMESPACE_BEGIN +namespace detail +{ + +/*! +@brief replace all occurrences of a substring by another string + +@param[in,out] s the string to manipulate; changed so that all + occurrences of @a f are replaced with @a t +@param[in] f the substring to replace with @a t +@param[in] t the string to replace @a f + +@pre The search string @a f must not be empty. **This precondition is +enforced with an assertion.** + +@since version 2.0.0 +*/ +template +inline void replace_substring(StringType& s, const StringType& f, + const StringType& t) +{ + JSON_ASSERT(!f.empty()); + for (auto pos = s.find(f); // find first occurrence of f + pos != StringType::npos; // make sure f was found + s.replace(pos, f.size(), t), // replace with t, and + pos = s.find(f, pos + t.size())) // find next occurrence of f + {} +} + +/*! + * @brief string escaping as described in RFC 6901 (Sect. 4) + * @param[in] s string to escape + * @return escaped string + * + * Note the order of escaping "~" to "~0" and "/" to "~1" is important. + */ +template +inline StringType escape(StringType s) +{ + replace_substring(s, StringType{"~"}, StringType{"~0"}); + replace_substring(s, StringType{"/"}, StringType{"~1"}); + return s; +} + +/*! + * @brief string unescaping as described in RFC 6901 (Sect. 4) + * @param[in] s string to unescape + * @return unescaped string + * + * Note the order of escaping "~1" to "/" and "~0" to "~" is important. + */ +template +static void unescape(StringType& s) +{ + replace_substring(s, StringType{"~1"}, StringType{"/"}); + replace_substring(s, StringType{"~0"}, StringType{"~"}); +} + +} // namespace detail +NLOHMANN_JSON_NAMESPACE_END + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include // size_t + +// #include + + +NLOHMANN_JSON_NAMESPACE_BEGIN +namespace detail +{ + +/// struct to capture the start position of the current token +struct position_t +{ + /// the total number of characters read + std::size_t chars_read_total = 0; + /// the number of characters read in the current line + std::size_t chars_read_current_line = 0; + /// the number of lines read + std::size_t lines_read = 0; + + /// conversion to size_t to preserve SAX interface + constexpr operator size_t() const + { + return chars_read_total; + } +}; + +} // namespace detail +NLOHMANN_JSON_NAMESPACE_END + +// #include + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-FileCopyrightText: 2018 The Abseil Authors +// SPDX-License-Identifier: MIT + + + +#include // array +#include // size_t +#include // conditional, enable_if, false_type, integral_constant, is_constructible, is_integral, is_same, remove_cv, remove_reference, true_type +#include // index_sequence, make_index_sequence, index_sequence_for + +// #include + + +NLOHMANN_JSON_NAMESPACE_BEGIN +namespace detail +{ + +template +using uncvref_t = typename std::remove_cv::type>::type; + +#ifdef JSON_HAS_CPP_14 + +// the following utilities are natively available in C++14 +using std::enable_if_t; +using std::index_sequence; +using std::make_index_sequence; +using std::index_sequence_for; + +#else + +// alias templates to reduce boilerplate +template +using enable_if_t = typename std::enable_if::type; + +// The following code is taken from https://github.com/abseil/abseil-cpp/blob/10cb35e459f5ecca5b2ff107635da0bfa41011b4/absl/utility/utility.h +// which is part of Google Abseil (https://github.com/abseil/abseil-cpp), licensed under the Apache License 2.0. + +//// START OF CODE FROM GOOGLE ABSEIL + +// integer_sequence +// +// Class template representing a compile-time integer sequence. An instantiation +// of `integer_sequence` has a sequence of integers encoded in its +// type through its template arguments (which is a common need when +// working with C++11 variadic templates). `absl::integer_sequence` is designed +// to be a drop-in replacement for C++14's `std::integer_sequence`. +// +// Example: +// +// template< class T, T... Ints > +// void user_function(integer_sequence); +// +// int main() +// { +// // user_function's `T` will be deduced to `int` and `Ints...` +// // will be deduced to `0, 1, 2, 3, 4`. +// user_function(make_integer_sequence()); +// } +template +struct integer_sequence +{ + using value_type = T; + static constexpr std::size_t size() noexcept + { + return sizeof...(Ints); + } +}; + +// index_sequence +// +// A helper template for an `integer_sequence` of `size_t`, +// `absl::index_sequence` is designed to be a drop-in replacement for C++14's +// `std::index_sequence`. +template +using index_sequence = integer_sequence; + +namespace utility_internal +{ + +template +struct Extend; + +// Note that SeqSize == sizeof...(Ints). It's passed explicitly for efficiency. +template +struct Extend, SeqSize, 0> +{ + using type = integer_sequence < T, Ints..., (Ints + SeqSize)... >; +}; + +template +struct Extend, SeqSize, 1> +{ + using type = integer_sequence < T, Ints..., (Ints + SeqSize)..., 2 * SeqSize >; +}; + +// Recursion helper for 'make_integer_sequence'. +// 'Gen::type' is an alias for 'integer_sequence'. +template +struct Gen +{ + using type = + typename Extend < typename Gen < T, N / 2 >::type, N / 2, N % 2 >::type; +}; + +template +struct Gen +{ + using type = integer_sequence; +}; + +} // namespace utility_internal + +// Compile-time sequences of integers + +// make_integer_sequence +// +// This template alias is equivalent to +// `integer_sequence`, and is designed to be a drop-in +// replacement for C++14's `std::make_integer_sequence`. +template +using make_integer_sequence = typename utility_internal::Gen::type; + +// make_index_sequence +// +// This template alias is equivalent to `index_sequence<0, 1, ..., N-1>`, +// and is designed to be a drop-in replacement for C++14's +// `std::make_index_sequence`. +template +using make_index_sequence = make_integer_sequence; + +// index_sequence_for +// +// Converts a typename pack into an index sequence of the same length, and +// is designed to be a drop-in replacement for C++14's +// `std::index_sequence_for()` +template +using index_sequence_for = make_index_sequence; + +//// END OF CODE FROM GOOGLE ABSEIL + +#endif + +// dispatch utility (taken from ranges-v3) +template struct priority_tag : priority_tag < N - 1 > {}; +template<> struct priority_tag<0> {}; + +// taken from ranges-v3 +template +struct static_const +{ + static JSON_INLINE_VARIABLE constexpr T value{}; +}; + +#ifndef JSON_HAS_CPP_17 + template + constexpr T static_const::value; +#endif + +template +constexpr std::array make_array(Args&& ... args) +{ + return std::array {{static_cast(std::forward(args))...}}; +} + +} // namespace detail +NLOHMANN_JSON_NAMESPACE_END + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include // numeric_limits +#include // char_traits +#include // tuple +#include // false_type, is_constructible, is_integral, is_same, true_type +#include // declval + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +#include // random_access_iterator_tag + +// #include + +// #include + +// #include + + +NLOHMANN_JSON_NAMESPACE_BEGIN +namespace detail +{ + +template +struct iterator_types {}; + +template +struct iterator_types < + It, + void_t> +{ + using difference_type = typename It::difference_type; + using value_type = typename It::value_type; + using pointer = typename It::pointer; + using reference = typename It::reference; + using iterator_category = typename It::iterator_category; +}; + +// This is required as some compilers implement std::iterator_traits in a way that +// doesn't work with SFINAE. See https://github.com/nlohmann/json/issues/1341. +template +struct iterator_traits +{ +}; + +template +struct iterator_traits < T, enable_if_t < !std::is_pointer::value >> + : iterator_types +{ +}; + +template +struct iterator_traits::value>> +{ + using iterator_category = std::random_access_iterator_tag; + using value_type = T; + using difference_type = ptrdiff_t; + using pointer = T*; + using reference = T&; +}; + +} // namespace detail +NLOHMANN_JSON_NAMESPACE_END + +// #include + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +// #include + + +NLOHMANN_JSON_NAMESPACE_BEGIN + +NLOHMANN_CAN_CALL_STD_FUNC_IMPL(begin); + +NLOHMANN_JSON_NAMESPACE_END + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + + + +// #include + + +NLOHMANN_JSON_NAMESPACE_BEGIN + +NLOHMANN_CAN_CALL_STD_FUNC_IMPL(end); + +NLOHMANN_JSON_NAMESPACE_END + +// #include + +// #include + +// #include +// __ _____ _____ _____ +// __| | __| | | | JSON for Modern C++ +// | | |__ | | | | | | version 3.12.0 +// |_____|_____|_____|_|___| https://github.com/nlohmann/json +// +// SPDX-FileCopyrightText: 2013 - 2025 Niels Lohmann +// SPDX-License-Identifier: MIT + +#ifndef INCLUDE_NLOHMANN_JSON_FWD_HPP_ + #define INCLUDE_NLOHMANN_JSON_FWD_HPP_ + + #include // int64_t, uint64_t + #include // map + #include // allocator + #include // string + #include // vector + + // #include + + + /*! + @brief namespace for Niels Lohmann + @see https://github.com/nlohmann + @since version 1.0.0 + */ + NLOHMANN_JSON_NAMESPACE_BEGIN + + /*! + @brief default JSONSerializer template argument + + This serializer ignores the template arguments and uses ADL + ([argument-dependent lookup](https://en.cppreference.com/w/cpp/language/adl)) + for serialization. + */ + template + struct adl_serializer; + + /// a class to store JSON values + /// @sa https://json.nlohmann.me/api/basic_json/ + template class ObjectType = + std::map, + template class ArrayType = std::vector, + class StringType = std::string, class BooleanType = bool, + class NumberIntegerType = std::int64_t, + class NumberUnsignedType = std::uint64_t, + class NumberFloatType = double, + template class AllocatorType = std::allocator, + template class JSONSerializer = + adl_serializer, + class BinaryType = std::vector, // cppcheck-suppress syntaxError + class CustomBaseClass = void> + class basic_json; + + /// @brief JSON Pointer defines a string syntax for identifying a specific value within a JSON document + /// @sa https://json.nlohmann.me/api/json_pointer/ + template + class json_pointer; + + /*! + @brief default specialization + @sa https://json.nlohmann.me/api/json/ + */ + using json = basic_json<>; + + /// @brief a minimal map-like container that preserves insertion order + /// @sa https://json.nlohmann.me/api/ordered_map/ + template + struct ordered_map; + + /// @brief specialization that maintains the insertion order of object keys + /// @sa https://json.nlohmann.me/api/ordered_json/ + using ordered_json = basic_json; + + NLOHMANN_JSON_NAMESPACE_END + +#endif // INCLUDE_NLOHMANN_JSON_FWD_HPP_ + + +NLOHMANN_JSON_NAMESPACE_BEGIN +/*! +@brief detail namespace with internal helper functions + +This namespace collects functions that should not be exposed, +implementations of some @ref basic_json methods, and meta-programming helpers. + +@since version 2.1.0 +*/ +namespace detail +{ + +///////////// +// helpers // +///////////// + +// Note to maintainers: +// +// Every trait in this file expects a non CV-qualified type. +// The only exceptions are in the 'aliases for detected' section +// (i.e. those of the form: decltype(T::member_function(std::declval()))) +// +// In this case, T has to be properly CV-qualified to constraint the function arguments +// (e.g. to_json(BasicJsonType&, const T&)) + +template struct is_basic_json : std::false_type {}; + +NLOHMANN_BASIC_JSON_TPL_DECLARATION +struct is_basic_json : std::true_type {}; + +// used by exceptions create() member functions +// true_type for pointer to possibly cv-qualified basic_json or std::nullptr_t +// false_type otherwise +template +struct is_basic_json_context : + std::integral_constant < bool, + is_basic_json::type>::type>::value + || std::is_same::value > +{}; + +////////////////////// +// json_ref helpers // +////////////////////// + +template +class json_ref; + +template +struct is_json_ref : std::false_type {}; + +template +struct is_json_ref> : std::true_type {}; + +////////////////////////// +// aliases for detected // +////////////////////////// + +template +using mapped_type_t = typename T::mapped_type; + +template +using key_type_t = typename T::key_type; + +template +using value_type_t = typename T::value_type; + +template +using difference_type_t = typename T::difference_type; + +template +using pointer_t = typename T::pointer; + +template +using reference_t = typename T::reference; + +template +using iterator_category_t = typename T::iterator_category; + +template +using to_json_function = decltype(T::to_json(std::declval()...)); + +template +using from_json_function = decltype(T::from_json(std::declval()...)); + +template +using get_template_function = decltype(std::declval().template get()); + +// trait checking if JSONSerializer::from_json(json const&, udt&) exists +template +struct has_from_json : std::false_type {}; + +// trait checking if j.get is valid +// use this trait instead of std::is_constructible or std::is_convertible, +// both rely on, or make use of implicit conversions, and thus fail when T +// has several constructors/operator= (see https://github.com/nlohmann/json/issues/958) +template +struct is_getable +{ + static constexpr bool value = is_detected::value; +}; + +template +struct has_from_json < BasicJsonType, T, enable_if_t < !is_basic_json::value >> +{ + using serializer = typename BasicJsonType::template json_serializer; + + static constexpr bool value = + is_detected_exact::value; +}; + +// This trait checks if JSONSerializer::from_json(json const&) exists +// this overload is used for non-default-constructible user-defined-types +template +struct has_non_default_from_json : std::false_type {}; + +template +struct has_non_default_from_json < BasicJsonType, T, enable_if_t < !is_basic_json::value >> +{ + using serializer = typename BasicJsonType::template json_serializer; + + static constexpr bool value = + is_detected_exact::value; +}; + +// This trait checks if BasicJsonType::json_serializer::to_json exists +// Do not evaluate the trait when T is a basic_json type, to avoid template instantiation infinite recursion. +template +struct has_to_json : std::false_type {}; + +template +struct has_to_json < BasicJsonType, T, enable_if_t < !is_basic_json::value >> +{ + using serializer = typename BasicJsonType::template json_serializer; + + static constexpr bool value = + is_detected_exact::value; +}; + +template +using detect_key_compare = typename T::key_compare; + +template +struct has_key_compare : std::integral_constant::value> {}; + +// obtains the actual object key comparator +template +struct actual_object_comparator +{ + using object_t = typename BasicJsonType::object_t; + using object_comparator_t = typename BasicJsonType::default_object_comparator_t; + using type = typename std::conditional < has_key_compare::value, + typename object_t::key_compare, object_comparator_t>::type; +}; + +template +using actual_object_comparator_t = typename actual_object_comparator::type; + +///////////////// +// char_traits // +///////////////// + +// Primary template of char_traits calls std char_traits +template +struct char_traits : std::char_traits +{}; + +// Explicitly define char traits for unsigned char since it is not standard +template<> +struct char_traits : std::char_traits +{ + using char_type = unsigned char; + using int_type = uint64_t; + + // Redefine to_int_type function + static int_type to_int_type(char_type c) noexcept + { + return static_cast(c); + } + + static char_type to_char_type(int_type i) noexcept + { + return static_cast(i); + } + + static constexpr int_type eof() noexcept + { + return static_cast(std::char_traits::eof()); + } +}; + +// Explicitly define char traits for signed char since it is not standard +template<> +struct char_traits : std::char_traits +{ + using char_type = signed char; + using int_type = uint64_t; + + // Redefine to_int_type function + static int_type to_int_type(char_type c) noexcept + { + return static_cast(c); + } + + static char_type to_char_type(int_type i) noexcept + { + return static_cast(i); + } + + static constexpr int_type eof() noexcept + { + return static_cast(std::char_traits::eof()); + } +}; + +/////////////////// +// is_ functions // +/////////////////// + +// https://en.cppreference.com/w/cpp/types/conjunction +template struct conjunction : std::true_type { }; +template struct conjunction : B { }; +template +struct conjunction +: std::conditional(B::value), conjunction, B>::type {}; + +// https://en.cppreference.com/w/cpp/types/negation +template struct negation : std::integral_constant < bool, !B::value > { }; + +// Reimplementation of is_constructible and is_default_constructible, due to them being broken for +// std::pair and std::tuple until LWG 2367 fix (see https://cplusplus.github.io/LWG/lwg-defects.html#2367). +// This causes compile errors in e.g. clang 3.5 or gcc 4.9. +template +struct is_default_constructible : std::is_default_constructible {}; + +template +struct is_default_constructible> + : conjunction, is_default_constructible> {}; + +template +struct is_default_constructible> + : conjunction, is_default_constructible> {}; + +template +struct is_default_constructible> + : conjunction...> {}; + +template +struct is_default_constructible> + : conjunction...> {}; + +template +struct is_constructible : std::is_constructible {}; + +template +struct is_constructible> : is_default_constructible> {}; + +template +struct is_constructible> : is_default_constructible> {}; + +template +struct is_constructible> : is_default_constructible> {}; + +template +struct is_constructible> : is_default_constructible> {}; + +template +struct is_iterator_traits : std::false_type {}; + +template +struct is_iterator_traits> +{ + private: + using traits = iterator_traits; + + public: + static constexpr auto value = + is_detected::value && + is_detected::value && + is_detected::value && + is_detected::value && + is_detected::value; +}; + +template +struct is_range +{ + private: + using t_ref = typename std::add_lvalue_reference::type; + + using iterator = detected_t; + using sentinel = detected_t; + + // to be 100% correct, it should use https://en.cppreference.com/w/cpp/iterator/input_or_output_iterator + // and https://en.cppreference.com/w/cpp/iterator/sentinel_for + // but reimplementing these would be too much work, as a lot of other concepts are used underneath + static constexpr auto is_iterator_begin = + is_iterator_traits>::value; + + public: + static constexpr bool value = !std::is_same::value && !std::is_same::value && is_iterator_begin; +}; + +template +using iterator_t = enable_if_t::value, result_of_begin())>>; + +template +using range_value_t = value_type_t>>; + +// The following implementation of is_complete_type is taken from +// https://blogs.msdn.microsoft.com/vcblog/2015/12/02/partial-support-for-expression-sfinae-in-vs-2015-update-1/ +// and is written by Xiang Fan who agreed to using it in this library. + +template +struct is_complete_type : std::false_type {}; + +template +struct is_complete_type : std::true_type {}; + +template +struct is_compatible_object_type_impl : std::false_type {}; + +template +struct is_compatible_object_type_impl < + BasicJsonType, CompatibleObjectType, + enable_if_t < is_detected::value&& + is_detected::value >> +{ + using object_t = typename BasicJsonType::object_t; + + // macOS's is_constructible does not play well with nonesuch... + static constexpr bool value = + is_constructible::value && + is_constructible::value; +}; + +template +struct is_compatible_object_type + : is_compatible_object_type_impl {}; + +template +struct is_constructible_object_type_impl : std::false_type {}; + +template +struct is_constructible_object_type_impl < + BasicJsonType, ConstructibleObjectType, + enable_if_t < is_detected::value&& + is_detected::value >> +{ + using object_t = typename BasicJsonType::object_t; + + static constexpr bool value = + (is_default_constructible::value && + (std::is_move_assignable::value || + std::is_copy_assignable::value) && + (is_constructible::value && + std::is_same < + typename object_t::mapped_type, + typename ConstructibleObjectType::mapped_type >::value)) || + (has_from_json::value || + has_non_default_from_json < + BasicJsonType, + typename ConstructibleObjectType::mapped_type >::value); +}; + +template +struct is_constructible_object_type + : is_constructible_object_type_impl {}; + +template +struct is_compatible_string_type +{ + static constexpr auto value = + is_constructible::value; +}; + +template +struct is_constructible_string_type +{ + // launder type through decltype() to fix compilation failure on ICPC +#ifdef __INTEL_COMPILER + using laundered_type = decltype(std::declval()); +#else + using laundered_type = ConstructibleStringType; +#endif + + static constexpr auto value = + conjunction < + is_constructible, + is_detected_exact>::value; +}; + +template +struct is_compatible_array_type_impl : std::false_type {}; + +template +struct is_compatible_array_type_impl < + BasicJsonType, CompatibleArrayType, + enable_if_t < + is_detected::value&& + is_iterator_traits>>::value&& +// special case for types like std::filesystem::path whose iterator's value_type are themselves +// c.f. https://github.com/nlohmann/json/pull/3073 + !std::is_same>::value >> +{ + static constexpr bool value = + is_constructible>::value; +}; + +template +struct is_compatible_array_type + : is_compatible_array_type_impl {}; + +template +struct is_constructible_array_type_impl : std::false_type {}; + +template +struct is_constructible_array_type_impl < + BasicJsonType, ConstructibleArrayType, + enable_if_t::value >> + : std::true_type {}; + +template +struct is_constructible_array_type_impl < + BasicJsonType, ConstructibleArrayType, + enable_if_t < !std::is_same::value&& + !is_compatible_string_type::value&& + is_default_constructible::value&& +(std::is_move_assignable::value || + std::is_copy_assignable::value)&& +is_detected::value&& +is_iterator_traits>>::value&& +is_detected::value&& +// special case for types like std::filesystem::path whose iterator's value_type are themselves +// c.f. https://github.com/nlohmann/json/pull/3073 +!std::is_same>::value&& +is_complete_type < +detected_t>::value >> +{ + using value_type = range_value_t; + + static constexpr bool value = + std::is_same::value || + has_from_json::value || + has_non_default_from_json < + BasicJsonType, + value_type >::value; +}; + +template +struct is_constructible_array_type + : is_constructible_array_type_impl {}; + +template +struct is_compatible_integer_type_impl : std::false_type {}; + +template +struct is_compatible_integer_type_impl < + RealIntegerType, CompatibleNumberIntegerType, + enable_if_t < std::is_integral::value&& + std::is_integral::value&& + !std::is_same::value >> +{ + // is there an assert somewhere on overflows? + using RealLimits = std::numeric_limits; + using CompatibleLimits = std::numeric_limits; + + static constexpr auto value = + is_constructible::value && + CompatibleLimits::is_integer && + RealLimits::is_signed == CompatibleLimits::is_signed; +}; + +template +struct is_compatible_integer_type + : is_compatible_integer_type_impl {}; + +template +struct is_compatible_type_impl: std::false_type {}; + +template +struct is_compatible_type_impl < + BasicJsonType, CompatibleType, + enable_if_t::value >> +{ + static constexpr bool value = + has_to_json::value; +}; + +template +struct is_compatible_type + : is_compatible_type_impl {}; + +template +struct is_constructible_tuple : std::false_type {}; + +template +struct is_constructible_tuple> : conjunction...> {}; + +template +struct is_json_iterator_of : std::false_type {}; + +template +struct is_json_iterator_of : std::true_type {}; + +template +struct is_json_iterator_of : std::true_type +{}; + +// checks if a given type T is a template specialization of Primary +template