From 8b8b634f65834a1d26e2ffc0f7c421b17429b44a Mon Sep 17 00:00:00 2001 From: Thad House Date: Thu, 7 Nov 2024 22:42:50 -0800 Subject: [PATCH] [wpiutil] Change C++ protobuf to nanopb (#7309) The Google C++ protobuf implementation has issues with dynamic linkage across DLL boundaries because it uses global variables. It also has a compile-time dependency because the protoc version must exactly match the libprotobuf version. Using nanopb with a customized generator fixes both of these issues. Co-authored-by: Gold856 <117957790+Gold856@users.noreply.github.com> --- .github/workflows/pregen_all.py | 14 + .github/workflows/pregenerate.yml | 4 +- .gitignore | 2 + shared/java/javacommon.gradle | 7 + upstream_utils/nanopb.py | 76 + ...imported-files-as-modified-by-WPILib.patch | 909 ++++++ .../nanopb_patches/0002-Remove-extern-C.patch | 188 ++ ...s-or-anything-non-static-as-callback.patch | 28 + ...e-as-cpp-and-add-wpilib-requirements.patch | 170 + wpimath/.styleguide | 1 + wpimath/CMakeLists.txt | 76 +- wpimath/build.gradle | 18 +- wpimath/generate_nanopb.py | 88 + .../cpp/wpimath/protobuf/controller.npb.cpp | 245 ++ .../cpp/wpimath/protobuf/controller.npb.h | 158 + .../cpp/wpimath/protobuf/geometry2d.npb.cpp | 256 ++ .../cpp/wpimath/protobuf/geometry2d.npb.h | 180 ++ .../cpp/wpimath/protobuf/geometry3d.npb.cpp | 249 ++ .../cpp/wpimath/protobuf/geometry3d.npb.h | 171 + .../cpp/wpimath/protobuf/kinematics.npb.cpp | 434 +++ .../cpp/wpimath/protobuf/kinematics.npb.h | 277 ++ .../native/cpp/wpimath/protobuf/plant.npb.cpp | 93 + .../native/cpp/wpimath/protobuf/plant.npb.h | 57 + .../cpp/wpimath/protobuf/spline.npb.cpp | 137 + .../native/cpp/wpimath/protobuf/spline.npb.h | 79 + .../cpp/wpimath/protobuf/system.npb.cpp | 107 + .../native/cpp/wpimath/protobuf/system.npb.h | 67 + .../cpp/wpimath/protobuf/trajectory.npb.cpp | 118 + .../cpp/wpimath/protobuf/trajectory.npb.h | 76 + .../cpp/wpimath/protobuf/wpimath.npb.cpp | 92 + .../native/cpp/wpimath/protobuf/wpimath.npb.h | 67 + .../controller/proto/ArmFeedforwardProto.cpp | 42 +- .../DifferentialDriveFeedforwardProto.cpp | 47 +- .../DifferentialDriveWheelVoltagesProto.cpp | 39 +- .../proto/ElevatorFeedforwardProto.cpp | 42 +- .../cpp/geometry/proto/Ellipse2dProto.cpp | 47 +- .../native/cpp/geometry/proto/Pose2dProto.cpp | 45 +- .../native/cpp/geometry/proto/Pose3dProto.cpp | 47 +- .../cpp/geometry/proto/QuaternionProto.cpp | 39 +- .../cpp/geometry/proto/Rectangle2dProto.cpp | 47 +- .../cpp/geometry/proto/Rotation2dProto.cpp | 27 +- .../cpp/geometry/proto/Rotation3dProto.cpp | 37 +- .../cpp/geometry/proto/Transform2dProto.cpp | 45 +- .../cpp/geometry/proto/Transform3dProto.cpp | 45 +- .../cpp/geometry/proto/Translation2dProto.cpp | 31 +- .../cpp/geometry/proto/Translation3dProto.cpp | 35 +- .../cpp/geometry/proto/Twist2dProto.cpp | 35 +- .../cpp/geometry/proto/Twist3dProto.cpp | 40 +- .../kinematics/proto/ChassisSpeedsProto.cpp | 35 +- .../DifferentialDriveKinematicsProto.cpp | 33 +- .../DifferentialDriveWheelPositionsProto.cpp | 39 +- .../DifferentialDriveWheelSpeedsProto.cpp | 37 +- .../proto/MecanumDriveKinematicsProto.cpp | 64 +- .../proto/MecanumDriveWheelPositionsProto.cpp | 45 +- .../proto/MecanumDriveWheelSpeedsProto.cpp | 43 +- .../proto/SwerveModulePositionProto.cpp | 44 +- .../proto/SwerveModuleStateProto.cpp | 44 +- .../spline/proto/CubicHermiteSplineProto.cpp | 62 +- .../proto/QuinticHermiteSplineProto.cpp | 62 +- .../cpp/system/plant/proto/DCMotorProto.cpp | 43 +- .../cpp/trajectory/proto/TrajectoryProto.cpp | 39 +- .../trajectory/proto/TrajectoryStateProto.cpp | 57 +- .../controller/proto/ArmFeedforwardProto.h | 11 +- .../proto/DifferentialDriveFeedforwardProto.h | 13 +- .../DifferentialDriveWheelVoltagesProto.h | 14 +- .../proto/ElevatorFeedforwardProto.h | 11 +- .../proto/SimpleMotorFeedforwardProto.h | 66 +- .../frc/geometry/proto/Ellipse2dProto.h | 9 +- .../include/frc/geometry/proto/Pose2dProto.h | 10 +- .../include/frc/geometry/proto/Pose3dProto.h | 9 +- .../frc/geometry/proto/QuaternionProto.h | 10 +- .../frc/geometry/proto/Rectangle2dProto.h | 10 +- .../frc/geometry/proto/Rotation2dProto.h | 11 +- .../frc/geometry/proto/Rotation3dProto.h | 10 +- .../frc/geometry/proto/Transform2dProto.h | 10 +- .../frc/geometry/proto/Transform3dProto.h | 10 +- .../frc/geometry/proto/Translation2dProto.h | 11 +- .../frc/geometry/proto/Translation3dProto.h | 10 +- .../include/frc/geometry/proto/Twist2dProto.h | 9 +- .../include/frc/geometry/proto/Twist3dProto.h | 9 +- .../include/frc/kinematics/Kinematics.h | 2 + .../frc/kinematics/SwerveDriveKinematics.h | 2 +- .../frc/kinematics/proto/ChassisSpeedsProto.h | 10 +- .../proto/DifferentialDriveKinematicsProto.h | 11 +- .../DifferentialDriveWheelPositionsProto.h | 13 +- .../proto/DifferentialDriveWheelSpeedsProto.h | 12 +- .../proto/MecanumDriveKinematicsProto.h | 10 +- .../proto/MecanumDriveWheelPositionsProto.h | 11 +- .../proto/MecanumDriveWheelSpeedsProto.h | 11 +- .../proto/SwerveDriveKinematicsProto.h | 44 +- .../proto/SwerveModulePositionProto.h | 9 +- .../kinematics/proto/SwerveModuleStateProto.h | 10 +- .../native/include/frc/proto/MatrixProto.h | 71 +- .../native/include/frc/proto/VectorProto.h | 63 +- .../spline/proto/CubicHermiteSplineProto.h | 10 +- .../spline/proto/QuinticHermiteSplineProto.h | 9 +- .../frc/system/plant/proto/DCMotorProto.h | 9 +- .../frc/system/proto/LinearSystemProto.h | 92 +- .../frc/trajectory/proto/TrajectoryProto.h | 10 +- .../trajectory/proto/TrajectoryStateProto.h | 10 +- wpimath/src/test/native/cpp/ProtoTestBase.h | 45 +- .../proto/ArmFeedforwardProtoTest.cpp | 22 +- ...ifferentialDriveWheelVoltagesProtoTest.cpp | 15 +- .../proto/ElevatorFeedforwardProtoTest.cpp | 22 +- .../cpp/geometry/proto/Ellipse2dProtoTest.cpp | 20 +- .../cpp/geometry/proto/Pose2dProtoTest.cpp | 18 +- .../cpp/geometry/proto/Pose3dProtoTest.cpp | 18 +- .../geometry/proto/QuaternionProtoTest.cpp | 22 +- .../geometry/proto/Rectangle2dProtoTest.cpp | 20 +- .../geometry/proto/Rotation2dProtoTest.cpp | 15 +- .../geometry/proto/Rotation3dProtoTest.cpp | 16 +- .../geometry/proto/Transform2dProtoTest.cpp | 18 +- .../geometry/proto/Transform3dProtoTest.cpp | 18 +- .../geometry/proto/Translation2dProtoTest.cpp | 17 +- .../geometry/proto/Translation3dProtoTest.cpp | 20 +- .../cpp/geometry/proto/Twist2dProtoTest.cpp | 20 +- .../cpp/geometry/proto/Twist3dProtoTest.cpp | 26 +- .../proto/ChassisSpeedsProtoTest.cpp | 20 +- .../DifferentialDriveKinematicsProtoTest.cpp | 16 +- .../DifferentialDriveWheelSpeedsProtoTest.cpp | 18 +- .../proto/MecanumDriveKinematicsProtoTest.cpp | 22 +- .../MecanumDriveWheelPositionsProtoTest.cpp | 23 +- .../MecanumDriveWheelSpeedsProtoTest.cpp | 23 +- .../proto/SwerveModulePositionProtoTest.cpp | 18 +- .../proto/SwerveModuleStateProtoTest.cpp | 18 +- .../system/plant/proto/DCMotorProtoTest.cpp | 28 +- .../trajectory/proto/TrajectoryProtoTest.cpp | 13 +- .../proto/TrajectoryStateProtoTest.cpp | 22 +- wpiutil/.styleguide | 1 + wpiutil/BUILD.bazel | 33 +- wpiutil/CMakeLists.txt | 6 + wpiutil/build.gradle | 44 +- wpiutil/generate_nanopb.py | 88 + .../generated/test/native/cpp/wpiutil.npb.cpp | 584 ++++ .../generated/test/native/cpp/wpiutil.npb.h | 246 ++ .../src/main/native/cpp/protobuf/Protobuf.cpp | 200 +- .../native/include/wpi/protobuf/Protobuf.h | 453 +-- .../include/wpi/protobuf/ProtobufCallbacks.h | 670 ++++ .../thirdparty/nanopb/generator/__init__.py | 0 .../nanopb/generator/nanopb_generator | 7 + .../nanopb/generator/nanopb_generator.bat | 5 + .../nanopb/generator/nanopb_generator.py | 2780 +++++++++++++++++ .../nanopb/generator/nanopb_generator.py2 | 13 + .../nanopb/generator/platformio_generator.py | 157 + .../nanopb/generator/proto/Makefile | 10 + .../nanopb/generator/proto/__init__.py | 126 + .../nanopb/generator/proto/_utils.py | 104 + .../proto/google/protobuf/descriptor.proto | 1293 ++++++++ .../nanopb/generator/proto/nanopb.proto | 213 ++ .../native/thirdparty/nanopb/generator/protoc | 45 + .../nanopb/generator/protoc-gen-nanopb | 11 + .../nanopb/generator/protoc-gen-nanopb-py2 | 16 + .../nanopb/generator/protoc-gen-nanopb.bat | 12 + .../thirdparty/nanopb/generator/protoc.bat | 9 + .../native/thirdparty/nanopb/include/pb.h | 931 ++++++ .../thirdparty/nanopb/include/pb_common.h | 42 + .../thirdparty/nanopb/include/pb_decode.h | 198 ++ .../thirdparty/nanopb/include/pb_encode.h | 189 ++ .../thirdparty/nanopb/src/pb_common.cpp | 389 +++ .../thirdparty/nanopb/src/pb_decode.cpp | 1730 ++++++++++ .../thirdparty/nanopb/src/pb_encode.cpp | 1003 ++++++ .../src/test/native/cpp/proto/TestProto.cpp | 125 + .../test/native/cpp/proto/TestProtoInner.cpp | 70 + .../test/native/cpp/proto/TestProtoInner.h | 24 + .../native/cpp/proto/TestProtoRepeated.cpp | 186 ++ wpiutil/src/test/proto/wpiutil.proto | 64 + 166 files changed, 17522 insertions(+), 1571 deletions(-) create mode 100755 upstream_utils/nanopb.py create mode 100644 upstream_utils/nanopb_patches/0001-Marked-imported-files-as-modified-by-WPILib.patch create mode 100644 upstream_utils/nanopb_patches/0002-Remove-extern-C.patch create mode 100644 upstream_utils/nanopb_patches/0003-Generate-messages-or-anything-non-static-as-callback.patch create mode 100644 upstream_utils/nanopb_patches/0004-Generate-as-cpp-and-add-wpilib-requirements.patch create mode 100755 wpimath/generate_nanopb.py create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/controller.npb.cpp create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/controller.npb.h create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry2d.npb.cpp create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry2d.npb.h create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry3d.npb.cpp create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry3d.npb.h create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.cpp create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.h create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/plant.npb.cpp create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/plant.npb.h create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/spline.npb.cpp create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/spline.npb.h create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/system.npb.cpp create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/system.npb.h create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/trajectory.npb.cpp create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/trajectory.npb.h create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/wpimath.npb.cpp create mode 100644 wpimath/src/generated/main/native/cpp/wpimath/protobuf/wpimath.npb.h create mode 100755 wpiutil/generate_nanopb.py create mode 100644 wpiutil/src/generated/test/native/cpp/wpiutil.npb.cpp create mode 100644 wpiutil/src/generated/test/native/cpp/wpiutil.npb.h create mode 100644 wpiutil/src/main/native/include/wpi/protobuf/ProtobufCallbacks.h create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/__init__.py create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator.bat create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator.py create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator.py2 create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/platformio_generator.py create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/proto/Makefile create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/proto/__init__.py create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/proto/_utils.py create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/proto/google/protobuf/descriptor.proto create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/proto/nanopb.proto create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/protoc create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/protoc-gen-nanopb create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/protoc-gen-nanopb-py2 create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/protoc-gen-nanopb.bat create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/generator/protoc.bat create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/include/pb.h create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/include/pb_common.h create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/include/pb_decode.h create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/include/pb_encode.h create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/src/pb_common.cpp create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/src/pb_decode.cpp create mode 100644 wpiutil/src/main/native/thirdparty/nanopb/src/pb_encode.cpp create mode 100644 wpiutil/src/test/native/cpp/proto/TestProto.cpp create mode 100644 wpiutil/src/test/native/cpp/proto/TestProtoInner.cpp create mode 100644 wpiutil/src/test/native/cpp/proto/TestProtoInner.h create mode 100644 wpiutil/src/test/native/cpp/proto/TestProtoRepeated.cpp create mode 100644 wpiutil/src/test/proto/wpiutil.proto diff --git a/.github/workflows/pregen_all.py b/.github/workflows/pregen_all.py index 0c15084c79..278e5c84cd 100755 --- a/.github/workflows/pregen_all.py +++ b/.github/workflows/pregen_all.py @@ -33,6 +33,13 @@ def main(): ], check=True, ) + subprocess.run( + [ + sys.executable, + f"{REPO_ROOT}/wpimath/generate_nanopb.py", + ], + check=True, + ) subprocess.run( [sys.executable, f"{REPO_ROOT}/wpiunits/generate_units.py"], check=True ) @@ -53,6 +60,13 @@ def main(): [sys.executable, f"{REPO_ROOT}/wpilibj/generate_pwm_motor_controllers.py"], check=True, ) + subprocess.run( + [ + sys.executable, + f"{REPO_ROOT}/wpiutil/generate_nanopb.py", + ], + check=True, + ) subprocess.run( [sys.executable, f"{REPO_ROOT}/thirdparty/imgui_suite/generate_gl3w.py"], check=True, diff --git a/.github/workflows/pregenerate.yml b/.github/workflows/pregenerate.yml index db17ce371c..12e09da6a5 100644 --- a/.github/workflows/pregenerate.yml +++ b/.github/workflows/pregenerate.yml @@ -22,8 +22,8 @@ jobs: uses: actions/setup-python@v5 with: python-version: '3.12' - - name: Install jinja - run: python -m pip install jinja2 + - name: Install jinja and protobuf + run: python -m pip install jinja2 protobuf grpcio-tools - name: Install protobuf dependencies run: sudo apt-get update && sudo apt-get install -y protobuf-compiler && wget https://github.com/HebiRobotics/QuickBuffers/releases/download/1.3.3/protoc-gen-quickbuf-1.3.3-linux-x86_64.exe && chmod +x protoc-gen-quickbuf-1.3.3-linux-x86_64.exe - name: Regenerate all diff --git a/.gitignore b/.gitignore index ff4b8ff226..43455125a4 100644 --- a/.gitignore +++ b/.gitignore @@ -15,6 +15,8 @@ networktables.json ntcore/connectionlistenertest.json ntcore/timesynctest.json +nanopb_pb2.py + # Created by the jenkins test script test-reports diff --git a/shared/java/javacommon.gradle b/shared/java/javacommon.gradle index 48e67e8d73..e1f81ecce2 100644 --- a/shared/java/javacommon.gradle +++ b/shared/java/javacommon.gradle @@ -155,6 +155,13 @@ protobuf { } generateProtoTasks { all().configureEach { task -> + if (project.hasProperty('skipproto')) { + task.builtins { + cpp {} + remove java + } + return + } task.inputs.file(rootProject.file("protoplugin/binary/wpiprotoplugin.jar")) task.plugins { wpilib { diff --git a/upstream_utils/nanopb.py b/upstream_utils/nanopb.py new file mode 100755 index 0000000000..1da46a8c19 --- /dev/null +++ b/upstream_utils/nanopb.py @@ -0,0 +1,76 @@ +#!/usr/bin/env python3 + +import os +import shutil + +from upstream_utils import Lib, copy_to, walk_if + +nanopb_sources = set( + [ + "pb_encode.c", + "pb_decode.c", + "pb_common.c", + ] +) + +nanopb_headers = set( + [ + "pb.h", + "pb_encode.h", + "pb_decode.h", + "pb_common.h", + ] +) + +nanopb_generator = set( + [ + "pb.h", + "pb_encode.h", + "pb_decode.h", + "pb_common.h", + ] +) + + +def copy_upstream_src(wpilib_root): + wpiutil = os.path.join(wpilib_root, "wpiutil") + + # Delete old install + for d in [ + "src/main/native/thirdparty/nanopb/src", + "src/main/native/thirdparty/nanopb/include", + "src/main/native/thirdparty/nanopb/generator", + ]: + shutil.rmtree(os.path.join(wpiutil, d), ignore_errors=True) + + # Copy nanopb source files into allwpilib + copy_to( + nanopb_sources, + os.path.join(wpiutil, "src/main/native/thirdparty/nanopb/src"), + rename_c_to_cpp=True, + ) + + # Copy nanopb header files into allwpilib + copy_to( + nanopb_headers, + os.path.join(wpiutil, "src/main/native/thirdparty/nanopb/include"), + ) + + generator_files = walk_if("generator", lambda dp, f: True) + copy_to( + generator_files, + os.path.join(wpiutil, "src/main/native/thirdparty/nanopb"), + ) + + +def main(): + name = "nanopb" + url = "https://github.com/nanopb/nanopb" + tag = "0.4.9" + + nanopb = Lib(name, url, tag, copy_upstream_src) + nanopb.main() + + +if __name__ == "__main__": + main() diff --git a/upstream_utils/nanopb_patches/0001-Marked-imported-files-as-modified-by-WPILib.patch b/upstream_utils/nanopb_patches/0001-Marked-imported-files-as-modified-by-WPILib.patch new file mode 100644 index 0000000000..3babd005ee --- /dev/null +++ b/upstream_utils/nanopb_patches/0001-Marked-imported-files-as-modified-by-WPILib.patch @@ -0,0 +1,909 @@ +From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 +From: Thad House +Date: Mon, 28 Oct 2024 17:38:55 -0700 +Subject: [PATCH 1/4] Marked imported files as modified by WPILib + +--- + generator/nanopb_generator.py | 2 + + pb.h | 2 + + pb_common.c | 3 +- + pb_common.h | 2 + + pb_decode.c | 144 +++++++++++++++++----------------- + pb_decode.h | 2 + + pb_encode.c | 80 ++++++++++--------- + pb_encode.h | 2 + + 8 files changed, 126 insertions(+), 111 deletions(-) + +diff --git a/generator/nanopb_generator.py b/generator/nanopb_generator.py +index 6068042b59da04842ff13d4d56dfc35366003a5f..735e4b7b31cdb66a1cdfbd2da6ae8fcde5986147 100755 +--- a/generator/nanopb_generator.py ++++ b/generator/nanopb_generator.py +@@ -1,6 +1,8 @@ + #!/usr/bin/env python3 + # kate: replace-tabs on; indent-width 4; + ++# Modified for WPILib use ++ + from __future__ import unicode_literals + + '''Generate header file for nanopb from a ProtoBuf FileDescriptorSet.''' +diff --git a/pb.h b/pb.h +index 1bff70e4e6fbf029e3d6140f5ffd812b9bc7d12e..cec078fe40d526712eda771db077ebf31c95e076 100644 +--- a/pb.h ++++ b/pb.h +@@ -1,5 +1,7 @@ + /* Common parts of the nanopb library. Most of these are quite low-level + * stuff. For the high-level interface, see pb_encode.h and pb_decode.h. ++ * ++ * Modified for WPILib Use + */ + + #ifndef PB_H_INCLUDED +diff --git a/pb_common.c b/pb_common.c +index 6aee76b1efa1e6f2f3fe7d43629da9b2114eea19..73698dd7c5b64f122f00a3a3dd8312b6d0e72557 100644 +--- a/pb_common.c ++++ b/pb_common.c +@@ -1,4 +1,6 @@ + /* pb_common.c: Common support functions for pb_encode.c and pb_decode.c. ++ * ++ * Modified for WPILib Use + * + * 2014 Petteri Aimonen + */ +@@ -385,4 +387,3 @@ bool pb_validate_utf8(const char *str) + } + + #endif +- +diff --git a/pb_common.h b/pb_common.h +index 58aa90f76d58596d3f45a120b65b4a0bff7fd688..d1d8bf55b13412887ab6d8fc6cfaf51348da9605 100644 +--- a/pb_common.h ++++ b/pb_common.h +@@ -1,5 +1,7 @@ + /* pb_common.h: Common support functions for pb_encode.c and pb_decode.c. + * These functions are rarely needed by applications directly. ++ * ++ * Modified for WPILib Use + */ + + #ifndef PB_COMMON_H_INCLUDED +diff --git a/pb_decode.c b/pb_decode.c +index 068306a05339af05b3b3fb80894746ed9a077bf8..03143e02a596b2f03023437e5f18e5f118580d22 100644 +--- a/pb_decode.c ++++ b/pb_decode.c +@@ -1,4 +1,6 @@ + /* pb_decode.c -- decode a protobuf using minimal resources ++ * ++ * Modified for WPILib Use + * + * 2011 Petteri Aimonen + */ +@@ -70,12 +72,12 @@ static bool checkreturn buf_read(pb_istream_t *stream, pb_byte_t *buf, size_t co + { + const pb_byte_t *source = (const pb_byte_t*)stream->state; + stream->state = (pb_byte_t*)stream->state + count; +- ++ + if (buf != NULL) + { + memcpy(buf, source, count * sizeof(pb_byte_t)); + } +- ++ + return true; + } + +@@ -93,17 +95,17 @@ bool checkreturn pb_read(pb_istream_t *stream, pb_byte_t *buf, size_t count) + { + if (!pb_read(stream, tmp, 16)) + return false; +- ++ + count -= 16; + } +- ++ + return pb_read(stream, tmp, count); + } + #endif + + if (stream->bytes_left < count) + PB_RETURN_ERROR(stream, "end-of-stream"); +- ++ + #ifndef PB_BUFFER_ONLY + if (!stream->callback(stream, buf, count)) + PB_RETURN_ERROR(stream, "io error"); +@@ -111,7 +113,7 @@ bool checkreturn pb_read(pb_istream_t *stream, pb_byte_t *buf, size_t count) + if (!buf_read(stream, buf, count)) + return false; + #endif +- ++ + if (stream->bytes_left < count) + stream->bytes_left = 0; + else +@@ -136,8 +138,8 @@ static bool checkreturn pb_readbyte(pb_istream_t *stream, pb_byte_t *buf) + #endif + + stream->bytes_left--; +- +- return true; ++ ++ return true; + } + + pb_istream_t pb_istream_from_buffer(const pb_byte_t *buf, size_t msglen) +@@ -172,7 +174,7 @@ static bool checkreturn pb_decode_varint32_eof(pb_istream_t *stream, uint32_t *d + { + pb_byte_t byte; + uint32_t result; +- ++ + if (!pb_readbyte(stream, &byte)) + { + if (stream->bytes_left == 0) +@@ -185,7 +187,7 @@ static bool checkreturn pb_decode_varint32_eof(pb_istream_t *stream, uint32_t *d + + return false; + } +- ++ + if ((byte & 0x80) == 0) + { + /* Quick case, 1 byte value */ +@@ -196,12 +198,12 @@ static bool checkreturn pb_decode_varint32_eof(pb_istream_t *stream, uint32_t *d + /* Multibyte case */ + uint_fast8_t bitpos = 7; + result = byte & 0x7F; +- ++ + do + { + if (!pb_readbyte(stream, &byte)) + return false; +- ++ + if (bitpos >= 32) + { + /* Note: The varint could have trailing 0x80 bytes, or 0xFF for negative. */ +@@ -229,7 +231,7 @@ static bool checkreturn pb_decode_varint32_eof(pb_istream_t *stream, uint32_t *d + bitpos = (uint_fast8_t)(bitpos + 7); + } while (byte & 0x80); + } +- ++ + *dest = result; + return true; + } +@@ -245,7 +247,7 @@ bool checkreturn pb_decode_varint(pb_istream_t *stream, uint64_t *dest) + pb_byte_t byte; + uint_fast8_t bitpos = 0; + uint64_t result = 0; +- ++ + do + { + if (!pb_readbyte(stream, &byte)) +@@ -257,7 +259,7 @@ bool checkreturn pb_decode_varint(pb_istream_t *stream, uint64_t *dest) + result |= (uint64_t)(byte & 0x7F) << bitpos; + bitpos = (uint_fast8_t)(bitpos + 7); + } while (byte & 0x80); +- ++ + *dest = result; + return true; + } +@@ -279,7 +281,7 @@ bool checkreturn pb_skip_string(pb_istream_t *stream) + uint32_t length; + if (!pb_decode_varint32(stream, &length)) + return false; +- ++ + if ((size_t)length != length) + { + PB_RETURN_ERROR(stream, "size too large"); +@@ -294,12 +296,12 @@ bool checkreturn pb_decode_tag(pb_istream_t *stream, pb_wire_type_t *wire_type, + *eof = false; + *wire_type = (pb_wire_type_t) 0; + *tag = 0; +- ++ + if (!pb_decode_varint32_eof(stream, &temp, eof)) + { + return false; + } +- ++ + *tag = temp >> 3; + *wire_type = (pb_wire_type_t)(temp & 7); + return true; +@@ -337,15 +339,15 @@ static bool checkreturn read_raw_value(pb_istream_t *stream, pb_wire_type_t wire + return false; + } while (*buf++ & 0x80); + return true; +- ++ + case PB_WT_64BIT: + *size = 8; + return pb_read(stream, buf, 8); +- ++ + case PB_WT_32BIT: + *size = 4; + return pb_read(stream, buf, 4); +- ++ + case PB_WT_STRING: + /* Calling read_raw_value with a PB_WT_STRING is an error. + * Explicitly handle this case and fallthrough to default to avoid +@@ -364,11 +366,11 @@ bool checkreturn pb_make_string_substream(pb_istream_t *stream, pb_istream_t *su + uint32_t size; + if (!pb_decode_varint32(stream, &size)) + return false; +- ++ + *substream = *stream; + if (substream->bytes_left < size) + PB_RETURN_ERROR(stream, "parent stream too short"); +- ++ + substream->bytes_left = (size_t)size; + stream->bytes_left -= (size_t)size; + return true; +@@ -470,12 +472,12 @@ static bool checkreturn decode_static_field(pb_istream_t *stream, pb_wire_type_t + { + case PB_HTYPE_REQUIRED: + return decode_basic_field(stream, wire_type, field); +- ++ + case PB_HTYPE_OPTIONAL: + if (field->pSize != NULL) + *(bool*)field->pSize = true; + return decode_basic_field(stream, wire_type, field); +- ++ + case PB_HTYPE_REPEATED: + if (wire_type == PB_WT_STRING + && PB_LTYPE(field->type) <= PB_LTYPE_LAST_PACKABLE) +@@ -560,12 +562,12 @@ static bool checkreturn decode_static_field(pb_istream_t *stream, pb_wire_type_t + * Zero size is not allowed, use pb_free() for releasing. + */ + static bool checkreturn allocate_field(pb_istream_t *stream, void *pData, size_t data_size, size_t array_size) +-{ ++{ + void *ptr = *(void**)pData; +- ++ + if (data_size == 0 || array_size == 0) + PB_RETURN_ERROR(stream, "invalid size"); +- ++ + #ifdef __AVR__ + /* Workaround for AVR libc bug 53284: http://savannah.nongnu.org/bugs/?53284 + * Realloc to size of 1 byte can cause corruption of the malloc structures. +@@ -592,14 +594,14 @@ static bool checkreturn allocate_field(pb_istream_t *stream, void *pData, size_t + } + } + } +- ++ + /* Allocate new or expand previous allocation */ + /* Note: on failure the old pointer will remain in the structure, + * the message must be freed by caller also on error return. */ + ptr = pb_realloc(ptr, array_size * data_size); + if (ptr == NULL) + PB_RETURN_ERROR(stream, "realloc failed"); +- ++ + *(void**)pData = ptr; + return true; + } +@@ -639,7 +641,7 @@ static bool checkreturn decode_pointer_field(pb_istream_t *stream, pb_wire_type_ + /* FIXME: Does this work correctly for oneofs? */ + pb_release_single_field(field); + } +- ++ + if (PB_HTYPE(field->type) == PB_HTYPE_ONEOF) + { + *(pb_size_t*)field->pSize = field->tag; +@@ -656,12 +658,12 @@ static bool checkreturn decode_pointer_field(pb_istream_t *stream, pb_wire_type_ + { + if (!allocate_field(stream, field->pField, field->data_size, 1)) + return false; +- ++ + field->pData = *(void**)field->pField; + initialize_pointer_field(field->pData, field); + return decode_basic_field(stream, wire_type, field); + } +- ++ + case PB_HTYPE_REPEATED: + if (wire_type == PB_WT_STRING + && PB_LTYPE(field->type) <= PB_LTYPE_LAST_PACKABLE) +@@ -671,10 +673,10 @@ static bool checkreturn decode_pointer_field(pb_istream_t *stream, pb_wire_type_ + pb_size_t *size = (pb_size_t*)field->pSize; + size_t allocated_size = *size; + pb_istream_t substream; +- ++ + if (!pb_make_string_substream(stream, &substream)) + return false; +- ++ + while (substream.bytes_left) + { + if (*size == PB_SIZE_MAX) +@@ -696,7 +698,7 @@ static bool checkreturn decode_pointer_field(pb_istream_t *stream, pb_wire_type_ + allocated_size += remain; + else + allocated_size += 1; +- ++ + if (!allocate_field(&substream, field->pField, field->data_size, allocated_size)) + { + status = false; +@@ -718,12 +720,12 @@ static bool checkreturn decode_pointer_field(pb_istream_t *stream, pb_wire_type_ + status = false; + break; + } +- ++ + (*size)++; + } + if (!pb_close_string_substream(stream, &substream)) + return false; +- ++ + return status; + } + else +@@ -733,10 +735,10 @@ static bool checkreturn decode_pointer_field(pb_istream_t *stream, pb_wire_type_ + + if (*size == PB_SIZE_MAX) + PB_RETURN_ERROR(stream, "too many array entries"); +- ++ + if (!allocate_field(stream, field->pField, field->data_size, (size_t)(*size + 1))) + return false; +- ++ + field->pData = *(char**)field->pField + field->data_size * (*size); + (*size)++; + initialize_pointer_field(field->pData, field); +@@ -758,10 +760,10 @@ static bool checkreturn decode_callback_field(pb_istream_t *stream, pb_wire_type + { + pb_istream_t substream; + size_t prev_bytes_left; +- ++ + if (!pb_make_string_substream(stream, &substream)) + return false; +- ++ + do + { + prev_bytes_left = substream.bytes_left; +@@ -771,7 +773,7 @@ static bool checkreturn decode_callback_field(pb_istream_t *stream, pb_wire_type + return false; + } + } while (substream.bytes_left > 0 && substream.bytes_left < prev_bytes_left); +- ++ + if (!pb_close_string_substream(stream, &substream)) + return false; + +@@ -786,11 +788,11 @@ static bool checkreturn decode_callback_field(pb_istream_t *stream, pb_wire_type + pb_istream_t substream; + pb_byte_t buffer[10]; + size_t size = sizeof(buffer); +- ++ + if (!read_raw_value(stream, wire_type, buffer, &size)) + return false; + substream = pb_istream_from_buffer(buffer, size); +- ++ + return field->descriptor->field_callback(&substream, NULL, field); + } + } +@@ -811,13 +813,13 @@ static bool checkreturn decode_field(pb_istream_t *stream, pb_wire_type_t wire_t + { + case PB_ATYPE_STATIC: + return decode_static_field(stream, wire_type, field); +- ++ + case PB_ATYPE_POINTER: + return decode_pointer_field(stream, wire_type, field); +- ++ + case PB_ATYPE_CALLBACK: + return decode_callback_field(stream, wire_type, field); +- ++ + default: + PB_RETURN_ERROR(stream, "invalid field type"); + } +@@ -847,7 +849,7 @@ static bool checkreturn decode_extension(pb_istream_t *stream, + uint32_t tag, pb_wire_type_t wire_type, pb_extension_t *extension) + { + size_t pos = stream->bytes_left; +- ++ + while (extension != NULL && pos == stream->bytes_left) + { + bool status; +@@ -858,10 +860,10 @@ static bool checkreturn decode_extension(pb_istream_t *stream, + + if (!status) + return false; +- ++ + extension = extension->next; + } +- ++ + return true; + } + +@@ -1170,12 +1172,12 @@ bool checkreturn pb_decode_ex(pb_istream_t *stream, const pb_msgdesc_t *fields, + if (!pb_close_string_substream(stream, &substream)) + return false; + } +- ++ + #ifdef PB_ENABLE_MALLOC + if (!status) + pb_release(fields, dest_struct); + #endif +- ++ + return status; + } + +@@ -1258,7 +1260,7 @@ static void pb_release_single_field(pb_field_iter_t *field) + { + /* Release fields in submessage or submsg array */ + pb_size_t count = 1; +- ++ + if (PB_ATYPE(type) == PB_ATYPE_POINTER) + { + field->pData = *(void**)field->pField; +@@ -1267,7 +1269,7 @@ static void pb_release_single_field(pb_field_iter_t *field) + { + field->pData = field->pField; + } +- ++ + if (PB_HTYPE(type) == PB_HTYPE_REPEATED) + { + count = *(pb_size_t*)field->pSize; +@@ -1278,7 +1280,7 @@ static void pb_release_single_field(pb_field_iter_t *field) + count = field->array_size; + } + } +- ++ + if (field->pData) + { + for (; count > 0; count--) +@@ -1288,7 +1290,7 @@ static void pb_release_single_field(pb_field_iter_t *field) + } + } + } +- ++ + if (PB_ATYPE(type) == PB_ATYPE_POINTER) + { + if (PB_HTYPE(type) == PB_HTYPE_REPEATED && +@@ -1304,13 +1306,13 @@ static void pb_release_single_field(pb_field_iter_t *field) + *pItem++ = NULL; + } + } +- ++ + if (PB_HTYPE(type) == PB_HTYPE_REPEATED) + { + /* We are going to release the array, so set the size to 0 */ + *(pb_size_t*)field->pSize = 0; + } +- ++ + /* Release main pointer */ + pb_free(*(void**)field->pField); + *(void**)field->pField = NULL; +@@ -1320,13 +1322,13 @@ static void pb_release_single_field(pb_field_iter_t *field) + void pb_release(const pb_msgdesc_t *fields, void *dest_struct) + { + pb_field_iter_t iter; +- ++ + if (!dest_struct) + return; /* Ignore NULL pointers, similar to free() */ + + if (!pb_field_iter_begin(&iter, fields, dest_struct)) + return; /* Empty message type */ +- ++ + do + { + pb_release_single_field(&iter); +@@ -1358,12 +1360,12 @@ bool pb_decode_svarint(pb_istream_t *stream, pb_int64_t *dest) + pb_uint64_t value; + if (!pb_decode_varint(stream, &value)) + return false; +- ++ + if (value & 1) + *dest = (pb_int64_t)(~(value >> 1)); + else + *dest = (pb_int64_t)(value >> 1); +- ++ + return true; + } + +@@ -1499,17 +1501,17 @@ static bool checkreturn pb_dec_bytes(pb_istream_t *stream, const pb_field_iter_t + uint32_t size; + size_t alloc_size; + pb_bytes_array_t *dest; +- ++ + if (!pb_decode_varint32(stream, &size)) + return false; +- ++ + if (size > PB_SIZE_MAX) + PB_RETURN_ERROR(stream, "bytes overflow"); +- ++ + alloc_size = PB_BYTES_ARRAY_T_ALLOCSIZE(size); + if (size > alloc_size) + PB_RETURN_ERROR(stream, "size too large"); +- ++ + if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) + { + #ifndef PB_ENABLE_MALLOC +@@ -1570,7 +1572,7 @@ static bool checkreturn pb_dec_string(pb_istream_t *stream, const pb_field_iter_ + if (alloc_size > field->data_size) + PB_RETURN_ERROR(stream, "string overflow"); + } +- ++ + dest[size] = 0; + + if (!pb_read(stream, dest, (size_t)size)) +@@ -1592,10 +1594,10 @@ static bool checkreturn pb_dec_submessage(pb_istream_t *stream, const pb_field_i + + if (!pb_make_string_substream(stream, &substream)) + return false; +- ++ + if (field->submsg_desc == NULL) + PB_RETURN_ERROR(stream, "invalid field descriptor"); +- ++ + /* Submessages can have a separate message-level callback that is called + * before decoding the message. Typically it is used to set callback fields + * inside oneofs. */ +@@ -1629,7 +1631,7 @@ static bool checkreturn pb_dec_submessage(pb_istream_t *stream, const pb_field_i + + status = pb_decode_inner(&substream, field->submsg_desc, field->pData, flags); + } +- ++ + if (!pb_close_string_substream(stream, &substream)) + return false; + +diff --git a/pb_decode.h b/pb_decode.h +index 3f392b29386e3dbbc69337316eb98029d239690a..c65d8ec716ea7282f68fdc2077a6a11130dd93fc 100644 +--- a/pb_decode.h ++++ b/pb_decode.h +@@ -1,6 +1,8 @@ + /* pb_decode.h: Functions to decode protocol buffers. Depends on pb_decode.c. + * The main function is pb_decode. You also need an input stream, and the + * field descriptions created by nanopb_generator.py. ++ * ++ * Modified for WPILib Use + */ + + #ifndef PB_DECODE_H_INCLUDED +diff --git a/pb_encode.c b/pb_encode.c +index f9034a542848f0be0656e2e9eb2b467b2a83cf41..270a721863fd0a218a9667d5f4cadb6fb943c0b9 100644 +--- a/pb_encode.c ++++ b/pb_encode.c +@@ -1,4 +1,6 @@ + /* pb_encode.c -- encode a protobuf using minimal resources ++ * ++ * Modified for WPILib Use + * + * 2011 Petteri Aimonen + */ +@@ -54,9 +56,9 @@ static bool checkreturn buf_write(pb_ostream_t *stream, const pb_byte_t *buf, si + { + pb_byte_t *dest = (pb_byte_t*)stream->state; + stream->state = dest + count; +- ++ + memcpy(dest, buf, count * sizeof(pb_byte_t)); +- ++ + return true; + } + +@@ -94,12 +96,12 @@ bool checkreturn pb_write(pb_ostream_t *stream, const pb_byte_t *buf, size_t cou + #ifdef PB_BUFFER_ONLY + if (!buf_write(stream, buf, count)) + PB_RETURN_ERROR(stream, "io error"); +-#else ++#else + if (!stream->callback(stream, buf, count)) + PB_RETURN_ERROR(stream, "io error"); + #endif + } +- ++ + stream->bytes_written += count; + return true; + } +@@ -140,14 +142,14 @@ static bool checkreturn encode_array(pb_ostream_t *stream, pb_field_iter_t *fiel + + if (PB_ATYPE(field->type) != PB_ATYPE_POINTER && count > field->array_size) + PB_RETURN_ERROR(stream, "array max size exceeded"); +- ++ + #ifndef PB_ENCODE_ARRAYS_UNPACKED + /* We always pack arrays if the datatype allows it. */ + if (PB_LTYPE(field->type) <= PB_LTYPE_LAST_PACKABLE) + { + if (!pb_encode_tag(stream, PB_WT_STRING, field->tag)) + return false; +- ++ + /* Determine the total size of packed array. */ + if (PB_LTYPE(field->type) == PB_LTYPE_FIXED32) + { +@@ -158,7 +160,7 @@ static bool checkreturn encode_array(pb_ostream_t *stream, pb_field_iter_t *fiel + size = 8 * (size_t)count; + } + else +- { ++ { + pb_ostream_t sizestream = PB_OSTREAM_SIZING; + void *pData_orig = field->pData; + for (i = 0; i < count; i++) +@@ -170,13 +172,13 @@ static bool checkreturn encode_array(pb_ostream_t *stream, pb_field_iter_t *fiel + field->pData = pData_orig; + size = sizestream.bytes_written; + } +- ++ + if (!pb_encode_varint(stream, (pb_uint64_t)size)) + return false; +- ++ + if (stream->callback == NULL) + return pb_write(stream, NULL, size); /* Just sizing.. */ +- ++ + /* Write the data */ + for (i = 0; i < count; i++) + { +@@ -235,7 +237,7 @@ static bool checkreturn encode_array(pb_ostream_t *stream, pb_field_iter_t *fiel + field->pData = (char*)field->pData + field->data_size; + } + } +- ++ + return true; + } + +@@ -498,10 +500,10 @@ static bool checkreturn encode_extension_field(pb_ostream_t *stream, const pb_fi + + if (!status) + return false; +- ++ + extension = extension->next; + } +- ++ + return true; + } + +@@ -514,7 +516,7 @@ bool checkreturn pb_encode(pb_ostream_t *stream, const pb_msgdesc_t *fields, con + pb_field_iter_t iter; + if (!pb_field_iter_begin_const(&iter, fields, src_struct)) + return true; /* Empty message type */ +- ++ + do { + if (PB_LTYPE(iter.type) == PB_LTYPE_EXTENSION) + { +@@ -529,7 +531,7 @@ bool checkreturn pb_encode(pb_ostream_t *stream, const pb_msgdesc_t *fields, con + return false; + } + } while (pb_field_iter_next(&iter)); +- ++ + return true; + } + +@@ -557,10 +559,10 @@ bool checkreturn pb_encode_ex(pb_ostream_t *stream, const pb_msgdesc_t *fields, + bool pb_get_encoded_size(size_t *size, const pb_msgdesc_t *fields, const void *src_struct) + { + pb_ostream_t stream = PB_OSTREAM_SIZING; +- ++ + if (!pb_encode(&stream, fields, src_struct)) + return false; +- ++ + *size = stream.bytes_written; + return true; + } +@@ -630,7 +632,7 @@ bool checkreturn pb_encode_svarint(pb_ostream_t *stream, pb_int64_t value) + zigzagged = ~(((pb_uint64_t)value & mask) << 1); + else + zigzagged = (pb_uint64_t)value << 1; +- ++ + return pb_encode_varint(stream, zigzagged); + } + +@@ -689,15 +691,15 @@ bool pb_encode_tag_for_field ( pb_ostream_t* stream, const pb_field_iter_t* fiel + case PB_LTYPE_SVARINT: + wiretype = PB_WT_VARINT; + break; +- ++ + case PB_LTYPE_FIXED32: + wiretype = PB_WT_32BIT; + break; +- ++ + case PB_LTYPE_FIXED64: + wiretype = PB_WT_64BIT; + break; +- ++ + case PB_LTYPE_BYTES: + case PB_LTYPE_STRING: + case PB_LTYPE_SUBMESSAGE: +@@ -705,11 +707,11 @@ bool pb_encode_tag_for_field ( pb_ostream_t* stream, const pb_field_iter_t* fiel + case PB_LTYPE_FIXED_LENGTH_BYTES: + wiretype = PB_WT_STRING; + break; +- ++ + default: + PB_RETURN_ERROR(stream, "invalid field type"); + } +- ++ + return pb_encode_tag(stream, wiretype, field->tag); + } + +@@ -717,7 +719,7 @@ bool checkreturn pb_encode_string(pb_ostream_t *stream, const pb_byte_t *buffer, + { + if (!pb_encode_varint(stream, (pb_uint64_t)size)) + return false; +- ++ + return pb_write(stream, buffer, size); + } + +@@ -727,7 +729,7 @@ bool checkreturn pb_encode_submessage(pb_ostream_t *stream, const pb_msgdesc_t * + pb_ostream_t substream = PB_OSTREAM_SIZING; + size_t size; + bool status; +- ++ + if (!pb_encode(&substream, fields, src_struct)) + { + #ifndef PB_NO_ERRMSG +@@ -735,18 +737,18 @@ bool checkreturn pb_encode_submessage(pb_ostream_t *stream, const pb_msgdesc_t * + #endif + return false; + } +- ++ + size = substream.bytes_written; +- ++ + if (!pb_encode_varint(stream, (pb_uint64_t)size)) + return false; +- ++ + if (stream->callback == NULL) + return pb_write(stream, NULL, size); /* Just sizing */ +- ++ + if (stream->bytes_written + size > stream->max_size) + PB_RETURN_ERROR(stream, "stream full"); +- ++ + /* Use a substream to verify that a callback doesn't write more than + * what it did the first time. */ + substream.callback = stream->callback; +@@ -756,18 +758,18 @@ bool checkreturn pb_encode_submessage(pb_ostream_t *stream, const pb_msgdesc_t * + #ifndef PB_NO_ERRMSG + substream.errmsg = NULL; + #endif +- ++ + status = pb_encode(&substream, fields, src_struct); +- ++ + stream->bytes_written += substream.bytes_written; + stream->state = substream.state; + #ifndef PB_NO_ERRMSG + stream->errmsg = substream.errmsg; + #endif +- ++ + if (substream.bytes_written != size) + PB_RETURN_ERROR(stream, "submsg size changed"); +- ++ + return status; + } + +@@ -858,19 +860,19 @@ static bool checkreturn pb_enc_bytes(pb_ostream_t *stream, const pb_field_iter_t + const pb_bytes_array_t *bytes = NULL; + + bytes = (const pb_bytes_array_t*)field->pData; +- ++ + if (bytes == NULL) + { + /* Treat null pointer as an empty bytes field */ + return pb_encode_string(stream, NULL, 0); + } +- ++ + if (PB_ATYPE(field->type) == PB_ATYPE_STATIC && + bytes->size > field->data_size - offsetof(pb_bytes_array_t, bytes)) + { + PB_RETURN_ERROR(stream, "bytes size exceeded"); + } +- ++ + return pb_encode_string(stream, bytes->bytes, (size_t)bytes->size); + } + +@@ -879,7 +881,7 @@ static bool checkreturn pb_enc_string(pb_ostream_t *stream, const pb_field_iter_ + size_t size = 0; + size_t max_size = (size_t)field->data_size; + const char *str = (const char*)field->pData; +- ++ + if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) + { + max_size = (size_t)-1; +@@ -942,7 +944,7 @@ static bool checkreturn pb_enc_submessage(pb_ostream_t *stream, const pb_field_i + return false; + } + } +- ++ + return pb_encode_submessage(stream, field->submsg_desc, field->pData); + } + +diff --git a/pb_encode.h b/pb_encode.h +index 6dc089da307a10a6d440e70acb2775ed6e7fb07c..22491a7f5e0d787e3c62b0a45dbae31a3c191f58 100644 +--- a/pb_encode.h ++++ b/pb_encode.h +@@ -1,6 +1,8 @@ + /* pb_encode.h: Functions to encode protocol buffers. Depends on pb_encode.c. + * The main function is pb_encode. You also need an output stream, and the + * field descriptions created by nanopb_generator.py. ++ * ++ * Modified for WPILib Use + */ + + #ifndef PB_ENCODE_H_INCLUDED diff --git a/upstream_utils/nanopb_patches/0002-Remove-extern-C.patch b/upstream_utils/nanopb_patches/0002-Remove-extern-C.patch new file mode 100644 index 0000000000..6c467ac843 --- /dev/null +++ b/upstream_utils/nanopb_patches/0002-Remove-extern-C.patch @@ -0,0 +1,188 @@ +From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 +From: Thad House +Date: Mon, 28 Oct 2024 16:58:15 -0700 +Subject: [PATCH 2/4] Remove extern C + +--- + generator/nanopb_generator.py | 8 -------- + pb.h | 8 -------- + pb_common.h | 9 --------- + pb_decode.h | 16 ++++------------ + pb_encode.h | 12 ++---------- + 5 files changed, 6 insertions(+), 47 deletions(-) + +diff --git a/generator/nanopb_generator.py b/generator/nanopb_generator.py +index 735e4b7b31cdb66a1cdfbd2da6ae8fcde5986147..239aed4f379b5d454e3b65c48ca11e9f92b6bc4d 100755 +--- a/generator/nanopb_generator.py ++++ b/generator/nanopb_generator.py +@@ -2086,10 +2086,6 @@ class ProtoFile: + yield extension.extension_decl() + yield '\n' + +- yield '#ifdef __cplusplus\n' +- yield 'extern "C" {\n' +- yield '#endif\n\n' +- + if self.enums: + yield '/* Helper constants for enums */\n' + for enum in self.enums: +@@ -2224,10 +2220,6 @@ class ProtoFile: + yield '#define %s %s\n' % (longname, shortname) + yield '\n' + +- yield '#ifdef __cplusplus\n' +- yield '} /* extern "C" */\n' +- yield '#endif\n' +- + if options.cpp_descriptors: + yield '\n' + yield '#ifdef __cplusplus\n' +diff --git a/pb.h b/pb.h +index cec078fe40d526712eda771db077ebf31c95e076..a7fd771f05d7182e73ab346b46294c6fc5ac44c7 100644 +--- a/pb.h ++++ b/pb.h +@@ -94,10 +94,6 @@ + #endif + #endif + +-#ifdef __cplusplus +-extern "C" { +-#endif +- + /* Macro for defining packed structures (compiler dependent). + * This just reduces memory requirements, but is not required. + */ +@@ -895,10 +891,6 @@ struct pb_extension_s { + + #define PB_RETURN_ERROR(stream, msg) return PB_SET_ERROR(stream, msg), false + +-#ifdef __cplusplus +-} /* extern "C" */ +-#endif +- + #ifdef __cplusplus + #if __cplusplus >= 201103L + #define PB_CONSTEXPR constexpr +diff --git a/pb_common.h b/pb_common.h +index d1d8bf55b13412887ab6d8fc6cfaf51348da9605..f08a87389b89e6d73468fd0d8e58af7f998cbbf3 100644 +--- a/pb_common.h ++++ b/pb_common.h +@@ -9,10 +9,6 @@ + + #include "pb.h" + +-#ifdef __cplusplus +-extern "C" { +-#endif +- + /* Initialize the field iterator structure to beginning. + * Returns false if the message type is empty. */ + bool pb_field_iter_begin(pb_field_iter_t *iter, const pb_msgdesc_t *desc, void *message); +@@ -43,9 +39,4 @@ bool pb_field_iter_find_extension(pb_field_iter_t *iter); + bool pb_validate_utf8(const char *s); + #endif + +-#ifdef __cplusplus +-} /* extern "C" */ + #endif +- +-#endif +- +diff --git a/pb_decode.h b/pb_decode.h +index c65d8ec716ea7282f68fdc2077a6a11130dd93fc..a96f18169127c3d2cd80ba89138421f2340b1fe2 100644 +--- a/pb_decode.h ++++ b/pb_decode.h +@@ -10,14 +10,10 @@ + + #include "pb.h" + +-#ifdef __cplusplus +-extern "C" { +-#endif +- + /* Structure for defining custom input streams. You will need to provide + * a callback function to read the bytes from your storage, which can be + * for example a file or a network socket. +- * ++ * + * The callback must conform to these rules: + * + * 1) Return false on IO errors. This will cause decoding to abort. +@@ -51,7 +47,7 @@ struct pb_istream_s + * denial-of-service by excessively long messages. + */ + size_t bytes_left; +- ++ + #ifndef PB_NO_ERRMSG + /* Pointer to constant (ROM) string when decoding function returns error */ + const char *errmsg; +@@ -67,7 +63,7 @@ struct pb_istream_s + /*************************** + * Main decoding functions * + ***************************/ +- ++ + /* Decode a single protocol buffers message from input stream into a C structure. + * Returns true on success, false on any failure. + * The actual struct pointed to by dest must match the description in fields. +@@ -78,7 +74,7 @@ struct pb_istream_s + * MyMessage msg = {}; + * uint8_t buffer[64]; + * pb_istream_t stream; +- * ++ * + * // ... read some data into buffer ... + * + * stream = pb_istream_from_buffer(buffer, count); +@@ -199,8 +195,4 @@ bool pb_decode_double_as_float(pb_istream_t *stream, float *dest); + bool pb_make_string_substream(pb_istream_t *stream, pb_istream_t *substream); + bool pb_close_string_substream(pb_istream_t *stream, pb_istream_t *substream); + +-#ifdef __cplusplus +-} /* extern "C" */ +-#endif +- + #endif +diff --git a/pb_encode.h b/pb_encode.h +index 22491a7f5e0d787e3c62b0a45dbae31a3c191f58..961bde1e3542392c1da6ea64cd15904af6289d22 100644 +--- a/pb_encode.h ++++ b/pb_encode.h +@@ -10,10 +10,6 @@ + + #include "pb.h" + +-#ifdef __cplusplus +-extern "C" { +-#endif +- + /* Structure for defining custom output streams. You will need to provide + * a callback function to write the bytes to your storage, which can be + * for example a file or a network socket. +@@ -51,7 +47,7 @@ struct pb_ostream_s + + /* Number of bytes written so far. */ + size_t bytes_written; +- ++ + #ifndef PB_NO_ERRMSG + /* Pointer to constant (ROM) string when decoding function returns error */ + const char *errmsg; +@@ -117,7 +113,7 @@ pb_ostream_t pb_ostream_from_buffer(pb_byte_t *buf, size_t bufsize); + + /* Pseudo-stream for measuring the size of a message without actually storing + * the encoded data. +- * ++ * + * Example usage: + * MyMessage msg = {}; + * pb_ostream_t stream = PB_OSTREAM_SIZING; +@@ -190,8 +186,4 @@ bool pb_encode_float_as_double(pb_ostream_t *stream, float value); + */ + bool pb_encode_submessage(pb_ostream_t *stream, const pb_msgdesc_t *fields, const void *src_struct); + +-#ifdef __cplusplus +-} /* extern "C" */ +-#endif +- + #endif diff --git a/upstream_utils/nanopb_patches/0003-Generate-messages-or-anything-non-static-as-callback.patch b/upstream_utils/nanopb_patches/0003-Generate-messages-or-anything-non-static-as-callback.patch new file mode 100644 index 0000000000..a8af91d69d --- /dev/null +++ b/upstream_utils/nanopb_patches/0003-Generate-messages-or-anything-non-static-as-callback.patch @@ -0,0 +1,28 @@ +From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 +From: Thad House +Date: Tue, 29 Oct 2024 20:23:48 -0700 +Subject: [PATCH 3/4] Generate messages or anything non static as callback + +--- + generator/nanopb_generator.py | 6 ++++-- + 1 file changed, 4 insertions(+), 2 deletions(-) + +diff --git a/generator/nanopb_generator.py b/generator/nanopb_generator.py +index 239aed4f379b5d454e3b65c48ca11e9f92b6bc4d..3b59ba59e6fc997350b1368a2faebc051cd6176a 100755 +--- a/generator/nanopb_generator.py ++++ b/generator/nanopb_generator.py +@@ -683,10 +683,12 @@ class Field(ProtoElement): + + # Decide how the field data will be allocated + if field_options.type == nanopb_pb2.FT_DEFAULT: +- if can_be_static: ++ if desc.type == FieldD.TYPE_MESSAGE: ++ field_options.type = nanopb_pb2.FT_CALLBACK ++ elif can_be_static: + field_options.type = nanopb_pb2.FT_STATIC + else: +- field_options.type = field_options.fallback_type ++ field_options.type = nanopb_pb2.FT_CALLBACK + + if field_options.type == nanopb_pb2.FT_STATIC and not can_be_static: + raise Exception("Field '%s' is defined as static, but max_size or " diff --git a/upstream_utils/nanopb_patches/0004-Generate-as-cpp-and-add-wpilib-requirements.patch b/upstream_utils/nanopb_patches/0004-Generate-as-cpp-and-add-wpilib-requirements.patch new file mode 100644 index 0000000000..f6aa3d31ba --- /dev/null +++ b/upstream_utils/nanopb_patches/0004-Generate-as-cpp-and-add-wpilib-requirements.patch @@ -0,0 +1,170 @@ +From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001 +From: Thad House +Date: Sat, 2 Nov 2024 20:25:45 -0700 +Subject: [PATCH 4/4] Generate as cpp and add wpilib requirements + +--- + generator/nanopb_generator.py | 43 +++++++++++++++++++++++++++-------- + pb.h | 23 +++++++++++++++---- + 2 files changed, 52 insertions(+), 14 deletions(-) + +diff --git a/generator/nanopb_generator.py b/generator/nanopb_generator.py +index 3b59ba59e6fc997350b1368a2faebc051cd6176a..01fc349538aec0c67ec3fd9bfaf3a356adc08e96 100755 +--- a/generator/nanopb_generator.py ++++ b/generator/nanopb_generator.py +@@ -1406,6 +1406,12 @@ class Message(ProtoElement): + + result += '\n' + ++ result += ' static const pb_msgdesc_t* msg_descriptor(void) noexcept;\n' ++ result += ' static std::string_view msg_name(void) noexcept;\n' ++ result += ' static pb_filedesc_t file_descriptor(void) noexcept;\n' ++ ++ result += '\n' ++ + if not self.fields: + # Empty structs are not allowed in C standard. + # Therefore add a dummy field if an empty message occurs. +@@ -2046,6 +2052,8 @@ class ProtoFile: + # no %s specified - use whatever was passed in as options.libformat + yield options.libformat + yield '\n' ++ yield "#include \n" ++ yield "#include \n" + + for incfile in self.file_options.include: + # allow including system headers +@@ -2126,16 +2134,6 @@ class ProtoFile: + yield '/* Struct field encoding specification for nanopb */\n' + for msg in self.messages: + yield msg.fields_declaration(self.dependencies) + '\n' +- for msg in self.messages: +- yield 'extern const pb_msgdesc_t %s_msg;\n' % Globals.naming_style.type_name(msg.name) +- yield '\n' +- +- yield '/* Defines for backwards compatibility with code written before nanopb-0.4.0 */\n' +- for msg in self.messages: +- yield '#define %s &%s_msg\n' % ( +- Globals.naming_style.define_name('%s_fields' % msg.name), +- Globals.naming_style.type_name(msg.name)) +- yield '\n' + + yield '/* Maximum encoded size of messages (where known) */\n' + messagesizes = [] +@@ -2259,6 +2257,24 @@ class ProtoFile: + yield '#endif\n' + yield '\n' + ++ yield "#include \n" ++ yield "#include \n" ++ ++ yield "static const uint8_t file_descriptor[] {\n" ++ ++ line_count = 0 ++ ++ for b in self.fdesc.SerializeToString(): ++ yield '0x' + format(b, '02x') + ',' ++ line_count += 1 ++ if line_count == 10: ++ yield '\n' ++ line_count = 0 ++ yield '\n' ++ ++ yield "};\n" ++ yield 'static const char file_name[] = "%s";\n' % self.fdesc.name ++ + # Check if any messages exceed the 64 kB limit of 16-bit pb_size_t + exceeds_64kB = [] + for msg in self.messages: +@@ -2275,6 +2291,13 @@ class ProtoFile: + + # Generate the message field definitions (PB_BIND() call) + for msg in self.messages: ++ if self.fdesc.package: ++ full_name = self.fdesc.package + '.' + msg.desc.name ++ else: ++ full_name = msg.desc.name ++ yield 'static const char %s_name[] = "%s";\n' % (msg.name, full_name) ++ yield 'std::string_view %s::msg_name(void) noexcept { return %s_name; }\n' % (msg.name, msg.name) ++ yield 'pb_filedesc_t %s::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; }\n' % msg.name + yield msg.fields_definition(self.dependencies) + '\n\n' + + # Generate pb_extension_type_t definitions if extensions are used in proto file +diff --git a/pb.h b/pb.h +index a7fd771f05d7182e73ab346b46294c6fc5ac44c7..832364a60900cbcb9134b6e122576436a6df6a00 100644 +--- a/pb.h ++++ b/pb.h +@@ -89,6 +89,9 @@ + #include + #include + ++#include ++#include ++ + #ifdef PB_ENABLE_MALLOC + #include + #endif +@@ -315,6 +318,12 @@ typedef struct pb_istream_s pb_istream_t; + typedef struct pb_ostream_s pb_ostream_t; + typedef struct pb_field_iter_s pb_field_iter_t; + ++typedef struct pb_filedesc_s pb_filedesc_t; ++struct pb_filedesc_s { ++ std::string_view file_name; ++ std::span file_descriptor; ++}; ++ + /* This structure is used in auto-generated constants + * to specify struct fields. + */ +@@ -329,6 +338,9 @@ struct pb_msgdesc_s { + pb_size_t field_count; + pb_size_t required_field_count; + pb_size_t largest_tag; ++ ++ pb_filedesc_t file_descriptor; ++ std::string_view proto_name; + }; + + /* Iterator for message descriptor */ +@@ -501,17 +513,17 @@ struct pb_extension_s { + + /* Binding of a message field set into a specific structure */ + #define PB_BIND(msgname, structname, width) \ +- const uint32_t structname ## _field_info[] PB_PROGMEM = \ ++ static const uint32_t structname ## _field_info[] PB_PROGMEM = \ + { \ + msgname ## _FIELDLIST(PB_GEN_FIELD_INFO_ ## width, structname) \ + 0 \ + }; \ +- const pb_msgdesc_t* const structname ## _submsg_info[] = \ ++ static const pb_msgdesc_t* const structname ## _submsg_info[] = \ + { \ + msgname ## _FIELDLIST(PB_GEN_SUBMSG_INFO, structname) \ + NULL \ + }; \ +- const pb_msgdesc_t structname ## _msg = \ ++ static const pb_msgdesc_t structname ## _msg = \ + { \ + structname ## _field_info, \ + structname ## _submsg_info, \ +@@ -520,7 +532,10 @@ struct pb_extension_s { + 0 msgname ## _FIELDLIST(PB_GEN_FIELD_COUNT, structname), \ + 0 msgname ## _FIELDLIST(PB_GEN_REQ_FIELD_COUNT, structname), \ + 0 msgname ## _FIELDLIST(PB_GEN_LARGEST_TAG, structname), \ ++ structname::file_descriptor(), \ ++ structname::msg_name(), \ + }; \ ++ const pb_msgdesc_t* structname::msg_descriptor(void) noexcept { return &(structname ## _msg); } \ + msgname ## _FIELDLIST(PB_GEN_FIELD_INFO_ASSERT_ ## width, structname) + + #define PB_GEN_FIELD_COUNT(structname, atype, htype, ltype, fieldname, tag) +1 +@@ -726,7 +741,7 @@ struct pb_extension_s { + #define PB_SI_PB_LTYPE_UINT64(t) + #define PB_SI_PB_LTYPE_EXTENSION(t) + #define PB_SI_PB_LTYPE_FIXED_LENGTH_BYTES(t) +-#define PB_SUBMSG_DESCRIPTOR(t) &(t ## _msg), ++#define PB_SUBMSG_DESCRIPTOR(t) (t::msg_descriptor()), + + /* The field descriptors use a variable width format, with width of either + * 1, 2, 4 or 8 of 32-bit words. The two lowest bytes of the first byte always diff --git a/wpimath/.styleguide b/wpimath/.styleguide index 3e67f48eec..91d68ae2b2 100644 --- a/wpimath/.styleguide +++ b/wpimath/.styleguide @@ -22,6 +22,7 @@ generatedFileExclude { src/test/native/cpp/drake/ src/test/native/include/drake/ src/generated/main/java/edu/wpi/first/math/proto + src/generated/main/native/cpp } repoRootNameOverride { diff --git a/wpimath/CMakeLists.txt b/wpimath/CMakeLists.txt index ac021369ee..19780acd83 100644 --- a/wpimath/CMakeLists.txt +++ b/wpimath/CMakeLists.txt @@ -4,13 +4,6 @@ include(SubDirList) include(CompileWarnings) include(AddTest) include(DownloadAndCheck) -include(WpiProtobuf) - -if(WITH_PROTOBUF) - # workaround for makefiles - for some reason parent directories aren't created. - file(MAKE_DIRECTORY "${CMAKE_CURRENT_BINARY_DIR}/protobuf") - file(GLOB wpimath_proto_src src/main/proto/*.proto) -endif() file( GLOB wpimath_jni_src @@ -122,49 +115,36 @@ file( src/main/native/thirdparty/sleipnir/src/*.cpp ) list(REMOVE_ITEM wpimath_native_src ${wpimath_jni_src}) -if(NOT WITH_PROTOBUF) - list(FILTER wpimath_native_src EXCLUDE REGEX "/proto/") -endif() set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS FALSE) -if(WITH_PROTOBUF) - add_library(protobuf OBJECT) - target_link_libraries(protobuf wpiutil) +file(GLOB_RECURSE wpimath_protobuf_native_src src/generated/main/native/cpp/wpimath/protobuf/*.cpp) - add_library(wpimath ${wpimath_native_src} $) +add_library(protobuf OBJECT ${wpimath_protobuf_native_src}) +target_link_libraries(protobuf wpiutil) - wpi_protobuf_generate( - TARGET - protobuf - PROTOS ${wpimath_proto_src} - PLUGIN ${PROTOC_WPILIB_PLUGIN} - PROTOC_OUT_DIR "${CMAKE_CURRENT_BINARY_DIR}/protobuf" +add_library(wpimath ${wpimath_native_src} $) + +if(MSVC) + get_property(IS_MULTI_CONFIG GLOBAL PROPERTY GENERATOR_IS_MULTI_CONFIG) + set(CONFIG_SUFFIX "$<$:_$>") + file( + GENERATE OUTPUT + ${CMAKE_CURRENT_BINARY_DIR}/protobuf_objects${CONFIG_SUFFIX}.txt + CONTENT $,\n> ) - if(MSVC) - get_property(IS_MULTI_CONFIG GLOBAL PROPERTY GENERATOR_IS_MULTI_CONFIG) - set(CONFIG_SUFFIX "$<$:_$>") - file( - GENERATE OUTPUT + add_custom_command( + TARGET wpimath + PRE_LINK + COMMAND + cmake -E __create_def ${CMAKE_CURRENT_BINARY_DIR}/protobuf_exports${CONFIG_SUFFIX}.def ${CMAKE_CURRENT_BINARY_DIR}/protobuf_objects${CONFIG_SUFFIX}.txt - CONTENT $,\n> - ) - add_custom_command( - TARGET wpimath - PRE_LINK - COMMAND - cmake -E __create_def - ${CMAKE_CURRENT_BINARY_DIR}/protobuf_exports${CONFIG_SUFFIX}.def - ${CMAKE_CURRENT_BINARY_DIR}/protobuf_objects${CONFIG_SUFFIX}.txt - ) - target_link_options( - wpimath - PRIVATE - /DEF:$ - ) - endif() -else() - add_library(wpimath ${wpimath_native_src}) + ) + target_link_options( + wpimath + PRIVATE + /DEF:$ + ) endif() set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS TRUE) @@ -177,14 +157,6 @@ target_compile_features(wpimath PUBLIC cxx_std_20) if(MSVC) target_compile_options(wpimath PUBLIC /utf-8 /bigobj) endif() - -if(WITH_PROTOBUF) - target_compile_features(protobuf PUBLIC cxx_std_20) - if(MSVC) - target_compile_options(protobuf PUBLIC /utf-8 /bigobj) - endif() -endif() - wpilib_target_warnings(wpimath) target_link_libraries(wpimath wpiutil) @@ -222,7 +194,7 @@ target_include_directories( wpimath PUBLIC $ - $ + $ $ ) diff --git a/wpimath/build.gradle b/wpimath/build.gradle index cbc49c7df7..07cd11b5e9 100644 --- a/wpimath/build.gradle +++ b/wpimath/build.gradle @@ -21,6 +21,15 @@ ext { 'src/main/native/thirdparty/sleipnir/src' } } + nanopbCpp(CppSourceSet) { + source { + srcDirs 'src/generated/main/native/cpp' + include '**/*.cpp' + } + exportedHeaders { + srcDirs 'src/generated/main/native/cpp' + } + } } } } @@ -38,6 +47,10 @@ cppHeadersZip { into '/wpimath/protobuf' include '*.h' } + from("src/generated/main/native/cpp/wpimath/protobuf") { + into '/wpimath/protobuf' + include '**/*.h' + } from('src/main/native/thirdparty/sleipnir/include') { into '/' } @@ -53,7 +66,8 @@ model { srcDirs 'src/main/native/include', 'src/main/native/thirdparty/eigen/include', 'src/main/native/thirdparty/gcem/include', - 'src/main/native/thirdparty/sleipnir/include' + 'src/main/native/thirdparty/sleipnir/include', + 'src/generated/main/native/cpp' } } } @@ -68,7 +82,7 @@ model { nativeUtils.exportsConfigs { wpimath { objectFilterClosure = { file -> - return file.name.endsWith('.pb.obj') + return file.name.endsWith('.pb.obj') || file.name.endsWith('.npb.obj') } } } diff --git a/wpimath/generate_nanopb.py b/wpimath/generate_nanopb.py new file mode 100755 index 0000000000..97af4dfa7c --- /dev/null +++ b/wpimath/generate_nanopb.py @@ -0,0 +1,88 @@ +#!/usr/bin/env python3 + +# Copyright (c) FIRST and other WPILib contributors. +# Open Source Software; you can modify and/or share it under the terms of +# the WPILib BSD license file in the root directory of this project. + +import argparse +import os +import shutil +import subprocess +import sys +from pathlib import Path + + +def generate_nanopb(nanopb: Path, output_directory: Path, proto_dir: Path): + shutil.rmtree(output_directory.absolute(), ignore_errors=True) + os.makedirs(output_directory.absolute()) + + proto_files = proto_dir.glob("*.proto") + for path in proto_files: + absolute_filename = path.absolute() + subprocess.run( + [ + sys.executable, + nanopb, + f"-I{absolute_filename.parent}", + f"-D{output_directory.absolute()}", + "-S.cpp", + "-e.npb", + absolute_filename, + ], + check=True, + ) + java_files = (output_directory).glob("*") + for java_file in java_files: + with (java_file).open(encoding="utf-8") as f: + content = f.read() + + java_file.write_text( + "// Copyright (c) FIRST and other WPILib contributors.\n// Open Source Software; you can modify and/or share it under the terms of\n// the WPILib BSD license file in the root directory of this project.\n" + + content, + encoding="utf-8", + newline="\n", + ) + + +def main(): + script_path = Path(__file__).resolve() + dirname = script_path.parent + + root_path = dirname.parent + nanopb_path = os.path.join( + root_path, + "wpiutil", + "src", + "main", + "native", + "thirdparty", + "nanopb", + "generator", + "nanopb_generator.py", + ) + + parser = argparse.ArgumentParser() + parser.add_argument( + "--nanopb", + help="Nanopb generator command", + default=nanopb_path, + ) + parser.add_argument( + "--output_directory", + help="Optional. If set, will output the generated files to this directory, otherwise it will use a path relative to the script", + default=dirname / "src/generated/main/native/cpp/wpimath/protobuf", + type=Path, + ) + parser.add_argument( + "--proto_directory", + help="Optional. If set, will use this directory to glob for protobuf files", + default=dirname / "src/main/proto", + type=Path, + ) + args = parser.parse_args() + + generate_nanopb(args.nanopb, args.output_directory, args.proto_directory) + + +if __name__ == "__main__": + main() diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/controller.npb.cpp b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/controller.npb.cpp new file mode 100644 index 0000000000..be3f6abd9c --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/controller.npb.cpp @@ -0,0 +1,245 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb constant definitions */ +/* Generated by nanopb-0.4.9 */ + +#include "controller.npb.h" +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +#include +#include +static const uint8_t file_descriptor[] { +0x0a,0x10,0x63,0x6f,0x6e,0x74,0x72,0x6f,0x6c,0x6c, +0x65,0x72,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x12,0x09, +0x77,0x70,0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x22, +0x68,0x0a,0x16,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75, +0x66,0x41,0x72,0x6d,0x46,0x65,0x65,0x64,0x66,0x6f, +0x72,0x77,0x61,0x72,0x64,0x12,0x0e,0x0a,0x02,0x6b, +0x73,0x18,0x01,0x20,0x01,0x28,0x01,0x52,0x02,0x6b, +0x73,0x12,0x0e,0x0a,0x02,0x6b,0x67,0x18,0x02,0x20, +0x01,0x28,0x01,0x52,0x02,0x6b,0x67,0x12,0x0e,0x0a, +0x02,0x6b,0x76,0x18,0x03,0x20,0x01,0x28,0x01,0x52, +0x02,0x6b,0x76,0x12,0x0e,0x0a,0x02,0x6b,0x61,0x18, +0x04,0x20,0x01,0x28,0x01,0x52,0x02,0x6b,0x61,0x12, +0x0e,0x0a,0x02,0x64,0x74,0x18,0x05,0x20,0x01,0x28, +0x01,0x52,0x02,0x64,0x74,0x22,0x9e,0x01,0x0a,0x24, +0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x44,0x69, +0x66,0x66,0x65,0x72,0x65,0x6e,0x74,0x69,0x61,0x6c, +0x44,0x72,0x69,0x76,0x65,0x46,0x65,0x65,0x64,0x66, +0x6f,0x72,0x77,0x61,0x72,0x64,0x12,0x1b,0x0a,0x09, +0x6b,0x76,0x5f,0x6c,0x69,0x6e,0x65,0x61,0x72,0x18, +0x01,0x20,0x01,0x28,0x01,0x52,0x08,0x6b,0x76,0x4c, +0x69,0x6e,0x65,0x61,0x72,0x12,0x1b,0x0a,0x09,0x6b, +0x61,0x5f,0x6c,0x69,0x6e,0x65,0x61,0x72,0x18,0x02, +0x20,0x01,0x28,0x01,0x52,0x08,0x6b,0x61,0x4c,0x69, +0x6e,0x65,0x61,0x72,0x12,0x1d,0x0a,0x0a,0x6b,0x76, +0x5f,0x61,0x6e,0x67,0x75,0x6c,0x61,0x72,0x18,0x03, +0x20,0x01,0x28,0x01,0x52,0x09,0x6b,0x76,0x41,0x6e, +0x67,0x75,0x6c,0x61,0x72,0x12,0x1d,0x0a,0x0a,0x6b, +0x61,0x5f,0x61,0x6e,0x67,0x75,0x6c,0x61,0x72,0x18, +0x04,0x20,0x01,0x28,0x01,0x52,0x09,0x6b,0x61,0x41, +0x6e,0x67,0x75,0x6c,0x61,0x72,0x22,0x6d,0x0a,0x1b, +0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x45,0x6c, +0x65,0x76,0x61,0x74,0x6f,0x72,0x46,0x65,0x65,0x64, +0x66,0x6f,0x72,0x77,0x61,0x72,0x64,0x12,0x0e,0x0a, +0x02,0x6b,0x73,0x18,0x01,0x20,0x01,0x28,0x01,0x52, +0x02,0x6b,0x73,0x12,0x0e,0x0a,0x02,0x6b,0x67,0x18, +0x02,0x20,0x01,0x28,0x01,0x52,0x02,0x6b,0x67,0x12, +0x0e,0x0a,0x02,0x6b,0x76,0x18,0x03,0x20,0x01,0x28, +0x01,0x52,0x02,0x6b,0x76,0x12,0x0e,0x0a,0x02,0x6b, +0x61,0x18,0x04,0x20,0x01,0x28,0x01,0x52,0x02,0x6b, +0x61,0x12,0x0e,0x0a,0x02,0x64,0x74,0x18,0x05,0x20, +0x01,0x28,0x01,0x52,0x02,0x64,0x74,0x22,0x60,0x0a, +0x1e,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x53, +0x69,0x6d,0x70,0x6c,0x65,0x4d,0x6f,0x74,0x6f,0x72, +0x46,0x65,0x65,0x64,0x66,0x6f,0x72,0x77,0x61,0x72, +0x64,0x12,0x0e,0x0a,0x02,0x6b,0x73,0x18,0x01,0x20, +0x01,0x28,0x01,0x52,0x02,0x6b,0x73,0x12,0x0e,0x0a, +0x02,0x6b,0x76,0x18,0x02,0x20,0x01,0x28,0x01,0x52, +0x02,0x6b,0x76,0x12,0x0e,0x0a,0x02,0x6b,0x61,0x18, +0x03,0x20,0x01,0x28,0x01,0x52,0x02,0x6b,0x61,0x12, +0x0e,0x0a,0x02,0x64,0x74,0x18,0x04,0x20,0x01,0x28, +0x01,0x52,0x02,0x64,0x74,0x22,0x52,0x0a,0x26,0x50, +0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x44,0x69,0x66, +0x66,0x65,0x72,0x65,0x6e,0x74,0x69,0x61,0x6c,0x44, +0x72,0x69,0x76,0x65,0x57,0x68,0x65,0x65,0x6c,0x56, +0x6f,0x6c,0x74,0x61,0x67,0x65,0x73,0x12,0x12,0x0a, +0x04,0x6c,0x65,0x66,0x74,0x18,0x01,0x20,0x01,0x28, +0x01,0x52,0x04,0x6c,0x65,0x66,0x74,0x12,0x14,0x0a, +0x05,0x72,0x69,0x67,0x68,0x74,0x18,0x02,0x20,0x01, +0x28,0x01,0x52,0x05,0x72,0x69,0x67,0x68,0x74,0x42, +0x1a,0x0a,0x18,0x65,0x64,0x75,0x2e,0x77,0x70,0x69, +0x2e,0x66,0x69,0x72,0x73,0x74,0x2e,0x6d,0x61,0x74, +0x68,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x4a,0xf5,0x09, +0x0a,0x06,0x12,0x04,0x00,0x00,0x27,0x01,0x0a,0x08, +0x0a,0x01,0x0c,0x12,0x03,0x00,0x00,0x12,0x0a,0x08, +0x0a,0x01,0x02,0x12,0x03,0x02,0x00,0x12,0x0a,0x08, +0x0a,0x01,0x08,0x12,0x03,0x04,0x00,0x31,0x0a,0x09, +0x0a,0x02,0x08,0x01,0x12,0x03,0x04,0x00,0x31,0x0a, +0x0a,0x0a,0x02,0x04,0x00,0x12,0x04,0x06,0x00,0x0c, +0x01,0x0a,0x0a,0x0a,0x03,0x04,0x00,0x01,0x12,0x03, +0x06,0x08,0x1e,0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02, +0x00,0x12,0x03,0x07,0x02,0x10,0x0a,0x0c,0x0a,0x05, +0x04,0x00,0x02,0x00,0x05,0x12,0x03,0x07,0x02,0x08, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x00,0x01,0x12, +0x03,0x07,0x09,0x0b,0x0a,0x0c,0x0a,0x05,0x04,0x00, +0x02,0x00,0x03,0x12,0x03,0x07,0x0e,0x0f,0x0a,0x0b, +0x0a,0x04,0x04,0x00,0x02,0x01,0x12,0x03,0x08,0x02, +0x10,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x01,0x05, +0x12,0x03,0x08,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04, +0x00,0x02,0x01,0x01,0x12,0x03,0x08,0x09,0x0b,0x0a, +0x0c,0x0a,0x05,0x04,0x00,0x02,0x01,0x03,0x12,0x03, +0x08,0x0e,0x0f,0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02, +0x02,0x12,0x03,0x09,0x02,0x10,0x0a,0x0c,0x0a,0x05, +0x04,0x00,0x02,0x02,0x05,0x12,0x03,0x09,0x02,0x08, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x02,0x01,0x12, +0x03,0x09,0x09,0x0b,0x0a,0x0c,0x0a,0x05,0x04,0x00, +0x02,0x02,0x03,0x12,0x03,0x09,0x0e,0x0f,0x0a,0x0b, +0x0a,0x04,0x04,0x00,0x02,0x03,0x12,0x03,0x0a,0x02, +0x10,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x03,0x05, +0x12,0x03,0x0a,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04, +0x00,0x02,0x03,0x01,0x12,0x03,0x0a,0x09,0x0b,0x0a, +0x0c,0x0a,0x05,0x04,0x00,0x02,0x03,0x03,0x12,0x03, +0x0a,0x0e,0x0f,0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02, +0x04,0x12,0x03,0x0b,0x02,0x10,0x0a,0x0c,0x0a,0x05, +0x04,0x00,0x02,0x04,0x05,0x12,0x03,0x0b,0x02,0x08, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x04,0x01,0x12, +0x03,0x0b,0x09,0x0b,0x0a,0x0c,0x0a,0x05,0x04,0x00, +0x02,0x04,0x03,0x12,0x03,0x0b,0x0e,0x0f,0x0a,0x0a, +0x0a,0x02,0x04,0x01,0x12,0x04,0x0e,0x00,0x13,0x01, +0x0a,0x0a,0x0a,0x03,0x04,0x01,0x01,0x12,0x03,0x0e, +0x08,0x2c,0x0a,0x0b,0x0a,0x04,0x04,0x01,0x02,0x00, +0x12,0x03,0x0f,0x02,0x17,0x0a,0x0c,0x0a,0x05,0x04, +0x01,0x02,0x00,0x05,0x12,0x03,0x0f,0x02,0x08,0x0a, +0x0c,0x0a,0x05,0x04,0x01,0x02,0x00,0x01,0x12,0x03, +0x0f,0x09,0x12,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02, +0x00,0x03,0x12,0x03,0x0f,0x15,0x16,0x0a,0x0b,0x0a, +0x04,0x04,0x01,0x02,0x01,0x12,0x03,0x10,0x02,0x17, +0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x01,0x05,0x12, +0x03,0x10,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x01, +0x02,0x01,0x01,0x12,0x03,0x10,0x09,0x12,0x0a,0x0c, +0x0a,0x05,0x04,0x01,0x02,0x01,0x03,0x12,0x03,0x10, +0x15,0x16,0x0a,0x0b,0x0a,0x04,0x04,0x01,0x02,0x02, +0x12,0x03,0x11,0x02,0x18,0x0a,0x0c,0x0a,0x05,0x04, +0x01,0x02,0x02,0x05,0x12,0x03,0x11,0x02,0x08,0x0a, +0x0c,0x0a,0x05,0x04,0x01,0x02,0x02,0x01,0x12,0x03, +0x11,0x09,0x13,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02, +0x02,0x03,0x12,0x03,0x11,0x16,0x17,0x0a,0x0b,0x0a, +0x04,0x04,0x01,0x02,0x03,0x12,0x03,0x12,0x02,0x18, +0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x03,0x05,0x12, +0x03,0x12,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x01, +0x02,0x03,0x01,0x12,0x03,0x12,0x09,0x13,0x0a,0x0c, +0x0a,0x05,0x04,0x01,0x02,0x03,0x03,0x12,0x03,0x12, +0x16,0x17,0x0a,0x0a,0x0a,0x02,0x04,0x02,0x12,0x04, +0x15,0x00,0x1b,0x01,0x0a,0x0a,0x0a,0x03,0x04,0x02, +0x01,0x12,0x03,0x15,0x08,0x23,0x0a,0x0b,0x0a,0x04, +0x04,0x02,0x02,0x00,0x12,0x03,0x16,0x02,0x10,0x0a, +0x0c,0x0a,0x05,0x04,0x02,0x02,0x00,0x05,0x12,0x03, +0x16,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02, +0x00,0x01,0x12,0x03,0x16,0x09,0x0b,0x0a,0x0c,0x0a, +0x05,0x04,0x02,0x02,0x00,0x03,0x12,0x03,0x16,0x0e, +0x0f,0x0a,0x0b,0x0a,0x04,0x04,0x02,0x02,0x01,0x12, +0x03,0x17,0x02,0x10,0x0a,0x0c,0x0a,0x05,0x04,0x02, +0x02,0x01,0x05,0x12,0x03,0x17,0x02,0x08,0x0a,0x0c, +0x0a,0x05,0x04,0x02,0x02,0x01,0x01,0x12,0x03,0x17, +0x09,0x0b,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x01, +0x03,0x12,0x03,0x17,0x0e,0x0f,0x0a,0x0b,0x0a,0x04, +0x04,0x02,0x02,0x02,0x12,0x03,0x18,0x02,0x10,0x0a, +0x0c,0x0a,0x05,0x04,0x02,0x02,0x02,0x05,0x12,0x03, +0x18,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02, +0x02,0x01,0x12,0x03,0x18,0x09,0x0b,0x0a,0x0c,0x0a, +0x05,0x04,0x02,0x02,0x02,0x03,0x12,0x03,0x18,0x0e, +0x0f,0x0a,0x0b,0x0a,0x04,0x04,0x02,0x02,0x03,0x12, +0x03,0x19,0x02,0x10,0x0a,0x0c,0x0a,0x05,0x04,0x02, +0x02,0x03,0x05,0x12,0x03,0x19,0x02,0x08,0x0a,0x0c, +0x0a,0x05,0x04,0x02,0x02,0x03,0x01,0x12,0x03,0x19, +0x09,0x0b,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x03, +0x03,0x12,0x03,0x19,0x0e,0x0f,0x0a,0x0b,0x0a,0x04, +0x04,0x02,0x02,0x04,0x12,0x03,0x1a,0x02,0x10,0x0a, +0x0c,0x0a,0x05,0x04,0x02,0x02,0x04,0x05,0x12,0x03, +0x1a,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02, +0x04,0x01,0x12,0x03,0x1a,0x09,0x0b,0x0a,0x0c,0x0a, +0x05,0x04,0x02,0x02,0x04,0x03,0x12,0x03,0x1a,0x0e, +0x0f,0x0a,0x0a,0x0a,0x02,0x04,0x03,0x12,0x04,0x1d, +0x00,0x22,0x01,0x0a,0x0a,0x0a,0x03,0x04,0x03,0x01, +0x12,0x03,0x1d,0x08,0x26,0x0a,0x0b,0x0a,0x04,0x04, +0x03,0x02,0x00,0x12,0x03,0x1e,0x02,0x10,0x0a,0x0c, +0x0a,0x05,0x04,0x03,0x02,0x00,0x05,0x12,0x03,0x1e, +0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x00, +0x01,0x12,0x03,0x1e,0x09,0x0b,0x0a,0x0c,0x0a,0x05, +0x04,0x03,0x02,0x00,0x03,0x12,0x03,0x1e,0x0e,0x0f, +0x0a,0x0b,0x0a,0x04,0x04,0x03,0x02,0x01,0x12,0x03, +0x1f,0x02,0x10,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02, +0x01,0x05,0x12,0x03,0x1f,0x02,0x08,0x0a,0x0c,0x0a, +0x05,0x04,0x03,0x02,0x01,0x01,0x12,0x03,0x1f,0x09, +0x0b,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x01,0x03, +0x12,0x03,0x1f,0x0e,0x0f,0x0a,0x0b,0x0a,0x04,0x04, +0x03,0x02,0x02,0x12,0x03,0x20,0x02,0x10,0x0a,0x0c, +0x0a,0x05,0x04,0x03,0x02,0x02,0x05,0x12,0x03,0x20, +0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x02, +0x01,0x12,0x03,0x20,0x09,0x0b,0x0a,0x0c,0x0a,0x05, +0x04,0x03,0x02,0x02,0x03,0x12,0x03,0x20,0x0e,0x0f, +0x0a,0x0b,0x0a,0x04,0x04,0x03,0x02,0x03,0x12,0x03, +0x21,0x02,0x10,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02, +0x03,0x05,0x12,0x03,0x21,0x02,0x08,0x0a,0x0c,0x0a, +0x05,0x04,0x03,0x02,0x03,0x01,0x12,0x03,0x21,0x09, +0x0b,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x03,0x03, +0x12,0x03,0x21,0x0e,0x0f,0x0a,0x0a,0x0a,0x02,0x04, +0x04,0x12,0x04,0x24,0x00,0x27,0x01,0x0a,0x0a,0x0a, +0x03,0x04,0x04,0x01,0x12,0x03,0x24,0x08,0x2e,0x0a, +0x0b,0x0a,0x04,0x04,0x04,0x02,0x00,0x12,0x03,0x25, +0x02,0x12,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x00, +0x05,0x12,0x03,0x25,0x02,0x08,0x0a,0x0c,0x0a,0x05, +0x04,0x04,0x02,0x00,0x01,0x12,0x03,0x25,0x09,0x0d, +0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x00,0x03,0x12, +0x03,0x25,0x10,0x11,0x0a,0x0b,0x0a,0x04,0x04,0x04, +0x02,0x01,0x12,0x03,0x26,0x02,0x13,0x0a,0x0c,0x0a, +0x05,0x04,0x04,0x02,0x01,0x05,0x12,0x03,0x26,0x02, +0x08,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x01,0x01, +0x12,0x03,0x26,0x09,0x0e,0x0a,0x0c,0x0a,0x05,0x04, +0x04,0x02,0x01,0x03,0x12,0x03,0x26,0x11,0x12,0x62, +0x06,0x70,0x72,0x6f,0x74,0x6f,0x33, +}; +static const char file_name[] = "controller.proto"; +static const char wpi_proto_ProtobufArmFeedforward_name[] = "wpi.proto.ProtobufArmFeedforward"; +std::string_view wpi_proto_ProtobufArmFeedforward::msg_name(void) noexcept { return wpi_proto_ProtobufArmFeedforward_name; } +pb_filedesc_t wpi_proto_ProtobufArmFeedforward::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufArmFeedforward, wpi_proto_ProtobufArmFeedforward, AUTO) + + +static const char wpi_proto_ProtobufDifferentialDriveFeedforward_name[] = "wpi.proto.ProtobufDifferentialDriveFeedforward"; +std::string_view wpi_proto_ProtobufDifferentialDriveFeedforward::msg_name(void) noexcept { return wpi_proto_ProtobufDifferentialDriveFeedforward_name; } +pb_filedesc_t wpi_proto_ProtobufDifferentialDriveFeedforward::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufDifferentialDriveFeedforward, wpi_proto_ProtobufDifferentialDriveFeedforward, AUTO) + + +static const char wpi_proto_ProtobufElevatorFeedforward_name[] = "wpi.proto.ProtobufElevatorFeedforward"; +std::string_view wpi_proto_ProtobufElevatorFeedforward::msg_name(void) noexcept { return wpi_proto_ProtobufElevatorFeedforward_name; } +pb_filedesc_t wpi_proto_ProtobufElevatorFeedforward::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufElevatorFeedforward, wpi_proto_ProtobufElevatorFeedforward, AUTO) + + +static const char wpi_proto_ProtobufSimpleMotorFeedforward_name[] = "wpi.proto.ProtobufSimpleMotorFeedforward"; +std::string_view wpi_proto_ProtobufSimpleMotorFeedforward::msg_name(void) noexcept { return wpi_proto_ProtobufSimpleMotorFeedforward_name; } +pb_filedesc_t wpi_proto_ProtobufSimpleMotorFeedforward::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufSimpleMotorFeedforward, wpi_proto_ProtobufSimpleMotorFeedforward, AUTO) + + +static const char wpi_proto_ProtobufDifferentialDriveWheelVoltages_name[] = "wpi.proto.ProtobufDifferentialDriveWheelVoltages"; +std::string_view wpi_proto_ProtobufDifferentialDriveWheelVoltages::msg_name(void) noexcept { return wpi_proto_ProtobufDifferentialDriveWheelVoltages_name; } +pb_filedesc_t wpi_proto_ProtobufDifferentialDriveWheelVoltages::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufDifferentialDriveWheelVoltages, wpi_proto_ProtobufDifferentialDriveWheelVoltages, AUTO) + + + +#ifndef PB_CONVERT_DOUBLE_FLOAT +/* On some platforms (such as AVR), double is really float. + * To be able to encode/decode double on these platforms, you need. + * to define PB_CONVERT_DOUBLE_FLOAT in pb.h or compiler command line. + */ +PB_STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES) +#endif + diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/controller.npb.h b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/controller.npb.h new file mode 100644 index 0000000000..3c18ee1ae8 --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/controller.npb.h @@ -0,0 +1,158 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb header */ +/* Generated by nanopb-0.4.9 */ + +#ifndef PB_WPI_PROTO_CONTROLLER_NPB_H_INCLUDED +#define PB_WPI_PROTO_CONTROLLER_NPB_H_INCLUDED +#include +#include +#include + +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +/* Struct definitions */ +typedef struct _wpi_proto_ProtobufArmFeedforward { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double ks; + double kg; + double kv; + double ka; + double dt; +} wpi_proto_ProtobufArmFeedforward; + +typedef struct _wpi_proto_ProtobufDifferentialDriveFeedforward { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double kv_linear; + double ka_linear; + double kv_angular; + double ka_angular; +} wpi_proto_ProtobufDifferentialDriveFeedforward; + +typedef struct _wpi_proto_ProtobufElevatorFeedforward { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double ks; + double kg; + double kv; + double ka; + double dt; +} wpi_proto_ProtobufElevatorFeedforward; + +typedef struct _wpi_proto_ProtobufSimpleMotorFeedforward { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double ks; + double kv; + double ka; + double dt; +} wpi_proto_ProtobufSimpleMotorFeedforward; + +typedef struct _wpi_proto_ProtobufDifferentialDriveWheelVoltages { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double left; + double right; +} wpi_proto_ProtobufDifferentialDriveWheelVoltages; + + +/* Initializer values for message structs */ +#define wpi_proto_ProtobufArmFeedforward_init_default {0, 0, 0, 0, 0} +#define wpi_proto_ProtobufDifferentialDriveFeedforward_init_default {0, 0, 0, 0} +#define wpi_proto_ProtobufElevatorFeedforward_init_default {0, 0, 0, 0, 0} +#define wpi_proto_ProtobufSimpleMotorFeedforward_init_default {0, 0, 0, 0} +#define wpi_proto_ProtobufDifferentialDriveWheelVoltages_init_default {0, 0} +#define wpi_proto_ProtobufArmFeedforward_init_zero {0, 0, 0, 0, 0} +#define wpi_proto_ProtobufDifferentialDriveFeedforward_init_zero {0, 0, 0, 0} +#define wpi_proto_ProtobufElevatorFeedforward_init_zero {0, 0, 0, 0, 0} +#define wpi_proto_ProtobufSimpleMotorFeedforward_init_zero {0, 0, 0, 0} +#define wpi_proto_ProtobufDifferentialDriveWheelVoltages_init_zero {0, 0} + +/* Field tags (for use in manual encoding/decoding) */ +#define wpi_proto_ProtobufArmFeedforward_ks_tag 1 +#define wpi_proto_ProtobufArmFeedforward_kg_tag 2 +#define wpi_proto_ProtobufArmFeedforward_kv_tag 3 +#define wpi_proto_ProtobufArmFeedforward_ka_tag 4 +#define wpi_proto_ProtobufArmFeedforward_dt_tag 5 +#define wpi_proto_ProtobufDifferentialDriveFeedforward_kv_linear_tag 1 +#define wpi_proto_ProtobufDifferentialDriveFeedforward_ka_linear_tag 2 +#define wpi_proto_ProtobufDifferentialDriveFeedforward_kv_angular_tag 3 +#define wpi_proto_ProtobufDifferentialDriveFeedforward_ka_angular_tag 4 +#define wpi_proto_ProtobufElevatorFeedforward_ks_tag 1 +#define wpi_proto_ProtobufElevatorFeedforward_kg_tag 2 +#define wpi_proto_ProtobufElevatorFeedforward_kv_tag 3 +#define wpi_proto_ProtobufElevatorFeedforward_ka_tag 4 +#define wpi_proto_ProtobufElevatorFeedforward_dt_tag 5 +#define wpi_proto_ProtobufSimpleMotorFeedforward_ks_tag 1 +#define wpi_proto_ProtobufSimpleMotorFeedforward_kv_tag 2 +#define wpi_proto_ProtobufSimpleMotorFeedforward_ka_tag 3 +#define wpi_proto_ProtobufSimpleMotorFeedforward_dt_tag 4 +#define wpi_proto_ProtobufDifferentialDriveWheelVoltages_left_tag 1 +#define wpi_proto_ProtobufDifferentialDriveWheelVoltages_right_tag 2 + +/* Struct field encoding specification for nanopb */ +#define wpi_proto_ProtobufArmFeedforward_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, ks, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, kg, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, kv, 3) \ +X(a, STATIC, SINGULAR, DOUBLE, ka, 4) \ +X(a, STATIC, SINGULAR, DOUBLE, dt, 5) +#define wpi_proto_ProtobufArmFeedforward_CALLBACK NULL +#define wpi_proto_ProtobufArmFeedforward_DEFAULT NULL + +#define wpi_proto_ProtobufDifferentialDriveFeedforward_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, kv_linear, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, ka_linear, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, kv_angular, 3) \ +X(a, STATIC, SINGULAR, DOUBLE, ka_angular, 4) +#define wpi_proto_ProtobufDifferentialDriveFeedforward_CALLBACK NULL +#define wpi_proto_ProtobufDifferentialDriveFeedforward_DEFAULT NULL + +#define wpi_proto_ProtobufElevatorFeedforward_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, ks, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, kg, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, kv, 3) \ +X(a, STATIC, SINGULAR, DOUBLE, ka, 4) \ +X(a, STATIC, SINGULAR, DOUBLE, dt, 5) +#define wpi_proto_ProtobufElevatorFeedforward_CALLBACK NULL +#define wpi_proto_ProtobufElevatorFeedforward_DEFAULT NULL + +#define wpi_proto_ProtobufSimpleMotorFeedforward_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, ks, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, kv, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, ka, 3) \ +X(a, STATIC, SINGULAR, DOUBLE, dt, 4) +#define wpi_proto_ProtobufSimpleMotorFeedforward_CALLBACK NULL +#define wpi_proto_ProtobufSimpleMotorFeedforward_DEFAULT NULL + +#define wpi_proto_ProtobufDifferentialDriveWheelVoltages_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, left, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, right, 2) +#define wpi_proto_ProtobufDifferentialDriveWheelVoltages_CALLBACK NULL +#define wpi_proto_ProtobufDifferentialDriveWheelVoltages_DEFAULT NULL + +/* Maximum encoded size of messages (where known) */ +#define WPI_PROTO_CONTROLLER_NPB_H_MAX_SIZE wpi_proto_ProtobufArmFeedforward_size +#define wpi_proto_ProtobufArmFeedforward_size 45 +#define wpi_proto_ProtobufDifferentialDriveFeedforward_size 36 +#define wpi_proto_ProtobufDifferentialDriveWheelVoltages_size 18 +#define wpi_proto_ProtobufElevatorFeedforward_size 45 +#define wpi_proto_ProtobufSimpleMotorFeedforward_size 36 + + +#endif diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry2d.npb.cpp b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry2d.npb.cpp new file mode 100644 index 0000000000..f726b40ac0 --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry2d.npb.cpp @@ -0,0 +1,256 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb constant definitions */ +/* Generated by nanopb-0.4.9 */ + +#include "geometry2d.npb.h" +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +#include +#include +static const uint8_t file_descriptor[] { +0x0a,0x10,0x67,0x65,0x6f,0x6d,0x65,0x74,0x72,0x79, +0x32,0x64,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x12,0x09, +0x77,0x70,0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x22, +0x33,0x0a,0x15,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75, +0x66,0x54,0x72,0x61,0x6e,0x73,0x6c,0x61,0x74,0x69, +0x6f,0x6e,0x32,0x64,0x12,0x0c,0x0a,0x01,0x78,0x18, +0x01,0x20,0x01,0x28,0x01,0x52,0x01,0x78,0x12,0x0c, +0x0a,0x01,0x79,0x18,0x02,0x20,0x01,0x28,0x01,0x52, +0x01,0x79,0x22,0x2a,0x0a,0x12,0x50,0x72,0x6f,0x74, +0x6f,0x62,0x75,0x66,0x52,0x6f,0x74,0x61,0x74,0x69, +0x6f,0x6e,0x32,0x64,0x12,0x14,0x0a,0x05,0x76,0x61, +0x6c,0x75,0x65,0x18,0x01,0x20,0x01,0x28,0x01,0x52, +0x05,0x76,0x61,0x6c,0x75,0x65,0x22,0x8f,0x01,0x0a, +0x0e,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x50, +0x6f,0x73,0x65,0x32,0x64,0x12,0x42,0x0a,0x0b,0x74, +0x72,0x61,0x6e,0x73,0x6c,0x61,0x74,0x69,0x6f,0x6e, +0x18,0x01,0x20,0x01,0x28,0x0b,0x32,0x20,0x2e,0x77, +0x70,0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e,0x50, +0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x54,0x72,0x61, +0x6e,0x73,0x6c,0x61,0x74,0x69,0x6f,0x6e,0x32,0x64, +0x52,0x0b,0x74,0x72,0x61,0x6e,0x73,0x6c,0x61,0x74, +0x69,0x6f,0x6e,0x12,0x39,0x0a,0x08,0x72,0x6f,0x74, +0x61,0x74,0x69,0x6f,0x6e,0x18,0x02,0x20,0x01,0x28, +0x0b,0x32,0x1d,0x2e,0x77,0x70,0x69,0x2e,0x70,0x72, +0x6f,0x74,0x6f,0x2e,0x50,0x72,0x6f,0x74,0x6f,0x62, +0x75,0x66,0x52,0x6f,0x74,0x61,0x74,0x69,0x6f,0x6e, +0x32,0x64,0x52,0x08,0x72,0x6f,0x74,0x61,0x74,0x69, +0x6f,0x6e,0x22,0x94,0x01,0x0a,0x13,0x50,0x72,0x6f, +0x74,0x6f,0x62,0x75,0x66,0x54,0x72,0x61,0x6e,0x73, +0x66,0x6f,0x72,0x6d,0x32,0x64,0x12,0x42,0x0a,0x0b, +0x74,0x72,0x61,0x6e,0x73,0x6c,0x61,0x74,0x69,0x6f, +0x6e,0x18,0x01,0x20,0x01,0x28,0x0b,0x32,0x20,0x2e, +0x77,0x70,0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e, +0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x54,0x72, +0x61,0x6e,0x73,0x6c,0x61,0x74,0x69,0x6f,0x6e,0x32, +0x64,0x52,0x0b,0x74,0x72,0x61,0x6e,0x73,0x6c,0x61, +0x74,0x69,0x6f,0x6e,0x12,0x39,0x0a,0x08,0x72,0x6f, +0x74,0x61,0x74,0x69,0x6f,0x6e,0x18,0x02,0x20,0x01, +0x28,0x0b,0x32,0x1d,0x2e,0x77,0x70,0x69,0x2e,0x70, +0x72,0x6f,0x74,0x6f,0x2e,0x50,0x72,0x6f,0x74,0x6f, +0x62,0x75,0x66,0x52,0x6f,0x74,0x61,0x74,0x69,0x6f, +0x6e,0x32,0x64,0x52,0x08,0x72,0x6f,0x74,0x61,0x74, +0x69,0x6f,0x6e,0x22,0x49,0x0a,0x0f,0x50,0x72,0x6f, +0x74,0x6f,0x62,0x75,0x66,0x54,0x77,0x69,0x73,0x74, +0x32,0x64,0x12,0x0e,0x0a,0x02,0x64,0x78,0x18,0x01, +0x20,0x01,0x28,0x01,0x52,0x02,0x64,0x78,0x12,0x0e, +0x0a,0x02,0x64,0x79,0x18,0x02,0x20,0x01,0x28,0x01, +0x52,0x02,0x64,0x79,0x12,0x16,0x0a,0x06,0x64,0x74, +0x68,0x65,0x74,0x61,0x18,0x03,0x20,0x01,0x28,0x01, +0x52,0x06,0x64,0x74,0x68,0x65,0x74,0x61,0x22,0x78, +0x0a,0x13,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66, +0x52,0x65,0x63,0x74,0x61,0x6e,0x67,0x6c,0x65,0x32, +0x64,0x12,0x31,0x0a,0x06,0x63,0x65,0x6e,0x74,0x65, +0x72,0x18,0x01,0x20,0x01,0x28,0x0b,0x32,0x19,0x2e, +0x77,0x70,0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e, +0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x50,0x6f, +0x73,0x65,0x32,0x64,0x52,0x06,0x63,0x65,0x6e,0x74, +0x65,0x72,0x12,0x16,0x0a,0x06,0x78,0x57,0x69,0x64, +0x74,0x68,0x18,0x02,0x20,0x01,0x28,0x01,0x52,0x06, +0x78,0x57,0x69,0x64,0x74,0x68,0x12,0x16,0x0a,0x06, +0x79,0x57,0x69,0x64,0x74,0x68,0x18,0x03,0x20,0x01, +0x28,0x01,0x52,0x06,0x79,0x57,0x69,0x64,0x74,0x68, +0x22,0x82,0x01,0x0a,0x11,0x50,0x72,0x6f,0x74,0x6f, +0x62,0x75,0x66,0x45,0x6c,0x6c,0x69,0x70,0x73,0x65, +0x32,0x64,0x12,0x31,0x0a,0x06,0x63,0x65,0x6e,0x74, +0x65,0x72,0x18,0x01,0x20,0x01,0x28,0x0b,0x32,0x19, +0x2e,0x77,0x70,0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f, +0x2e,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x50, +0x6f,0x73,0x65,0x32,0x64,0x52,0x06,0x63,0x65,0x6e, +0x74,0x65,0x72,0x12,0x1c,0x0a,0x09,0x78,0x53,0x65, +0x6d,0x69,0x41,0x78,0x69,0x73,0x18,0x02,0x20,0x01, +0x28,0x01,0x52,0x09,0x78,0x53,0x65,0x6d,0x69,0x41, +0x78,0x69,0x73,0x12,0x1c,0x0a,0x09,0x79,0x53,0x65, +0x6d,0x69,0x41,0x78,0x69,0x73,0x18,0x03,0x20,0x01, +0x28,0x01,0x52,0x09,0x79,0x53,0x65,0x6d,0x69,0x41, +0x78,0x69,0x73,0x42,0x1a,0x0a,0x18,0x65,0x64,0x75, +0x2e,0x77,0x70,0x69,0x2e,0x66,0x69,0x72,0x73,0x74, +0x2e,0x6d,0x61,0x74,0x68,0x2e,0x70,0x72,0x6f,0x74, +0x6f,0x4a,0xc9,0x08,0x0a,0x06,0x12,0x04,0x00,0x00, +0x29,0x01,0x0a,0x08,0x0a,0x01,0x0c,0x12,0x03,0x00, +0x00,0x12,0x0a,0x08,0x0a,0x01,0x02,0x12,0x03,0x02, +0x00,0x12,0x0a,0x08,0x0a,0x01,0x08,0x12,0x03,0x04, +0x00,0x31,0x0a,0x09,0x0a,0x02,0x08,0x01,0x12,0x03, +0x04,0x00,0x31,0x0a,0x0a,0x0a,0x02,0x04,0x00,0x12, +0x04,0x06,0x00,0x09,0x01,0x0a,0x0a,0x0a,0x03,0x04, +0x00,0x01,0x12,0x03,0x06,0x08,0x1d,0x0a,0x0b,0x0a, +0x04,0x04,0x00,0x02,0x00,0x12,0x03,0x07,0x02,0x0f, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x00,0x05,0x12, +0x03,0x07,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x00, +0x02,0x00,0x01,0x12,0x03,0x07,0x09,0x0a,0x0a,0x0c, +0x0a,0x05,0x04,0x00,0x02,0x00,0x03,0x12,0x03,0x07, +0x0d,0x0e,0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02,0x01, +0x12,0x03,0x08,0x02,0x0f,0x0a,0x0c,0x0a,0x05,0x04, +0x00,0x02,0x01,0x05,0x12,0x03,0x08,0x02,0x08,0x0a, +0x0c,0x0a,0x05,0x04,0x00,0x02,0x01,0x01,0x12,0x03, +0x08,0x09,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02, +0x01,0x03,0x12,0x03,0x08,0x0d,0x0e,0x0a,0x0a,0x0a, +0x02,0x04,0x01,0x12,0x04,0x0b,0x00,0x0d,0x01,0x0a, +0x0a,0x0a,0x03,0x04,0x01,0x01,0x12,0x03,0x0b,0x08, +0x1a,0x0a,0x0b,0x0a,0x04,0x04,0x01,0x02,0x00,0x12, +0x03,0x0c,0x02,0x13,0x0a,0x0c,0x0a,0x05,0x04,0x01, +0x02,0x00,0x05,0x12,0x03,0x0c,0x02,0x08,0x0a,0x0c, +0x0a,0x05,0x04,0x01,0x02,0x00,0x01,0x12,0x03,0x0c, +0x09,0x0e,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x00, +0x03,0x12,0x03,0x0c,0x11,0x12,0x0a,0x0a,0x0a,0x02, +0x04,0x02,0x12,0x04,0x0f,0x00,0x12,0x01,0x0a,0x0a, +0x0a,0x03,0x04,0x02,0x01,0x12,0x03,0x0f,0x08,0x16, +0x0a,0x0b,0x0a,0x04,0x04,0x02,0x02,0x00,0x12,0x03, +0x10,0x02,0x28,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02, +0x00,0x06,0x12,0x03,0x10,0x02,0x17,0x0a,0x0c,0x0a, +0x05,0x04,0x02,0x02,0x00,0x01,0x12,0x03,0x10,0x18, +0x23,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x00,0x03, +0x12,0x03,0x10,0x26,0x27,0x0a,0x0b,0x0a,0x04,0x04, +0x02,0x02,0x01,0x12,0x03,0x11,0x02,0x22,0x0a,0x0c, +0x0a,0x05,0x04,0x02,0x02,0x01,0x06,0x12,0x03,0x11, +0x02,0x14,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x01, +0x01,0x12,0x03,0x11,0x15,0x1d,0x0a,0x0c,0x0a,0x05, +0x04,0x02,0x02,0x01,0x03,0x12,0x03,0x11,0x20,0x21, +0x0a,0x0a,0x0a,0x02,0x04,0x03,0x12,0x04,0x14,0x00, +0x17,0x01,0x0a,0x0a,0x0a,0x03,0x04,0x03,0x01,0x12, +0x03,0x14,0x08,0x1b,0x0a,0x0b,0x0a,0x04,0x04,0x03, +0x02,0x00,0x12,0x03,0x15,0x02,0x28,0x0a,0x0c,0x0a, +0x05,0x04,0x03,0x02,0x00,0x06,0x12,0x03,0x15,0x02, +0x17,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x00,0x01, +0x12,0x03,0x15,0x18,0x23,0x0a,0x0c,0x0a,0x05,0x04, +0x03,0x02,0x00,0x03,0x12,0x03,0x15,0x26,0x27,0x0a, +0x0b,0x0a,0x04,0x04,0x03,0x02,0x01,0x12,0x03,0x16, +0x02,0x22,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x01, +0x06,0x12,0x03,0x16,0x02,0x14,0x0a,0x0c,0x0a,0x05, +0x04,0x03,0x02,0x01,0x01,0x12,0x03,0x16,0x15,0x1d, +0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x01,0x03,0x12, +0x03,0x16,0x20,0x21,0x0a,0x0a,0x0a,0x02,0x04,0x04, +0x12,0x04,0x19,0x00,0x1d,0x01,0x0a,0x0a,0x0a,0x03, +0x04,0x04,0x01,0x12,0x03,0x19,0x08,0x17,0x0a,0x0b, +0x0a,0x04,0x04,0x04,0x02,0x00,0x12,0x03,0x1a,0x02, +0x10,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x00,0x05, +0x12,0x03,0x1a,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04, +0x04,0x02,0x00,0x01,0x12,0x03,0x1a,0x09,0x0b,0x0a, +0x0c,0x0a,0x05,0x04,0x04,0x02,0x00,0x03,0x12,0x03, +0x1a,0x0e,0x0f,0x0a,0x0b,0x0a,0x04,0x04,0x04,0x02, +0x01,0x12,0x03,0x1b,0x02,0x10,0x0a,0x0c,0x0a,0x05, +0x04,0x04,0x02,0x01,0x05,0x12,0x03,0x1b,0x02,0x08, +0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x01,0x01,0x12, +0x03,0x1b,0x09,0x0b,0x0a,0x0c,0x0a,0x05,0x04,0x04, +0x02,0x01,0x03,0x12,0x03,0x1b,0x0e,0x0f,0x0a,0x0b, +0x0a,0x04,0x04,0x04,0x02,0x02,0x12,0x03,0x1c,0x02, +0x14,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x02,0x05, +0x12,0x03,0x1c,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04, +0x04,0x02,0x02,0x01,0x12,0x03,0x1c,0x09,0x0f,0x0a, +0x0c,0x0a,0x05,0x04,0x04,0x02,0x02,0x03,0x12,0x03, +0x1c,0x12,0x13,0x0a,0x0a,0x0a,0x02,0x04,0x05,0x12, +0x04,0x1f,0x00,0x23,0x01,0x0a,0x0a,0x0a,0x03,0x04, +0x05,0x01,0x12,0x03,0x1f,0x08,0x1b,0x0a,0x0b,0x0a, +0x04,0x04,0x05,0x02,0x00,0x12,0x03,0x20,0x02,0x1c, +0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x00,0x06,0x12, +0x03,0x20,0x02,0x10,0x0a,0x0c,0x0a,0x05,0x04,0x05, +0x02,0x00,0x01,0x12,0x03,0x20,0x11,0x17,0x0a,0x0c, +0x0a,0x05,0x04,0x05,0x02,0x00,0x03,0x12,0x03,0x20, +0x1a,0x1b,0x0a,0x0b,0x0a,0x04,0x04,0x05,0x02,0x01, +0x12,0x03,0x21,0x02,0x14,0x0a,0x0c,0x0a,0x05,0x04, +0x05,0x02,0x01,0x05,0x12,0x03,0x21,0x02,0x08,0x0a, +0x0c,0x0a,0x05,0x04,0x05,0x02,0x01,0x01,0x12,0x03, +0x21,0x09,0x0f,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02, +0x01,0x03,0x12,0x03,0x21,0x12,0x13,0x0a,0x0b,0x0a, +0x04,0x04,0x05,0x02,0x02,0x12,0x03,0x22,0x02,0x14, +0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x02,0x05,0x12, +0x03,0x22,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x05, +0x02,0x02,0x01,0x12,0x03,0x22,0x09,0x0f,0x0a,0x0c, +0x0a,0x05,0x04,0x05,0x02,0x02,0x03,0x12,0x03,0x22, +0x12,0x13,0x0a,0x0a,0x0a,0x02,0x04,0x06,0x12,0x04, +0x25,0x00,0x29,0x01,0x0a,0x0a,0x0a,0x03,0x04,0x06, +0x01,0x12,0x03,0x25,0x08,0x19,0x0a,0x0b,0x0a,0x04, +0x04,0x06,0x02,0x00,0x12,0x03,0x26,0x02,0x1c,0x0a, +0x0c,0x0a,0x05,0x04,0x06,0x02,0x00,0x06,0x12,0x03, +0x26,0x02,0x10,0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02, +0x00,0x01,0x12,0x03,0x26,0x11,0x17,0x0a,0x0c,0x0a, +0x05,0x04,0x06,0x02,0x00,0x03,0x12,0x03,0x26,0x1a, +0x1b,0x0a,0x0b,0x0a,0x04,0x04,0x06,0x02,0x01,0x12, +0x03,0x27,0x02,0x17,0x0a,0x0c,0x0a,0x05,0x04,0x06, +0x02,0x01,0x05,0x12,0x03,0x27,0x02,0x08,0x0a,0x0c, +0x0a,0x05,0x04,0x06,0x02,0x01,0x01,0x12,0x03,0x27, +0x09,0x12,0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,0x01, +0x03,0x12,0x03,0x27,0x15,0x16,0x0a,0x0b,0x0a,0x04, +0x04,0x06,0x02,0x02,0x12,0x03,0x28,0x02,0x17,0x0a, +0x0c,0x0a,0x05,0x04,0x06,0x02,0x02,0x05,0x12,0x03, +0x28,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02, +0x02,0x01,0x12,0x03,0x28,0x09,0x12,0x0a,0x0c,0x0a, +0x05,0x04,0x06,0x02,0x02,0x03,0x12,0x03,0x28,0x15, +0x16,0x62,0x06,0x70,0x72,0x6f,0x74,0x6f,0x33, +}; +static const char file_name[] = "geometry2d.proto"; +static const char wpi_proto_ProtobufTranslation2d_name[] = "wpi.proto.ProtobufTranslation2d"; +std::string_view wpi_proto_ProtobufTranslation2d::msg_name(void) noexcept { return wpi_proto_ProtobufTranslation2d_name; } +pb_filedesc_t wpi_proto_ProtobufTranslation2d::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufTranslation2d, wpi_proto_ProtobufTranslation2d, AUTO) + + +static const char wpi_proto_ProtobufRotation2d_name[] = "wpi.proto.ProtobufRotation2d"; +std::string_view wpi_proto_ProtobufRotation2d::msg_name(void) noexcept { return wpi_proto_ProtobufRotation2d_name; } +pb_filedesc_t wpi_proto_ProtobufRotation2d::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufRotation2d, wpi_proto_ProtobufRotation2d, AUTO) + + +static const char wpi_proto_ProtobufPose2d_name[] = "wpi.proto.ProtobufPose2d"; +std::string_view wpi_proto_ProtobufPose2d::msg_name(void) noexcept { return wpi_proto_ProtobufPose2d_name; } +pb_filedesc_t wpi_proto_ProtobufPose2d::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufPose2d, wpi_proto_ProtobufPose2d, AUTO) + + +static const char wpi_proto_ProtobufTransform2d_name[] = "wpi.proto.ProtobufTransform2d"; +std::string_view wpi_proto_ProtobufTransform2d::msg_name(void) noexcept { return wpi_proto_ProtobufTransform2d_name; } +pb_filedesc_t wpi_proto_ProtobufTransform2d::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufTransform2d, wpi_proto_ProtobufTransform2d, AUTO) + + +static const char wpi_proto_ProtobufTwist2d_name[] = "wpi.proto.ProtobufTwist2d"; +std::string_view wpi_proto_ProtobufTwist2d::msg_name(void) noexcept { return wpi_proto_ProtobufTwist2d_name; } +pb_filedesc_t wpi_proto_ProtobufTwist2d::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufTwist2d, wpi_proto_ProtobufTwist2d, AUTO) + + +static const char wpi_proto_ProtobufRectangle2d_name[] = "wpi.proto.ProtobufRectangle2d"; +std::string_view wpi_proto_ProtobufRectangle2d::msg_name(void) noexcept { return wpi_proto_ProtobufRectangle2d_name; } +pb_filedesc_t wpi_proto_ProtobufRectangle2d::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufRectangle2d, wpi_proto_ProtobufRectangle2d, AUTO) + + +static const char wpi_proto_ProtobufEllipse2d_name[] = "wpi.proto.ProtobufEllipse2d"; +std::string_view wpi_proto_ProtobufEllipse2d::msg_name(void) noexcept { return wpi_proto_ProtobufEllipse2d_name; } +pb_filedesc_t wpi_proto_ProtobufEllipse2d::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufEllipse2d, wpi_proto_ProtobufEllipse2d, AUTO) + + + +#ifndef PB_CONVERT_DOUBLE_FLOAT +/* On some platforms (such as AVR), double is really float. + * To be able to encode/decode double on these platforms, you need. + * to define PB_CONVERT_DOUBLE_FLOAT in pb.h or compiler command line. + */ +PB_STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES) +#endif + diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry2d.npb.h b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry2d.npb.h new file mode 100644 index 0000000000..717a7abf2f --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry2d.npb.h @@ -0,0 +1,180 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb header */ +/* Generated by nanopb-0.4.9 */ + +#ifndef PB_WPI_PROTO_GEOMETRY2D_NPB_H_INCLUDED +#define PB_WPI_PROTO_GEOMETRY2D_NPB_H_INCLUDED +#include +#include +#include + +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +/* Struct definitions */ +typedef struct _wpi_proto_ProtobufTranslation2d { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double x; + double y; +} wpi_proto_ProtobufTranslation2d; + +typedef struct _wpi_proto_ProtobufRotation2d { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double value; +} wpi_proto_ProtobufRotation2d; + +typedef struct _wpi_proto_ProtobufPose2d { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + pb_callback_t translation; + pb_callback_t rotation; +} wpi_proto_ProtobufPose2d; + +typedef struct _wpi_proto_ProtobufTransform2d { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + pb_callback_t translation; + pb_callback_t rotation; +} wpi_proto_ProtobufTransform2d; + +typedef struct _wpi_proto_ProtobufTwist2d { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double dx; + double dy; + double dtheta; +} wpi_proto_ProtobufTwist2d; + +typedef struct _wpi_proto_ProtobufRectangle2d { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + pb_callback_t center; + double xWidth; + double yWidth; +} wpi_proto_ProtobufRectangle2d; + +typedef struct _wpi_proto_ProtobufEllipse2d { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + pb_callback_t center; + double xSemiAxis; + double ySemiAxis; +} wpi_proto_ProtobufEllipse2d; + + +/* Initializer values for message structs */ +#define wpi_proto_ProtobufTranslation2d_init_default {0, 0} +#define wpi_proto_ProtobufRotation2d_init_default {0} +#define wpi_proto_ProtobufPose2d_init_default {{{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_ProtobufTransform2d_init_default {{{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_ProtobufTwist2d_init_default {0, 0, 0} +#define wpi_proto_ProtobufRectangle2d_init_default {{{NULL}, NULL}, 0, 0} +#define wpi_proto_ProtobufEllipse2d_init_default {{{NULL}, NULL}, 0, 0} +#define wpi_proto_ProtobufTranslation2d_init_zero {0, 0} +#define wpi_proto_ProtobufRotation2d_init_zero {0} +#define wpi_proto_ProtobufPose2d_init_zero {{{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_ProtobufTransform2d_init_zero {{{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_ProtobufTwist2d_init_zero {0, 0, 0} +#define wpi_proto_ProtobufRectangle2d_init_zero {{{NULL}, NULL}, 0, 0} +#define wpi_proto_ProtobufEllipse2d_init_zero {{{NULL}, NULL}, 0, 0} + +/* Field tags (for use in manual encoding/decoding) */ +#define wpi_proto_ProtobufTranslation2d_x_tag 1 +#define wpi_proto_ProtobufTranslation2d_y_tag 2 +#define wpi_proto_ProtobufRotation2d_value_tag 1 +#define wpi_proto_ProtobufPose2d_translation_tag 1 +#define wpi_proto_ProtobufPose2d_rotation_tag 2 +#define wpi_proto_ProtobufTransform2d_translation_tag 1 +#define wpi_proto_ProtobufTransform2d_rotation_tag 2 +#define wpi_proto_ProtobufTwist2d_dx_tag 1 +#define wpi_proto_ProtobufTwist2d_dy_tag 2 +#define wpi_proto_ProtobufTwist2d_dtheta_tag 3 +#define wpi_proto_ProtobufRectangle2d_center_tag 1 +#define wpi_proto_ProtobufRectangle2d_xWidth_tag 2 +#define wpi_proto_ProtobufRectangle2d_yWidth_tag 3 +#define wpi_proto_ProtobufEllipse2d_center_tag 1 +#define wpi_proto_ProtobufEllipse2d_xSemiAxis_tag 2 +#define wpi_proto_ProtobufEllipse2d_ySemiAxis_tag 3 + +/* Struct field encoding specification for nanopb */ +#define wpi_proto_ProtobufTranslation2d_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, x, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, y, 2) +#define wpi_proto_ProtobufTranslation2d_CALLBACK NULL +#define wpi_proto_ProtobufTranslation2d_DEFAULT NULL + +#define wpi_proto_ProtobufRotation2d_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, value, 1) +#define wpi_proto_ProtobufRotation2d_CALLBACK NULL +#define wpi_proto_ProtobufRotation2d_DEFAULT NULL + +#define wpi_proto_ProtobufPose2d_FIELDLIST(X, a) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, translation, 1) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, rotation, 2) +#define wpi_proto_ProtobufPose2d_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufPose2d_DEFAULT NULL +#define wpi_proto_ProtobufPose2d_translation_MSGTYPE wpi_proto_ProtobufTranslation2d +#define wpi_proto_ProtobufPose2d_rotation_MSGTYPE wpi_proto_ProtobufRotation2d + +#define wpi_proto_ProtobufTransform2d_FIELDLIST(X, a) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, translation, 1) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, rotation, 2) +#define wpi_proto_ProtobufTransform2d_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufTransform2d_DEFAULT NULL +#define wpi_proto_ProtobufTransform2d_translation_MSGTYPE wpi_proto_ProtobufTranslation2d +#define wpi_proto_ProtobufTransform2d_rotation_MSGTYPE wpi_proto_ProtobufRotation2d + +#define wpi_proto_ProtobufTwist2d_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, dx, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, dy, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, dtheta, 3) +#define wpi_proto_ProtobufTwist2d_CALLBACK NULL +#define wpi_proto_ProtobufTwist2d_DEFAULT NULL + +#define wpi_proto_ProtobufRectangle2d_FIELDLIST(X, a) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, center, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, xWidth, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, yWidth, 3) +#define wpi_proto_ProtobufRectangle2d_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufRectangle2d_DEFAULT NULL +#define wpi_proto_ProtobufRectangle2d_center_MSGTYPE wpi_proto_ProtobufPose2d + +#define wpi_proto_ProtobufEllipse2d_FIELDLIST(X, a) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, center, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, xSemiAxis, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, ySemiAxis, 3) +#define wpi_proto_ProtobufEllipse2d_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufEllipse2d_DEFAULT NULL +#define wpi_proto_ProtobufEllipse2d_center_MSGTYPE wpi_proto_ProtobufPose2d + +/* Maximum encoded size of messages (where known) */ +/* wpi_proto_ProtobufPose2d_size depends on runtime parameters */ +/* wpi_proto_ProtobufTransform2d_size depends on runtime parameters */ +/* wpi_proto_ProtobufRectangle2d_size depends on runtime parameters */ +/* wpi_proto_ProtobufEllipse2d_size depends on runtime parameters */ +#define WPI_PROTO_GEOMETRY2D_NPB_H_MAX_SIZE wpi_proto_ProtobufTwist2d_size +#define wpi_proto_ProtobufRotation2d_size 9 +#define wpi_proto_ProtobufTranslation2d_size 18 +#define wpi_proto_ProtobufTwist2d_size 27 + + +#endif diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry3d.npb.cpp b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry3d.npb.cpp new file mode 100644 index 0000000000..cb995e9fd6 --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry3d.npb.cpp @@ -0,0 +1,249 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb constant definitions */ +/* Generated by nanopb-0.4.9 */ + +#include "geometry3d.npb.h" +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +#include +#include +static const uint8_t file_descriptor[] { +0x0a,0x10,0x67,0x65,0x6f,0x6d,0x65,0x74,0x72,0x79, +0x33,0x64,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x12,0x09, +0x77,0x70,0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x22, +0x41,0x0a,0x15,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75, +0x66,0x54,0x72,0x61,0x6e,0x73,0x6c,0x61,0x74,0x69, +0x6f,0x6e,0x33,0x64,0x12,0x0c,0x0a,0x01,0x78,0x18, +0x01,0x20,0x01,0x28,0x01,0x52,0x01,0x78,0x12,0x0c, +0x0a,0x01,0x79,0x18,0x02,0x20,0x01,0x28,0x01,0x52, +0x01,0x79,0x12,0x0c,0x0a,0x01,0x7a,0x18,0x03,0x20, +0x01,0x28,0x01,0x52,0x01,0x7a,0x22,0x4c,0x0a,0x12, +0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x51,0x75, +0x61,0x74,0x65,0x72,0x6e,0x69,0x6f,0x6e,0x12,0x0c, +0x0a,0x01,0x77,0x18,0x01,0x20,0x01,0x28,0x01,0x52, +0x01,0x77,0x12,0x0c,0x0a,0x01,0x78,0x18,0x02,0x20, +0x01,0x28,0x01,0x52,0x01,0x78,0x12,0x0c,0x0a,0x01, +0x79,0x18,0x03,0x20,0x01,0x28,0x01,0x52,0x01,0x79, +0x12,0x0c,0x0a,0x01,0x7a,0x18,0x04,0x20,0x01,0x28, +0x01,0x52,0x01,0x7a,0x22,0x41,0x0a,0x12,0x50,0x72, +0x6f,0x74,0x6f,0x62,0x75,0x66,0x52,0x6f,0x74,0x61, +0x74,0x69,0x6f,0x6e,0x33,0x64,0x12,0x2b,0x0a,0x01, +0x71,0x18,0x01,0x20,0x01,0x28,0x0b,0x32,0x1d,0x2e, +0x77,0x70,0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e, +0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x51,0x75, +0x61,0x74,0x65,0x72,0x6e,0x69,0x6f,0x6e,0x52,0x01, +0x71,0x22,0x8f,0x01,0x0a,0x0e,0x50,0x72,0x6f,0x74, +0x6f,0x62,0x75,0x66,0x50,0x6f,0x73,0x65,0x33,0x64, +0x12,0x42,0x0a,0x0b,0x74,0x72,0x61,0x6e,0x73,0x6c, +0x61,0x74,0x69,0x6f,0x6e,0x18,0x01,0x20,0x01,0x28, +0x0b,0x32,0x20,0x2e,0x77,0x70,0x69,0x2e,0x70,0x72, +0x6f,0x74,0x6f,0x2e,0x50,0x72,0x6f,0x74,0x6f,0x62, +0x75,0x66,0x54,0x72,0x61,0x6e,0x73,0x6c,0x61,0x74, +0x69,0x6f,0x6e,0x33,0x64,0x52,0x0b,0x74,0x72,0x61, +0x6e,0x73,0x6c,0x61,0x74,0x69,0x6f,0x6e,0x12,0x39, +0x0a,0x08,0x72,0x6f,0x74,0x61,0x74,0x69,0x6f,0x6e, +0x18,0x02,0x20,0x01,0x28,0x0b,0x32,0x1d,0x2e,0x77, +0x70,0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e,0x50, +0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x52,0x6f,0x74, +0x61,0x74,0x69,0x6f,0x6e,0x33,0x64,0x52,0x08,0x72, +0x6f,0x74,0x61,0x74,0x69,0x6f,0x6e,0x22,0x94,0x01, +0x0a,0x13,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66, +0x54,0x72,0x61,0x6e,0x73,0x66,0x6f,0x72,0x6d,0x33, +0x64,0x12,0x42,0x0a,0x0b,0x74,0x72,0x61,0x6e,0x73, +0x6c,0x61,0x74,0x69,0x6f,0x6e,0x18,0x01,0x20,0x01, +0x28,0x0b,0x32,0x20,0x2e,0x77,0x70,0x69,0x2e,0x70, +0x72,0x6f,0x74,0x6f,0x2e,0x50,0x72,0x6f,0x74,0x6f, +0x62,0x75,0x66,0x54,0x72,0x61,0x6e,0x73,0x6c,0x61, +0x74,0x69,0x6f,0x6e,0x33,0x64,0x52,0x0b,0x74,0x72, +0x61,0x6e,0x73,0x6c,0x61,0x74,0x69,0x6f,0x6e,0x12, +0x39,0x0a,0x08,0x72,0x6f,0x74,0x61,0x74,0x69,0x6f, +0x6e,0x18,0x02,0x20,0x01,0x28,0x0b,0x32,0x1d,0x2e, +0x77,0x70,0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e, +0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x52,0x6f, +0x74,0x61,0x74,0x69,0x6f,0x6e,0x33,0x64,0x52,0x08, +0x72,0x6f,0x74,0x61,0x74,0x69,0x6f,0x6e,0x22,0x71, +0x0a,0x0f,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66, +0x54,0x77,0x69,0x73,0x74,0x33,0x64,0x12,0x0e,0x0a, +0x02,0x64,0x78,0x18,0x01,0x20,0x01,0x28,0x01,0x52, +0x02,0x64,0x78,0x12,0x0e,0x0a,0x02,0x64,0x79,0x18, +0x02,0x20,0x01,0x28,0x01,0x52,0x02,0x64,0x79,0x12, +0x0e,0x0a,0x02,0x64,0x7a,0x18,0x03,0x20,0x01,0x28, +0x01,0x52,0x02,0x64,0x7a,0x12,0x0e,0x0a,0x02,0x72, +0x78,0x18,0x04,0x20,0x01,0x28,0x01,0x52,0x02,0x72, +0x78,0x12,0x0e,0x0a,0x02,0x72,0x79,0x18,0x05,0x20, +0x01,0x28,0x01,0x52,0x02,0x72,0x79,0x12,0x0e,0x0a, +0x02,0x72,0x7a,0x18,0x06,0x20,0x01,0x28,0x01,0x52, +0x02,0x72,0x7a,0x42,0x1a,0x0a,0x18,0x65,0x64,0x75, +0x2e,0x77,0x70,0x69,0x2e,0x66,0x69,0x72,0x73,0x74, +0x2e,0x6d,0x61,0x74,0x68,0x2e,0x70,0x72,0x6f,0x74, +0x6f,0x4a,0x9f,0x09,0x0a,0x06,0x12,0x04,0x00,0x00, +0x28,0x01,0x0a,0x08,0x0a,0x01,0x0c,0x12,0x03,0x00, +0x00,0x12,0x0a,0x08,0x0a,0x01,0x02,0x12,0x03,0x02, +0x00,0x12,0x0a,0x08,0x0a,0x01,0x08,0x12,0x03,0x04, +0x00,0x31,0x0a,0x09,0x0a,0x02,0x08,0x01,0x12,0x03, +0x04,0x00,0x31,0x0a,0x0a,0x0a,0x02,0x04,0x00,0x12, +0x04,0x06,0x00,0x0a,0x01,0x0a,0x0a,0x0a,0x03,0x04, +0x00,0x01,0x12,0x03,0x06,0x08,0x1d,0x0a,0x0b,0x0a, +0x04,0x04,0x00,0x02,0x00,0x12,0x03,0x07,0x02,0x0f, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x00,0x05,0x12, +0x03,0x07,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x00, +0x02,0x00,0x01,0x12,0x03,0x07,0x09,0x0a,0x0a,0x0c, +0x0a,0x05,0x04,0x00,0x02,0x00,0x03,0x12,0x03,0x07, +0x0d,0x0e,0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02,0x01, +0x12,0x03,0x08,0x02,0x0f,0x0a,0x0c,0x0a,0x05,0x04, +0x00,0x02,0x01,0x05,0x12,0x03,0x08,0x02,0x08,0x0a, +0x0c,0x0a,0x05,0x04,0x00,0x02,0x01,0x01,0x12,0x03, +0x08,0x09,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02, +0x01,0x03,0x12,0x03,0x08,0x0d,0x0e,0x0a,0x0b,0x0a, +0x04,0x04,0x00,0x02,0x02,0x12,0x03,0x09,0x02,0x0f, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x02,0x05,0x12, +0x03,0x09,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x00, +0x02,0x02,0x01,0x12,0x03,0x09,0x09,0x0a,0x0a,0x0c, +0x0a,0x05,0x04,0x00,0x02,0x02,0x03,0x12,0x03,0x09, +0x0d,0x0e,0x0a,0x0a,0x0a,0x02,0x04,0x01,0x12,0x04, +0x0c,0x00,0x11,0x01,0x0a,0x0a,0x0a,0x03,0x04,0x01, +0x01,0x12,0x03,0x0c,0x08,0x1a,0x0a,0x0b,0x0a,0x04, +0x04,0x01,0x02,0x00,0x12,0x03,0x0d,0x02,0x0f,0x0a, +0x0c,0x0a,0x05,0x04,0x01,0x02,0x00,0x05,0x12,0x03, +0x0d,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02, +0x00,0x01,0x12,0x03,0x0d,0x09,0x0a,0x0a,0x0c,0x0a, +0x05,0x04,0x01,0x02,0x00,0x03,0x12,0x03,0x0d,0x0d, +0x0e,0x0a,0x0b,0x0a,0x04,0x04,0x01,0x02,0x01,0x12, +0x03,0x0e,0x02,0x0f,0x0a,0x0c,0x0a,0x05,0x04,0x01, +0x02,0x01,0x05,0x12,0x03,0x0e,0x02,0x08,0x0a,0x0c, +0x0a,0x05,0x04,0x01,0x02,0x01,0x01,0x12,0x03,0x0e, +0x09,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x01, +0x03,0x12,0x03,0x0e,0x0d,0x0e,0x0a,0x0b,0x0a,0x04, +0x04,0x01,0x02,0x02,0x12,0x03,0x0f,0x02,0x0f,0x0a, +0x0c,0x0a,0x05,0x04,0x01,0x02,0x02,0x05,0x12,0x03, +0x0f,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02, +0x02,0x01,0x12,0x03,0x0f,0x09,0x0a,0x0a,0x0c,0x0a, +0x05,0x04,0x01,0x02,0x02,0x03,0x12,0x03,0x0f,0x0d, +0x0e,0x0a,0x0b,0x0a,0x04,0x04,0x01,0x02,0x03,0x12, +0x03,0x10,0x02,0x0f,0x0a,0x0c,0x0a,0x05,0x04,0x01, +0x02,0x03,0x05,0x12,0x03,0x10,0x02,0x08,0x0a,0x0c, +0x0a,0x05,0x04,0x01,0x02,0x03,0x01,0x12,0x03,0x10, +0x09,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x03, +0x03,0x12,0x03,0x10,0x0d,0x0e,0x0a,0x0a,0x0a,0x02, +0x04,0x02,0x12,0x04,0x13,0x00,0x15,0x01,0x0a,0x0a, +0x0a,0x03,0x04,0x02,0x01,0x12,0x03,0x13,0x08,0x1a, +0x0a,0x0b,0x0a,0x04,0x04,0x02,0x02,0x00,0x12,0x03, +0x14,0x02,0x1b,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02, +0x00,0x06,0x12,0x03,0x14,0x02,0x14,0x0a,0x0c,0x0a, +0x05,0x04,0x02,0x02,0x00,0x01,0x12,0x03,0x14,0x15, +0x16,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x00,0x03, +0x12,0x03,0x14,0x19,0x1a,0x0a,0x0a,0x0a,0x02,0x04, +0x03,0x12,0x04,0x17,0x00,0x1a,0x01,0x0a,0x0a,0x0a, +0x03,0x04,0x03,0x01,0x12,0x03,0x17,0x08,0x16,0x0a, +0x0b,0x0a,0x04,0x04,0x03,0x02,0x00,0x12,0x03,0x18, +0x02,0x28,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x00, +0x06,0x12,0x03,0x18,0x02,0x17,0x0a,0x0c,0x0a,0x05, +0x04,0x03,0x02,0x00,0x01,0x12,0x03,0x18,0x18,0x23, +0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x00,0x03,0x12, +0x03,0x18,0x26,0x27,0x0a,0x0b,0x0a,0x04,0x04,0x03, +0x02,0x01,0x12,0x03,0x19,0x02,0x22,0x0a,0x0c,0x0a, +0x05,0x04,0x03,0x02,0x01,0x06,0x12,0x03,0x19,0x02, +0x14,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x01,0x01, +0x12,0x03,0x19,0x15,0x1d,0x0a,0x0c,0x0a,0x05,0x04, +0x03,0x02,0x01,0x03,0x12,0x03,0x19,0x20,0x21,0x0a, +0x0a,0x0a,0x02,0x04,0x04,0x12,0x04,0x1c,0x00,0x1f, +0x01,0x0a,0x0a,0x0a,0x03,0x04,0x04,0x01,0x12,0x03, +0x1c,0x08,0x1b,0x0a,0x0b,0x0a,0x04,0x04,0x04,0x02, +0x00,0x12,0x03,0x1d,0x02,0x28,0x0a,0x0c,0x0a,0x05, +0x04,0x04,0x02,0x00,0x06,0x12,0x03,0x1d,0x02,0x17, +0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x00,0x01,0x12, +0x03,0x1d,0x18,0x23,0x0a,0x0c,0x0a,0x05,0x04,0x04, +0x02,0x00,0x03,0x12,0x03,0x1d,0x26,0x27,0x0a,0x0b, +0x0a,0x04,0x04,0x04,0x02,0x01,0x12,0x03,0x1e,0x02, +0x22,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x01,0x06, +0x12,0x03,0x1e,0x02,0x14,0x0a,0x0c,0x0a,0x05,0x04, +0x04,0x02,0x01,0x01,0x12,0x03,0x1e,0x15,0x1d,0x0a, +0x0c,0x0a,0x05,0x04,0x04,0x02,0x01,0x03,0x12,0x03, +0x1e,0x20,0x21,0x0a,0x0a,0x0a,0x02,0x04,0x05,0x12, +0x04,0x21,0x00,0x28,0x01,0x0a,0x0a,0x0a,0x03,0x04, +0x05,0x01,0x12,0x03,0x21,0x08,0x17,0x0a,0x0b,0x0a, +0x04,0x04,0x05,0x02,0x00,0x12,0x03,0x22,0x02,0x10, +0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x00,0x05,0x12, +0x03,0x22,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x05, +0x02,0x00,0x01,0x12,0x03,0x22,0x09,0x0b,0x0a,0x0c, +0x0a,0x05,0x04,0x05,0x02,0x00,0x03,0x12,0x03,0x22, +0x0e,0x0f,0x0a,0x0b,0x0a,0x04,0x04,0x05,0x02,0x01, +0x12,0x03,0x23,0x02,0x10,0x0a,0x0c,0x0a,0x05,0x04, +0x05,0x02,0x01,0x05,0x12,0x03,0x23,0x02,0x08,0x0a, +0x0c,0x0a,0x05,0x04,0x05,0x02,0x01,0x01,0x12,0x03, +0x23,0x09,0x0b,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02, +0x01,0x03,0x12,0x03,0x23,0x0e,0x0f,0x0a,0x0b,0x0a, +0x04,0x04,0x05,0x02,0x02,0x12,0x03,0x24,0x02,0x10, +0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x02,0x05,0x12, +0x03,0x24,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x05, +0x02,0x02,0x01,0x12,0x03,0x24,0x09,0x0b,0x0a,0x0c, +0x0a,0x05,0x04,0x05,0x02,0x02,0x03,0x12,0x03,0x24, +0x0e,0x0f,0x0a,0x0b,0x0a,0x04,0x04,0x05,0x02,0x03, +0x12,0x03,0x25,0x02,0x10,0x0a,0x0c,0x0a,0x05,0x04, +0x05,0x02,0x03,0x05,0x12,0x03,0x25,0x02,0x08,0x0a, +0x0c,0x0a,0x05,0x04,0x05,0x02,0x03,0x01,0x12,0x03, +0x25,0x09,0x0b,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02, +0x03,0x03,0x12,0x03,0x25,0x0e,0x0f,0x0a,0x0b,0x0a, +0x04,0x04,0x05,0x02,0x04,0x12,0x03,0x26,0x02,0x10, +0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x04,0x05,0x12, +0x03,0x26,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x05, +0x02,0x04,0x01,0x12,0x03,0x26,0x09,0x0b,0x0a,0x0c, +0x0a,0x05,0x04,0x05,0x02,0x04,0x03,0x12,0x03,0x26, +0x0e,0x0f,0x0a,0x0b,0x0a,0x04,0x04,0x05,0x02,0x05, +0x12,0x03,0x27,0x02,0x10,0x0a,0x0c,0x0a,0x05,0x04, +0x05,0x02,0x05,0x05,0x12,0x03,0x27,0x02,0x08,0x0a, +0x0c,0x0a,0x05,0x04,0x05,0x02,0x05,0x01,0x12,0x03, +0x27,0x09,0x0b,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02, +0x05,0x03,0x12,0x03,0x27,0x0e,0x0f,0x62,0x06,0x70, +0x72,0x6f,0x74,0x6f,0x33, +}; +static const char file_name[] = "geometry3d.proto"; +static const char wpi_proto_ProtobufTranslation3d_name[] = "wpi.proto.ProtobufTranslation3d"; +std::string_view wpi_proto_ProtobufTranslation3d::msg_name(void) noexcept { return wpi_proto_ProtobufTranslation3d_name; } +pb_filedesc_t wpi_proto_ProtobufTranslation3d::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufTranslation3d, wpi_proto_ProtobufTranslation3d, AUTO) + + +static const char wpi_proto_ProtobufQuaternion_name[] = "wpi.proto.ProtobufQuaternion"; +std::string_view wpi_proto_ProtobufQuaternion::msg_name(void) noexcept { return wpi_proto_ProtobufQuaternion_name; } +pb_filedesc_t wpi_proto_ProtobufQuaternion::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufQuaternion, wpi_proto_ProtobufQuaternion, AUTO) + + +static const char wpi_proto_ProtobufRotation3d_name[] = "wpi.proto.ProtobufRotation3d"; +std::string_view wpi_proto_ProtobufRotation3d::msg_name(void) noexcept { return wpi_proto_ProtobufRotation3d_name; } +pb_filedesc_t wpi_proto_ProtobufRotation3d::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufRotation3d, wpi_proto_ProtobufRotation3d, AUTO) + + +static const char wpi_proto_ProtobufPose3d_name[] = "wpi.proto.ProtobufPose3d"; +std::string_view wpi_proto_ProtobufPose3d::msg_name(void) noexcept { return wpi_proto_ProtobufPose3d_name; } +pb_filedesc_t wpi_proto_ProtobufPose3d::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufPose3d, wpi_proto_ProtobufPose3d, AUTO) + + +static const char wpi_proto_ProtobufTransform3d_name[] = "wpi.proto.ProtobufTransform3d"; +std::string_view wpi_proto_ProtobufTransform3d::msg_name(void) noexcept { return wpi_proto_ProtobufTransform3d_name; } +pb_filedesc_t wpi_proto_ProtobufTransform3d::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufTransform3d, wpi_proto_ProtobufTransform3d, AUTO) + + +static const char wpi_proto_ProtobufTwist3d_name[] = "wpi.proto.ProtobufTwist3d"; +std::string_view wpi_proto_ProtobufTwist3d::msg_name(void) noexcept { return wpi_proto_ProtobufTwist3d_name; } +pb_filedesc_t wpi_proto_ProtobufTwist3d::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufTwist3d, wpi_proto_ProtobufTwist3d, AUTO) + + + +#ifndef PB_CONVERT_DOUBLE_FLOAT +/* On some platforms (such as AVR), double is really float. + * To be able to encode/decode double on these platforms, you need. + * to define PB_CONVERT_DOUBLE_FLOAT in pb.h or compiler command line. + */ +PB_STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES) +#endif + diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry3d.npb.h b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry3d.npb.h new file mode 100644 index 0000000000..ffa77720ae --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/geometry3d.npb.h @@ -0,0 +1,171 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb header */ +/* Generated by nanopb-0.4.9 */ + +#ifndef PB_WPI_PROTO_GEOMETRY3D_NPB_H_INCLUDED +#define PB_WPI_PROTO_GEOMETRY3D_NPB_H_INCLUDED +#include +#include +#include + +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +/* Struct definitions */ +typedef struct _wpi_proto_ProtobufTranslation3d { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double x; + double y; + double z; +} wpi_proto_ProtobufTranslation3d; + +typedef struct _wpi_proto_ProtobufQuaternion { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double w; + double x; + double y; + double z; +} wpi_proto_ProtobufQuaternion; + +typedef struct _wpi_proto_ProtobufRotation3d { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + pb_callback_t q; +} wpi_proto_ProtobufRotation3d; + +typedef struct _wpi_proto_ProtobufPose3d { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + pb_callback_t translation; + pb_callback_t rotation; +} wpi_proto_ProtobufPose3d; + +typedef struct _wpi_proto_ProtobufTransform3d { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + pb_callback_t translation; + pb_callback_t rotation; +} wpi_proto_ProtobufTransform3d; + +typedef struct _wpi_proto_ProtobufTwist3d { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double dx; + double dy; + double dz; + double rx; + double ry; + double rz; +} wpi_proto_ProtobufTwist3d; + + +/* Initializer values for message structs */ +#define wpi_proto_ProtobufTranslation3d_init_default {0, 0, 0} +#define wpi_proto_ProtobufQuaternion_init_default {0, 0, 0, 0} +#define wpi_proto_ProtobufRotation3d_init_default {{{NULL}, NULL}} +#define wpi_proto_ProtobufPose3d_init_default {{{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_ProtobufTransform3d_init_default {{{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_ProtobufTwist3d_init_default {0, 0, 0, 0, 0, 0} +#define wpi_proto_ProtobufTranslation3d_init_zero {0, 0, 0} +#define wpi_proto_ProtobufQuaternion_init_zero {0, 0, 0, 0} +#define wpi_proto_ProtobufRotation3d_init_zero {{{NULL}, NULL}} +#define wpi_proto_ProtobufPose3d_init_zero {{{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_ProtobufTransform3d_init_zero {{{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_ProtobufTwist3d_init_zero {0, 0, 0, 0, 0, 0} + +/* Field tags (for use in manual encoding/decoding) */ +#define wpi_proto_ProtobufTranslation3d_x_tag 1 +#define wpi_proto_ProtobufTranslation3d_y_tag 2 +#define wpi_proto_ProtobufTranslation3d_z_tag 3 +#define wpi_proto_ProtobufQuaternion_w_tag 1 +#define wpi_proto_ProtobufQuaternion_x_tag 2 +#define wpi_proto_ProtobufQuaternion_y_tag 3 +#define wpi_proto_ProtobufQuaternion_z_tag 4 +#define wpi_proto_ProtobufRotation3d_q_tag 1 +#define wpi_proto_ProtobufPose3d_translation_tag 1 +#define wpi_proto_ProtobufPose3d_rotation_tag 2 +#define wpi_proto_ProtobufTransform3d_translation_tag 1 +#define wpi_proto_ProtobufTransform3d_rotation_tag 2 +#define wpi_proto_ProtobufTwist3d_dx_tag 1 +#define wpi_proto_ProtobufTwist3d_dy_tag 2 +#define wpi_proto_ProtobufTwist3d_dz_tag 3 +#define wpi_proto_ProtobufTwist3d_rx_tag 4 +#define wpi_proto_ProtobufTwist3d_ry_tag 5 +#define wpi_proto_ProtobufTwist3d_rz_tag 6 + +/* Struct field encoding specification for nanopb */ +#define wpi_proto_ProtobufTranslation3d_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, x, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, y, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, z, 3) +#define wpi_proto_ProtobufTranslation3d_CALLBACK NULL +#define wpi_proto_ProtobufTranslation3d_DEFAULT NULL + +#define wpi_proto_ProtobufQuaternion_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, w, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, x, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, y, 3) \ +X(a, STATIC, SINGULAR, DOUBLE, z, 4) +#define wpi_proto_ProtobufQuaternion_CALLBACK NULL +#define wpi_proto_ProtobufQuaternion_DEFAULT NULL + +#define wpi_proto_ProtobufRotation3d_FIELDLIST(X, a) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, q, 1) +#define wpi_proto_ProtobufRotation3d_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufRotation3d_DEFAULT NULL +#define wpi_proto_ProtobufRotation3d_q_MSGTYPE wpi_proto_ProtobufQuaternion + +#define wpi_proto_ProtobufPose3d_FIELDLIST(X, a) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, translation, 1) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, rotation, 2) +#define wpi_proto_ProtobufPose3d_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufPose3d_DEFAULT NULL +#define wpi_proto_ProtobufPose3d_translation_MSGTYPE wpi_proto_ProtobufTranslation3d +#define wpi_proto_ProtobufPose3d_rotation_MSGTYPE wpi_proto_ProtobufRotation3d + +#define wpi_proto_ProtobufTransform3d_FIELDLIST(X, a) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, translation, 1) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, rotation, 2) +#define wpi_proto_ProtobufTransform3d_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufTransform3d_DEFAULT NULL +#define wpi_proto_ProtobufTransform3d_translation_MSGTYPE wpi_proto_ProtobufTranslation3d +#define wpi_proto_ProtobufTransform3d_rotation_MSGTYPE wpi_proto_ProtobufRotation3d + +#define wpi_proto_ProtobufTwist3d_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, dx, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, dy, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, dz, 3) \ +X(a, STATIC, SINGULAR, DOUBLE, rx, 4) \ +X(a, STATIC, SINGULAR, DOUBLE, ry, 5) \ +X(a, STATIC, SINGULAR, DOUBLE, rz, 6) +#define wpi_proto_ProtobufTwist3d_CALLBACK NULL +#define wpi_proto_ProtobufTwist3d_DEFAULT NULL + +/* Maximum encoded size of messages (where known) */ +/* wpi_proto_ProtobufRotation3d_size depends on runtime parameters */ +/* wpi_proto_ProtobufPose3d_size depends on runtime parameters */ +/* wpi_proto_ProtobufTransform3d_size depends on runtime parameters */ +#define WPI_PROTO_GEOMETRY3D_NPB_H_MAX_SIZE wpi_proto_ProtobufTwist3d_size +#define wpi_proto_ProtobufQuaternion_size 36 +#define wpi_proto_ProtobufTranslation3d_size 27 +#define wpi_proto_ProtobufTwist3d_size 54 + + +#endif diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.cpp b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.cpp new file mode 100644 index 0000000000..6508741375 --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.cpp @@ -0,0 +1,434 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb constant definitions */ +/* Generated by nanopb-0.4.9 */ + +#include "kinematics.npb.h" +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +#include +#include +static const uint8_t file_descriptor[] { +0x0a,0x10,0x6b,0x69,0x6e,0x65,0x6d,0x61,0x74,0x69, +0x63,0x73,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x12,0x09, +0x77,0x70,0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x1a, +0x10,0x67,0x65,0x6f,0x6d,0x65,0x74,0x72,0x79,0x32, +0x64,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x22,0x4d,0x0a, +0x15,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x43, +0x68,0x61,0x73,0x73,0x69,0x73,0x53,0x70,0x65,0x65, +0x64,0x73,0x12,0x0e,0x0a,0x02,0x76,0x78,0x18,0x01, +0x20,0x01,0x28,0x01,0x52,0x02,0x76,0x78,0x12,0x0e, +0x0a,0x02,0x76,0x79,0x18,0x02,0x20,0x01,0x28,0x01, +0x52,0x02,0x76,0x79,0x12,0x14,0x0a,0x05,0x6f,0x6d, +0x65,0x67,0x61,0x18,0x03,0x20,0x01,0x28,0x01,0x52, +0x05,0x6f,0x6d,0x65,0x67,0x61,0x22,0x46,0x0a,0x23, +0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x44,0x69, +0x66,0x66,0x65,0x72,0x65,0x6e,0x74,0x69,0x61,0x6c, +0x44,0x72,0x69,0x76,0x65,0x4b,0x69,0x6e,0x65,0x6d, +0x61,0x74,0x69,0x63,0x73,0x12,0x1f,0x0a,0x0b,0x74, +0x72,0x61,0x63,0x6b,0x5f,0x77,0x69,0x64,0x74,0x68, +0x18,0x01,0x20,0x01,0x28,0x01,0x52,0x0a,0x74,0x72, +0x61,0x63,0x6b,0x57,0x69,0x64,0x74,0x68,0x22,0x50, +0x0a,0x24,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66, +0x44,0x69,0x66,0x66,0x65,0x72,0x65,0x6e,0x74,0x69, +0x61,0x6c,0x44,0x72,0x69,0x76,0x65,0x57,0x68,0x65, +0x65,0x6c,0x53,0x70,0x65,0x65,0x64,0x73,0x12,0x12, +0x0a,0x04,0x6c,0x65,0x66,0x74,0x18,0x01,0x20,0x01, +0x28,0x01,0x52,0x04,0x6c,0x65,0x66,0x74,0x12,0x14, +0x0a,0x05,0x72,0x69,0x67,0x68,0x74,0x18,0x02,0x20, +0x01,0x28,0x01,0x52,0x05,0x72,0x69,0x67,0x68,0x74, +0x22,0x53,0x0a,0x27,0x50,0x72,0x6f,0x74,0x6f,0x62, +0x75,0x66,0x44,0x69,0x66,0x66,0x65,0x72,0x65,0x6e, +0x74,0x69,0x61,0x6c,0x44,0x72,0x69,0x76,0x65,0x57, +0x68,0x65,0x65,0x6c,0x50,0x6f,0x73,0x69,0x74,0x69, +0x6f,0x6e,0x73,0x12,0x12,0x0a,0x04,0x6c,0x65,0x66, +0x74,0x18,0x01,0x20,0x01,0x28,0x01,0x52,0x04,0x6c, +0x65,0x66,0x74,0x12,0x14,0x0a,0x05,0x72,0x69,0x67, +0x68,0x74,0x18,0x02,0x20,0x01,0x28,0x01,0x52,0x05, +0x72,0x69,0x67,0x68,0x74,0x22,0xa4,0x02,0x0a,0x1e, +0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x4d,0x65, +0x63,0x61,0x6e,0x75,0x6d,0x44,0x72,0x69,0x76,0x65, +0x4b,0x69,0x6e,0x65,0x6d,0x61,0x74,0x69,0x63,0x73, +0x12,0x3f,0x0a,0x0a,0x66,0x72,0x6f,0x6e,0x74,0x5f, +0x6c,0x65,0x66,0x74,0x18,0x01,0x20,0x01,0x28,0x0b, +0x32,0x20,0x2e,0x77,0x70,0x69,0x2e,0x70,0x72,0x6f, +0x74,0x6f,0x2e,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75, +0x66,0x54,0x72,0x61,0x6e,0x73,0x6c,0x61,0x74,0x69, +0x6f,0x6e,0x32,0x64,0x52,0x09,0x66,0x72,0x6f,0x6e, +0x74,0x4c,0x65,0x66,0x74,0x12,0x41,0x0a,0x0b,0x66, +0x72,0x6f,0x6e,0x74,0x5f,0x72,0x69,0x67,0x68,0x74, +0x18,0x02,0x20,0x01,0x28,0x0b,0x32,0x20,0x2e,0x77, +0x70,0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e,0x50, +0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x54,0x72,0x61, +0x6e,0x73,0x6c,0x61,0x74,0x69,0x6f,0x6e,0x32,0x64, +0x52,0x0a,0x66,0x72,0x6f,0x6e,0x74,0x52,0x69,0x67, +0x68,0x74,0x12,0x3d,0x0a,0x09,0x72,0x65,0x61,0x72, +0x5f,0x6c,0x65,0x66,0x74,0x18,0x03,0x20,0x01,0x28, +0x0b,0x32,0x20,0x2e,0x77,0x70,0x69,0x2e,0x70,0x72, +0x6f,0x74,0x6f,0x2e,0x50,0x72,0x6f,0x74,0x6f,0x62, +0x75,0x66,0x54,0x72,0x61,0x6e,0x73,0x6c,0x61,0x74, +0x69,0x6f,0x6e,0x32,0x64,0x52,0x08,0x72,0x65,0x61, +0x72,0x4c,0x65,0x66,0x74,0x12,0x3f,0x0a,0x0a,0x72, +0x65,0x61,0x72,0x5f,0x72,0x69,0x67,0x68,0x74,0x18, +0x04,0x20,0x01,0x28,0x0b,0x32,0x20,0x2e,0x77,0x70, +0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e,0x50,0x72, +0x6f,0x74,0x6f,0x62,0x75,0x66,0x54,0x72,0x61,0x6e, +0x73,0x6c,0x61,0x74,0x69,0x6f,0x6e,0x32,0x64,0x52, +0x09,0x72,0x65,0x61,0x72,0x52,0x69,0x67,0x68,0x74, +0x22,0x9f,0x01,0x0a,0x21,0x50,0x72,0x6f,0x74,0x6f, +0x62,0x75,0x66,0x4d,0x65,0x63,0x61,0x6e,0x75,0x6d, +0x44,0x72,0x69,0x76,0x65,0x4d,0x6f,0x74,0x6f,0x72, +0x56,0x6f,0x6c,0x74,0x61,0x67,0x65,0x73,0x12,0x1d, +0x0a,0x0a,0x66,0x72,0x6f,0x6e,0x74,0x5f,0x6c,0x65, +0x66,0x74,0x18,0x01,0x20,0x01,0x28,0x01,0x52,0x09, +0x66,0x72,0x6f,0x6e,0x74,0x4c,0x65,0x66,0x74,0x12, +0x1f,0x0a,0x0b,0x66,0x72,0x6f,0x6e,0x74,0x5f,0x72, +0x69,0x67,0x68,0x74,0x18,0x02,0x20,0x01,0x28,0x01, +0x52,0x0a,0x66,0x72,0x6f,0x6e,0x74,0x52,0x69,0x67, +0x68,0x74,0x12,0x1b,0x0a,0x09,0x72,0x65,0x61,0x72, +0x5f,0x6c,0x65,0x66,0x74,0x18,0x03,0x20,0x01,0x28, +0x01,0x52,0x08,0x72,0x65,0x61,0x72,0x4c,0x65,0x66, +0x74,0x12,0x1d,0x0a,0x0a,0x72,0x65,0x61,0x72,0x5f, +0x72,0x69,0x67,0x68,0x74,0x18,0x04,0x20,0x01,0x28, +0x01,0x52,0x09,0x72,0x65,0x61,0x72,0x52,0x69,0x67, +0x68,0x74,0x22,0xa0,0x01,0x0a,0x22,0x50,0x72,0x6f, +0x74,0x6f,0x62,0x75,0x66,0x4d,0x65,0x63,0x61,0x6e, +0x75,0x6d,0x44,0x72,0x69,0x76,0x65,0x57,0x68,0x65, +0x65,0x6c,0x50,0x6f,0x73,0x69,0x74,0x69,0x6f,0x6e, +0x73,0x12,0x1d,0x0a,0x0a,0x66,0x72,0x6f,0x6e,0x74, +0x5f,0x6c,0x65,0x66,0x74,0x18,0x01,0x20,0x01,0x28, +0x01,0x52,0x09,0x66,0x72,0x6f,0x6e,0x74,0x4c,0x65, +0x66,0x74,0x12,0x1f,0x0a,0x0b,0x66,0x72,0x6f,0x6e, +0x74,0x5f,0x72,0x69,0x67,0x68,0x74,0x18,0x02,0x20, +0x01,0x28,0x01,0x52,0x0a,0x66,0x72,0x6f,0x6e,0x74, +0x52,0x69,0x67,0x68,0x74,0x12,0x1b,0x0a,0x09,0x72, +0x65,0x61,0x72,0x5f,0x6c,0x65,0x66,0x74,0x18,0x03, +0x20,0x01,0x28,0x01,0x52,0x08,0x72,0x65,0x61,0x72, +0x4c,0x65,0x66,0x74,0x12,0x1d,0x0a,0x0a,0x72,0x65, +0x61,0x72,0x5f,0x72,0x69,0x67,0x68,0x74,0x18,0x04, +0x20,0x01,0x28,0x01,0x52,0x09,0x72,0x65,0x61,0x72, +0x52,0x69,0x67,0x68,0x74,0x22,0x9d,0x01,0x0a,0x1f, +0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x4d,0x65, +0x63,0x61,0x6e,0x75,0x6d,0x44,0x72,0x69,0x76,0x65, +0x57,0x68,0x65,0x65,0x6c,0x53,0x70,0x65,0x65,0x64, +0x73,0x12,0x1d,0x0a,0x0a,0x66,0x72,0x6f,0x6e,0x74, +0x5f,0x6c,0x65,0x66,0x74,0x18,0x01,0x20,0x01,0x28, +0x01,0x52,0x09,0x66,0x72,0x6f,0x6e,0x74,0x4c,0x65, +0x66,0x74,0x12,0x1f,0x0a,0x0b,0x66,0x72,0x6f,0x6e, +0x74,0x5f,0x72,0x69,0x67,0x68,0x74,0x18,0x02,0x20, +0x01,0x28,0x01,0x52,0x0a,0x66,0x72,0x6f,0x6e,0x74, +0x52,0x69,0x67,0x68,0x74,0x12,0x1b,0x0a,0x09,0x72, +0x65,0x61,0x72,0x5f,0x6c,0x65,0x66,0x74,0x18,0x03, +0x20,0x01,0x28,0x01,0x52,0x08,0x72,0x65,0x61,0x72, +0x4c,0x65,0x66,0x74,0x12,0x1d,0x0a,0x0a,0x72,0x65, +0x61,0x72,0x5f,0x72,0x69,0x67,0x68,0x74,0x18,0x04, +0x20,0x01,0x28,0x01,0x52,0x09,0x72,0x65,0x61,0x72, +0x52,0x69,0x67,0x68,0x74,0x22,0x5b,0x0a,0x1d,0x50, +0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x53,0x77,0x65, +0x72,0x76,0x65,0x44,0x72,0x69,0x76,0x65,0x4b,0x69, +0x6e,0x65,0x6d,0x61,0x74,0x69,0x63,0x73,0x12,0x3a, +0x0a,0x07,0x6d,0x6f,0x64,0x75,0x6c,0x65,0x73,0x18, +0x01,0x20,0x03,0x28,0x0b,0x32,0x20,0x2e,0x77,0x70, +0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e,0x50,0x72, +0x6f,0x74,0x6f,0x62,0x75,0x66,0x54,0x72,0x61,0x6e, +0x73,0x6c,0x61,0x74,0x69,0x6f,0x6e,0x32,0x64,0x52, +0x07,0x6d,0x6f,0x64,0x75,0x6c,0x65,0x73,0x22,0x6f, +0x0a,0x1c,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66, +0x53,0x77,0x65,0x72,0x76,0x65,0x4d,0x6f,0x64,0x75, +0x6c,0x65,0x50,0x6f,0x73,0x69,0x74,0x69,0x6f,0x6e, +0x12,0x1a,0x0a,0x08,0x64,0x69,0x73,0x74,0x61,0x6e, +0x63,0x65,0x18,0x01,0x20,0x01,0x28,0x01,0x52,0x08, +0x64,0x69,0x73,0x74,0x61,0x6e,0x63,0x65,0x12,0x33, +0x0a,0x05,0x61,0x6e,0x67,0x6c,0x65,0x18,0x02,0x20, +0x01,0x28,0x0b,0x32,0x1d,0x2e,0x77,0x70,0x69,0x2e, +0x70,0x72,0x6f,0x74,0x6f,0x2e,0x50,0x72,0x6f,0x74, +0x6f,0x62,0x75,0x66,0x52,0x6f,0x74,0x61,0x74,0x69, +0x6f,0x6e,0x32,0x64,0x52,0x05,0x61,0x6e,0x67,0x6c, +0x65,0x22,0x66,0x0a,0x19,0x50,0x72,0x6f,0x74,0x6f, +0x62,0x75,0x66,0x53,0x77,0x65,0x72,0x76,0x65,0x4d, +0x6f,0x64,0x75,0x6c,0x65,0x53,0x74,0x61,0x74,0x65, +0x12,0x14,0x0a,0x05,0x73,0x70,0x65,0x65,0x64,0x18, +0x01,0x20,0x01,0x28,0x01,0x52,0x05,0x73,0x70,0x65, +0x65,0x64,0x12,0x33,0x0a,0x05,0x61,0x6e,0x67,0x6c, +0x65,0x18,0x02,0x20,0x01,0x28,0x0b,0x32,0x1d,0x2e, +0x77,0x70,0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e, +0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x52,0x6f, +0x74,0x61,0x74,0x69,0x6f,0x6e,0x32,0x64,0x52,0x05, +0x61,0x6e,0x67,0x6c,0x65,0x42,0x1a,0x0a,0x18,0x65, +0x64,0x75,0x2e,0x77,0x70,0x69,0x2e,0x66,0x69,0x72, +0x73,0x74,0x2e,0x6d,0x61,0x74,0x68,0x2e,0x70,0x72, +0x6f,0x74,0x6f,0x4a,0x8d,0x0f,0x0a,0x06,0x12,0x04, +0x00,0x00,0x44,0x01,0x0a,0x08,0x0a,0x01,0x0c,0x12, +0x03,0x00,0x00,0x12,0x0a,0x08,0x0a,0x01,0x02,0x12, +0x03,0x02,0x00,0x12,0x0a,0x09,0x0a,0x02,0x03,0x00, +0x12,0x03,0x04,0x00,0x1a,0x0a,0x08,0x0a,0x01,0x08, +0x12,0x03,0x06,0x00,0x31,0x0a,0x09,0x0a,0x02,0x08, +0x01,0x12,0x03,0x06,0x00,0x31,0x0a,0x0a,0x0a,0x02, +0x04,0x00,0x12,0x04,0x08,0x00,0x0c,0x01,0x0a,0x0a, +0x0a,0x03,0x04,0x00,0x01,0x12,0x03,0x08,0x08,0x1d, +0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02,0x00,0x12,0x03, +0x09,0x02,0x10,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02, +0x00,0x05,0x12,0x03,0x09,0x02,0x08,0x0a,0x0c,0x0a, +0x05,0x04,0x00,0x02,0x00,0x01,0x12,0x03,0x09,0x09, +0x0b,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x00,0x03, +0x12,0x03,0x09,0x0e,0x0f,0x0a,0x0b,0x0a,0x04,0x04, +0x00,0x02,0x01,0x12,0x03,0x0a,0x02,0x10,0x0a,0x0c, +0x0a,0x05,0x04,0x00,0x02,0x01,0x05,0x12,0x03,0x0a, +0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x01, +0x01,0x12,0x03,0x0a,0x09,0x0b,0x0a,0x0c,0x0a,0x05, +0x04,0x00,0x02,0x01,0x03,0x12,0x03,0x0a,0x0e,0x0f, +0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02,0x02,0x12,0x03, +0x0b,0x02,0x13,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02, +0x02,0x05,0x12,0x03,0x0b,0x02,0x08,0x0a,0x0c,0x0a, +0x05,0x04,0x00,0x02,0x02,0x01,0x12,0x03,0x0b,0x09, +0x0e,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x02,0x03, +0x12,0x03,0x0b,0x11,0x12,0x0a,0x0a,0x0a,0x02,0x04, +0x01,0x12,0x04,0x0e,0x00,0x10,0x01,0x0a,0x0a,0x0a, +0x03,0x04,0x01,0x01,0x12,0x03,0x0e,0x08,0x2b,0x0a, +0x0b,0x0a,0x04,0x04,0x01,0x02,0x00,0x12,0x03,0x0f, +0x02,0x19,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x00, +0x05,0x12,0x03,0x0f,0x02,0x08,0x0a,0x0c,0x0a,0x05, +0x04,0x01,0x02,0x00,0x01,0x12,0x03,0x0f,0x09,0x14, +0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x00,0x03,0x12, +0x03,0x0f,0x17,0x18,0x0a,0x0a,0x0a,0x02,0x04,0x02, +0x12,0x04,0x12,0x00,0x15,0x01,0x0a,0x0a,0x0a,0x03, +0x04,0x02,0x01,0x12,0x03,0x12,0x08,0x2c,0x0a,0x0b, +0x0a,0x04,0x04,0x02,0x02,0x00,0x12,0x03,0x13,0x02, +0x12,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x00,0x05, +0x12,0x03,0x13,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04, +0x02,0x02,0x00,0x01,0x12,0x03,0x13,0x09,0x0d,0x0a, +0x0c,0x0a,0x05,0x04,0x02,0x02,0x00,0x03,0x12,0x03, +0x13,0x10,0x11,0x0a,0x0b,0x0a,0x04,0x04,0x02,0x02, +0x01,0x12,0x03,0x14,0x02,0x13,0x0a,0x0c,0x0a,0x05, +0x04,0x02,0x02,0x01,0x05,0x12,0x03,0x14,0x02,0x08, +0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x01,0x01,0x12, +0x03,0x14,0x09,0x0e,0x0a,0x0c,0x0a,0x05,0x04,0x02, +0x02,0x01,0x03,0x12,0x03,0x14,0x11,0x12,0x0a,0x0a, +0x0a,0x02,0x04,0x03,0x12,0x04,0x17,0x00,0x1a,0x01, +0x0a,0x0a,0x0a,0x03,0x04,0x03,0x01,0x12,0x03,0x17, +0x08,0x2f,0x0a,0x0b,0x0a,0x04,0x04,0x03,0x02,0x00, +0x12,0x03,0x18,0x02,0x12,0x0a,0x0c,0x0a,0x05,0x04, +0x03,0x02,0x00,0x05,0x12,0x03,0x18,0x02,0x08,0x0a, +0x0c,0x0a,0x05,0x04,0x03,0x02,0x00,0x01,0x12,0x03, +0x18,0x09,0x0d,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02, +0x00,0x03,0x12,0x03,0x18,0x10,0x11,0x0a,0x0b,0x0a, +0x04,0x04,0x03,0x02,0x01,0x12,0x03,0x19,0x02,0x13, +0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x01,0x05,0x12, +0x03,0x19,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x03, +0x02,0x01,0x01,0x12,0x03,0x19,0x09,0x0e,0x0a,0x0c, +0x0a,0x05,0x04,0x03,0x02,0x01,0x03,0x12,0x03,0x19, +0x11,0x12,0x0a,0x0a,0x0a,0x02,0x04,0x04,0x12,0x04, +0x1c,0x00,0x21,0x01,0x0a,0x0a,0x0a,0x03,0x04,0x04, +0x01,0x12,0x03,0x1c,0x08,0x26,0x0a,0x0b,0x0a,0x04, +0x04,0x04,0x02,0x00,0x12,0x03,0x1d,0x02,0x27,0x0a, +0x0c,0x0a,0x05,0x04,0x04,0x02,0x00,0x06,0x12,0x03, +0x1d,0x02,0x17,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02, +0x00,0x01,0x12,0x03,0x1d,0x18,0x22,0x0a,0x0c,0x0a, +0x05,0x04,0x04,0x02,0x00,0x03,0x12,0x03,0x1d,0x25, +0x26,0x0a,0x0b,0x0a,0x04,0x04,0x04,0x02,0x01,0x12, +0x03,0x1e,0x02,0x28,0x0a,0x0c,0x0a,0x05,0x04,0x04, +0x02,0x01,0x06,0x12,0x03,0x1e,0x02,0x17,0x0a,0x0c, +0x0a,0x05,0x04,0x04,0x02,0x01,0x01,0x12,0x03,0x1e, +0x18,0x23,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x01, +0x03,0x12,0x03,0x1e,0x26,0x27,0x0a,0x0b,0x0a,0x04, +0x04,0x04,0x02,0x02,0x12,0x03,0x1f,0x02,0x26,0x0a, +0x0c,0x0a,0x05,0x04,0x04,0x02,0x02,0x06,0x12,0x03, +0x1f,0x02,0x17,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02, +0x02,0x01,0x12,0x03,0x1f,0x18,0x21,0x0a,0x0c,0x0a, +0x05,0x04,0x04,0x02,0x02,0x03,0x12,0x03,0x1f,0x24, +0x25,0x0a,0x0b,0x0a,0x04,0x04,0x04,0x02,0x03,0x12, +0x03,0x20,0x02,0x27,0x0a,0x0c,0x0a,0x05,0x04,0x04, +0x02,0x03,0x06,0x12,0x03,0x20,0x02,0x17,0x0a,0x0c, +0x0a,0x05,0x04,0x04,0x02,0x03,0x01,0x12,0x03,0x20, +0x18,0x22,0x0a,0x0c,0x0a,0x05,0x04,0x04,0x02,0x03, +0x03,0x12,0x03,0x20,0x25,0x26,0x0a,0x0a,0x0a,0x02, +0x04,0x05,0x12,0x04,0x23,0x00,0x28,0x01,0x0a,0x0a, +0x0a,0x03,0x04,0x05,0x01,0x12,0x03,0x23,0x08,0x29, +0x0a,0x0b,0x0a,0x04,0x04,0x05,0x02,0x00,0x12,0x03, +0x24,0x02,0x18,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02, +0x00,0x05,0x12,0x03,0x24,0x02,0x08,0x0a,0x0c,0x0a, +0x05,0x04,0x05,0x02,0x00,0x01,0x12,0x03,0x24,0x09, +0x13,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x00,0x03, +0x12,0x03,0x24,0x16,0x17,0x0a,0x0b,0x0a,0x04,0x04, +0x05,0x02,0x01,0x12,0x03,0x25,0x02,0x19,0x0a,0x0c, +0x0a,0x05,0x04,0x05,0x02,0x01,0x05,0x12,0x03,0x25, +0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x01, +0x01,0x12,0x03,0x25,0x09,0x14,0x0a,0x0c,0x0a,0x05, +0x04,0x05,0x02,0x01,0x03,0x12,0x03,0x25,0x17,0x18, +0x0a,0x0b,0x0a,0x04,0x04,0x05,0x02,0x02,0x12,0x03, +0x26,0x02,0x17,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02, +0x02,0x05,0x12,0x03,0x26,0x02,0x08,0x0a,0x0c,0x0a, +0x05,0x04,0x05,0x02,0x02,0x01,0x12,0x03,0x26,0x09, +0x12,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x02,0x03, +0x12,0x03,0x26,0x15,0x16,0x0a,0x0b,0x0a,0x04,0x04, +0x05,0x02,0x03,0x12,0x03,0x27,0x02,0x18,0x0a,0x0c, +0x0a,0x05,0x04,0x05,0x02,0x03,0x05,0x12,0x03,0x27, +0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x05,0x02,0x03, +0x01,0x12,0x03,0x27,0x09,0x13,0x0a,0x0c,0x0a,0x05, +0x04,0x05,0x02,0x03,0x03,0x12,0x03,0x27,0x16,0x17, +0x0a,0x0a,0x0a,0x02,0x04,0x06,0x12,0x04,0x2a,0x00, +0x2f,0x01,0x0a,0x0a,0x0a,0x03,0x04,0x06,0x01,0x12, +0x03,0x2a,0x08,0x2a,0x0a,0x0b,0x0a,0x04,0x04,0x06, +0x02,0x00,0x12,0x03,0x2b,0x02,0x18,0x0a,0x0c,0x0a, +0x05,0x04,0x06,0x02,0x00,0x05,0x12,0x03,0x2b,0x02, +0x08,0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,0x00,0x01, +0x12,0x03,0x2b,0x09,0x13,0x0a,0x0c,0x0a,0x05,0x04, +0x06,0x02,0x00,0x03,0x12,0x03,0x2b,0x16,0x17,0x0a, +0x0b,0x0a,0x04,0x04,0x06,0x02,0x01,0x12,0x03,0x2c, +0x02,0x19,0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,0x01, +0x05,0x12,0x03,0x2c,0x02,0x08,0x0a,0x0c,0x0a,0x05, +0x04,0x06,0x02,0x01,0x01,0x12,0x03,0x2c,0x09,0x14, +0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,0x01,0x03,0x12, +0x03,0x2c,0x17,0x18,0x0a,0x0b,0x0a,0x04,0x04,0x06, +0x02,0x02,0x12,0x03,0x2d,0x02,0x17,0x0a,0x0c,0x0a, +0x05,0x04,0x06,0x02,0x02,0x05,0x12,0x03,0x2d,0x02, +0x08,0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,0x02,0x01, +0x12,0x03,0x2d,0x09,0x12,0x0a,0x0c,0x0a,0x05,0x04, +0x06,0x02,0x02,0x03,0x12,0x03,0x2d,0x15,0x16,0x0a, +0x0b,0x0a,0x04,0x04,0x06,0x02,0x03,0x12,0x03,0x2e, +0x02,0x18,0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,0x03, +0x05,0x12,0x03,0x2e,0x02,0x08,0x0a,0x0c,0x0a,0x05, +0x04,0x06,0x02,0x03,0x01,0x12,0x03,0x2e,0x09,0x13, +0x0a,0x0c,0x0a,0x05,0x04,0x06,0x02,0x03,0x03,0x12, +0x03,0x2e,0x16,0x17,0x0a,0x0a,0x0a,0x02,0x04,0x07, +0x12,0x04,0x31,0x00,0x36,0x01,0x0a,0x0a,0x0a,0x03, +0x04,0x07,0x01,0x12,0x03,0x31,0x08,0x27,0x0a,0x0b, +0x0a,0x04,0x04,0x07,0x02,0x00,0x12,0x03,0x32,0x02, +0x18,0x0a,0x0c,0x0a,0x05,0x04,0x07,0x02,0x00,0x05, +0x12,0x03,0x32,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04, +0x07,0x02,0x00,0x01,0x12,0x03,0x32,0x09,0x13,0x0a, +0x0c,0x0a,0x05,0x04,0x07,0x02,0x00,0x03,0x12,0x03, +0x32,0x16,0x17,0x0a,0x0b,0x0a,0x04,0x04,0x07,0x02, +0x01,0x12,0x03,0x33,0x02,0x19,0x0a,0x0c,0x0a,0x05, +0x04,0x07,0x02,0x01,0x05,0x12,0x03,0x33,0x02,0x08, +0x0a,0x0c,0x0a,0x05,0x04,0x07,0x02,0x01,0x01,0x12, +0x03,0x33,0x09,0x14,0x0a,0x0c,0x0a,0x05,0x04,0x07, +0x02,0x01,0x03,0x12,0x03,0x33,0x17,0x18,0x0a,0x0b, +0x0a,0x04,0x04,0x07,0x02,0x02,0x12,0x03,0x34,0x02, +0x17,0x0a,0x0c,0x0a,0x05,0x04,0x07,0x02,0x02,0x05, +0x12,0x03,0x34,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04, +0x07,0x02,0x02,0x01,0x12,0x03,0x34,0x09,0x12,0x0a, +0x0c,0x0a,0x05,0x04,0x07,0x02,0x02,0x03,0x12,0x03, +0x34,0x15,0x16,0x0a,0x0b,0x0a,0x04,0x04,0x07,0x02, +0x03,0x12,0x03,0x35,0x02,0x18,0x0a,0x0c,0x0a,0x05, +0x04,0x07,0x02,0x03,0x05,0x12,0x03,0x35,0x02,0x08, +0x0a,0x0c,0x0a,0x05,0x04,0x07,0x02,0x03,0x01,0x12, +0x03,0x35,0x09,0x13,0x0a,0x0c,0x0a,0x05,0x04,0x07, +0x02,0x03,0x03,0x12,0x03,0x35,0x16,0x17,0x0a,0x0a, +0x0a,0x02,0x04,0x08,0x12,0x04,0x38,0x00,0x3a,0x01, +0x0a,0x0a,0x0a,0x03,0x04,0x08,0x01,0x12,0x03,0x38, +0x08,0x25,0x0a,0x0b,0x0a,0x04,0x04,0x08,0x02,0x00, +0x12,0x03,0x39,0x02,0x2d,0x0a,0x0c,0x0a,0x05,0x04, +0x08,0x02,0x00,0x04,0x12,0x03,0x39,0x02,0x0a,0x0a, +0x0c,0x0a,0x05,0x04,0x08,0x02,0x00,0x06,0x12,0x03, +0x39,0x0b,0x20,0x0a,0x0c,0x0a,0x05,0x04,0x08,0x02, +0x00,0x01,0x12,0x03,0x39,0x21,0x28,0x0a,0x0c,0x0a, +0x05,0x04,0x08,0x02,0x00,0x03,0x12,0x03,0x39,0x2b, +0x2c,0x0a,0x0a,0x0a,0x02,0x04,0x09,0x12,0x04,0x3c, +0x00,0x3f,0x01,0x0a,0x0a,0x0a,0x03,0x04,0x09,0x01, +0x12,0x03,0x3c,0x08,0x24,0x0a,0x0b,0x0a,0x04,0x04, +0x09,0x02,0x00,0x12,0x03,0x3d,0x02,0x16,0x0a,0x0c, +0x0a,0x05,0x04,0x09,0x02,0x00,0x05,0x12,0x03,0x3d, +0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x09,0x02,0x00, +0x01,0x12,0x03,0x3d,0x09,0x11,0x0a,0x0c,0x0a,0x05, +0x04,0x09,0x02,0x00,0x03,0x12,0x03,0x3d,0x14,0x15, +0x0a,0x0b,0x0a,0x04,0x04,0x09,0x02,0x01,0x12,0x03, +0x3e,0x02,0x1f,0x0a,0x0c,0x0a,0x05,0x04,0x09,0x02, +0x01,0x06,0x12,0x03,0x3e,0x02,0x14,0x0a,0x0c,0x0a, +0x05,0x04,0x09,0x02,0x01,0x01,0x12,0x03,0x3e,0x15, +0x1a,0x0a,0x0c,0x0a,0x05,0x04,0x09,0x02,0x01,0x03, +0x12,0x03,0x3e,0x1d,0x1e,0x0a,0x0a,0x0a,0x02,0x04, +0x0a,0x12,0x04,0x41,0x00,0x44,0x01,0x0a,0x0a,0x0a, +0x03,0x04,0x0a,0x01,0x12,0x03,0x41,0x08,0x21,0x0a, +0x0b,0x0a,0x04,0x04,0x0a,0x02,0x00,0x12,0x03,0x42, +0x02,0x13,0x0a,0x0c,0x0a,0x05,0x04,0x0a,0x02,0x00, +0x05,0x12,0x03,0x42,0x02,0x08,0x0a,0x0c,0x0a,0x05, +0x04,0x0a,0x02,0x00,0x01,0x12,0x03,0x42,0x09,0x0e, +0x0a,0x0c,0x0a,0x05,0x04,0x0a,0x02,0x00,0x03,0x12, +0x03,0x42,0x11,0x12,0x0a,0x0b,0x0a,0x04,0x04,0x0a, +0x02,0x01,0x12,0x03,0x43,0x02,0x1f,0x0a,0x0c,0x0a, +0x05,0x04,0x0a,0x02,0x01,0x06,0x12,0x03,0x43,0x02, +0x14,0x0a,0x0c,0x0a,0x05,0x04,0x0a,0x02,0x01,0x01, +0x12,0x03,0x43,0x15,0x1a,0x0a,0x0c,0x0a,0x05,0x04, +0x0a,0x02,0x01,0x03,0x12,0x03,0x43,0x1d,0x1e,0x62, +0x06,0x70,0x72,0x6f,0x74,0x6f,0x33, +}; +static const char file_name[] = "kinematics.proto"; +static const char wpi_proto_ProtobufChassisSpeeds_name[] = "wpi.proto.ProtobufChassisSpeeds"; +std::string_view wpi_proto_ProtobufChassisSpeeds::msg_name(void) noexcept { return wpi_proto_ProtobufChassisSpeeds_name; } +pb_filedesc_t wpi_proto_ProtobufChassisSpeeds::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufChassisSpeeds, wpi_proto_ProtobufChassisSpeeds, AUTO) + + +static const char wpi_proto_ProtobufDifferentialDriveKinematics_name[] = "wpi.proto.ProtobufDifferentialDriveKinematics"; +std::string_view wpi_proto_ProtobufDifferentialDriveKinematics::msg_name(void) noexcept { return wpi_proto_ProtobufDifferentialDriveKinematics_name; } +pb_filedesc_t wpi_proto_ProtobufDifferentialDriveKinematics::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufDifferentialDriveKinematics, wpi_proto_ProtobufDifferentialDriveKinematics, AUTO) + + +static const char wpi_proto_ProtobufDifferentialDriveWheelSpeeds_name[] = "wpi.proto.ProtobufDifferentialDriveWheelSpeeds"; +std::string_view wpi_proto_ProtobufDifferentialDriveWheelSpeeds::msg_name(void) noexcept { return wpi_proto_ProtobufDifferentialDriveWheelSpeeds_name; } +pb_filedesc_t wpi_proto_ProtobufDifferentialDriveWheelSpeeds::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufDifferentialDriveWheelSpeeds, wpi_proto_ProtobufDifferentialDriveWheelSpeeds, AUTO) + + +static const char wpi_proto_ProtobufDifferentialDriveWheelPositions_name[] = "wpi.proto.ProtobufDifferentialDriveWheelPositions"; +std::string_view wpi_proto_ProtobufDifferentialDriveWheelPositions::msg_name(void) noexcept { return wpi_proto_ProtobufDifferentialDriveWheelPositions_name; } +pb_filedesc_t wpi_proto_ProtobufDifferentialDriveWheelPositions::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufDifferentialDriveWheelPositions, wpi_proto_ProtobufDifferentialDriveWheelPositions, AUTO) + + +static const char wpi_proto_ProtobufMecanumDriveKinematics_name[] = "wpi.proto.ProtobufMecanumDriveKinematics"; +std::string_view wpi_proto_ProtobufMecanumDriveKinematics::msg_name(void) noexcept { return wpi_proto_ProtobufMecanumDriveKinematics_name; } +pb_filedesc_t wpi_proto_ProtobufMecanumDriveKinematics::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufMecanumDriveKinematics, wpi_proto_ProtobufMecanumDriveKinematics, AUTO) + + +static const char wpi_proto_ProtobufMecanumDriveMotorVoltages_name[] = "wpi.proto.ProtobufMecanumDriveMotorVoltages"; +std::string_view wpi_proto_ProtobufMecanumDriveMotorVoltages::msg_name(void) noexcept { return wpi_proto_ProtobufMecanumDriveMotorVoltages_name; } +pb_filedesc_t wpi_proto_ProtobufMecanumDriveMotorVoltages::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufMecanumDriveMotorVoltages, wpi_proto_ProtobufMecanumDriveMotorVoltages, AUTO) + + +static const char wpi_proto_ProtobufMecanumDriveWheelPositions_name[] = "wpi.proto.ProtobufMecanumDriveWheelPositions"; +std::string_view wpi_proto_ProtobufMecanumDriveWheelPositions::msg_name(void) noexcept { return wpi_proto_ProtobufMecanumDriveWheelPositions_name; } +pb_filedesc_t wpi_proto_ProtobufMecanumDriveWheelPositions::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufMecanumDriveWheelPositions, wpi_proto_ProtobufMecanumDriveWheelPositions, AUTO) + + +static const char wpi_proto_ProtobufMecanumDriveWheelSpeeds_name[] = "wpi.proto.ProtobufMecanumDriveWheelSpeeds"; +std::string_view wpi_proto_ProtobufMecanumDriveWheelSpeeds::msg_name(void) noexcept { return wpi_proto_ProtobufMecanumDriveWheelSpeeds_name; } +pb_filedesc_t wpi_proto_ProtobufMecanumDriveWheelSpeeds::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufMecanumDriveWheelSpeeds, wpi_proto_ProtobufMecanumDriveWheelSpeeds, AUTO) + + +static const char wpi_proto_ProtobufSwerveDriveKinematics_name[] = "wpi.proto.ProtobufSwerveDriveKinematics"; +std::string_view wpi_proto_ProtobufSwerveDriveKinematics::msg_name(void) noexcept { return wpi_proto_ProtobufSwerveDriveKinematics_name; } +pb_filedesc_t wpi_proto_ProtobufSwerveDriveKinematics::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufSwerveDriveKinematics, wpi_proto_ProtobufSwerveDriveKinematics, AUTO) + + +static const char wpi_proto_ProtobufSwerveModulePosition_name[] = "wpi.proto.ProtobufSwerveModulePosition"; +std::string_view wpi_proto_ProtobufSwerveModulePosition::msg_name(void) noexcept { return wpi_proto_ProtobufSwerveModulePosition_name; } +pb_filedesc_t wpi_proto_ProtobufSwerveModulePosition::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufSwerveModulePosition, wpi_proto_ProtobufSwerveModulePosition, AUTO) + + +static const char wpi_proto_ProtobufSwerveModuleState_name[] = "wpi.proto.ProtobufSwerveModuleState"; +std::string_view wpi_proto_ProtobufSwerveModuleState::msg_name(void) noexcept { return wpi_proto_ProtobufSwerveModuleState_name; } +pb_filedesc_t wpi_proto_ProtobufSwerveModuleState::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufSwerveModuleState, wpi_proto_ProtobufSwerveModuleState, AUTO) + + + +#ifndef PB_CONVERT_DOUBLE_FLOAT +/* On some platforms (such as AVR), double is really float. + * To be able to encode/decode double on these platforms, you need. + * to define PB_CONVERT_DOUBLE_FLOAT in pb.h or compiler command line. + */ +PB_STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES) +#endif + diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.h b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.h new file mode 100644 index 0000000000..e55103ffb8 --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/kinematics.npb.h @@ -0,0 +1,277 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb header */ +/* Generated by nanopb-0.4.9 */ + +#ifndef PB_WPI_PROTO_KINEMATICS_NPB_H_INCLUDED +#define PB_WPI_PROTO_KINEMATICS_NPB_H_INCLUDED +#include +#include +#include +#include "geometry2d.npb.h" + +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +/* Struct definitions */ +typedef struct _wpi_proto_ProtobufChassisSpeeds { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double vx; + double vy; + double omega; +} wpi_proto_ProtobufChassisSpeeds; + +typedef struct _wpi_proto_ProtobufDifferentialDriveKinematics { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double track_width; +} wpi_proto_ProtobufDifferentialDriveKinematics; + +typedef struct _wpi_proto_ProtobufDifferentialDriveWheelSpeeds { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double left; + double right; +} wpi_proto_ProtobufDifferentialDriveWheelSpeeds; + +typedef struct _wpi_proto_ProtobufDifferentialDriveWheelPositions { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double left; + double right; +} wpi_proto_ProtobufDifferentialDriveWheelPositions; + +typedef struct _wpi_proto_ProtobufMecanumDriveKinematics { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + pb_callback_t front_left; + pb_callback_t front_right; + pb_callback_t rear_left; + pb_callback_t rear_right; +} wpi_proto_ProtobufMecanumDriveKinematics; + +typedef struct _wpi_proto_ProtobufMecanumDriveMotorVoltages { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double front_left; + double front_right; + double rear_left; + double rear_right; +} wpi_proto_ProtobufMecanumDriveMotorVoltages; + +typedef struct _wpi_proto_ProtobufMecanumDriveWheelPositions { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double front_left; + double front_right; + double rear_left; + double rear_right; +} wpi_proto_ProtobufMecanumDriveWheelPositions; + +typedef struct _wpi_proto_ProtobufMecanumDriveWheelSpeeds { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double front_left; + double front_right; + double rear_left; + double rear_right; +} wpi_proto_ProtobufMecanumDriveWheelSpeeds; + +typedef struct _wpi_proto_ProtobufSwerveDriveKinematics { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + pb_callback_t modules; +} wpi_proto_ProtobufSwerveDriveKinematics; + +typedef struct _wpi_proto_ProtobufSwerveModulePosition { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double distance; + pb_callback_t angle; +} wpi_proto_ProtobufSwerveModulePosition; + +typedef struct _wpi_proto_ProtobufSwerveModuleState { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double speed; + pb_callback_t angle; +} wpi_proto_ProtobufSwerveModuleState; + + +/* Initializer values for message structs */ +#define wpi_proto_ProtobufChassisSpeeds_init_default {0, 0, 0} +#define wpi_proto_ProtobufDifferentialDriveKinematics_init_default {0} +#define wpi_proto_ProtobufDifferentialDriveWheelSpeeds_init_default {0, 0} +#define wpi_proto_ProtobufDifferentialDriveWheelPositions_init_default {0, 0} +#define wpi_proto_ProtobufMecanumDriveKinematics_init_default {{{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_ProtobufMecanumDriveMotorVoltages_init_default {0, 0, 0, 0} +#define wpi_proto_ProtobufMecanumDriveWheelPositions_init_default {0, 0, 0, 0} +#define wpi_proto_ProtobufMecanumDriveWheelSpeeds_init_default {0, 0, 0, 0} +#define wpi_proto_ProtobufSwerveDriveKinematics_init_default {{{NULL}, NULL}} +#define wpi_proto_ProtobufSwerveModulePosition_init_default {0, {{NULL}, NULL}} +#define wpi_proto_ProtobufSwerveModuleState_init_default {0, {{NULL}, NULL}} +#define wpi_proto_ProtobufChassisSpeeds_init_zero {0, 0, 0} +#define wpi_proto_ProtobufDifferentialDriveKinematics_init_zero {0} +#define wpi_proto_ProtobufDifferentialDriveWheelSpeeds_init_zero {0, 0} +#define wpi_proto_ProtobufDifferentialDriveWheelPositions_init_zero {0, 0} +#define wpi_proto_ProtobufMecanumDriveKinematics_init_zero {{{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_ProtobufMecanumDriveMotorVoltages_init_zero {0, 0, 0, 0} +#define wpi_proto_ProtobufMecanumDriveWheelPositions_init_zero {0, 0, 0, 0} +#define wpi_proto_ProtobufMecanumDriveWheelSpeeds_init_zero {0, 0, 0, 0} +#define wpi_proto_ProtobufSwerveDriveKinematics_init_zero {{{NULL}, NULL}} +#define wpi_proto_ProtobufSwerveModulePosition_init_zero {0, {{NULL}, NULL}} +#define wpi_proto_ProtobufSwerveModuleState_init_zero {0, {{NULL}, NULL}} + +/* Field tags (for use in manual encoding/decoding) */ +#define wpi_proto_ProtobufChassisSpeeds_vx_tag 1 +#define wpi_proto_ProtobufChassisSpeeds_vy_tag 2 +#define wpi_proto_ProtobufChassisSpeeds_omega_tag 3 +#define wpi_proto_ProtobufDifferentialDriveKinematics_track_width_tag 1 +#define wpi_proto_ProtobufDifferentialDriveWheelSpeeds_left_tag 1 +#define wpi_proto_ProtobufDifferentialDriveWheelSpeeds_right_tag 2 +#define wpi_proto_ProtobufDifferentialDriveWheelPositions_left_tag 1 +#define wpi_proto_ProtobufDifferentialDriveWheelPositions_right_tag 2 +#define wpi_proto_ProtobufMecanumDriveKinematics_front_left_tag 1 +#define wpi_proto_ProtobufMecanumDriveKinematics_front_right_tag 2 +#define wpi_proto_ProtobufMecanumDriveKinematics_rear_left_tag 3 +#define wpi_proto_ProtobufMecanumDriveKinematics_rear_right_tag 4 +#define wpi_proto_ProtobufMecanumDriveMotorVoltages_front_left_tag 1 +#define wpi_proto_ProtobufMecanumDriveMotorVoltages_front_right_tag 2 +#define wpi_proto_ProtobufMecanumDriveMotorVoltages_rear_left_tag 3 +#define wpi_proto_ProtobufMecanumDriveMotorVoltages_rear_right_tag 4 +#define wpi_proto_ProtobufMecanumDriveWheelPositions_front_left_tag 1 +#define wpi_proto_ProtobufMecanumDriveWheelPositions_front_right_tag 2 +#define wpi_proto_ProtobufMecanumDriveWheelPositions_rear_left_tag 3 +#define wpi_proto_ProtobufMecanumDriveWheelPositions_rear_right_tag 4 +#define wpi_proto_ProtobufMecanumDriveWheelSpeeds_front_left_tag 1 +#define wpi_proto_ProtobufMecanumDriveWheelSpeeds_front_right_tag 2 +#define wpi_proto_ProtobufMecanumDriveWheelSpeeds_rear_left_tag 3 +#define wpi_proto_ProtobufMecanumDriveWheelSpeeds_rear_right_tag 4 +#define wpi_proto_ProtobufSwerveDriveKinematics_modules_tag 1 +#define wpi_proto_ProtobufSwerveModulePosition_distance_tag 1 +#define wpi_proto_ProtobufSwerveModulePosition_angle_tag 2 +#define wpi_proto_ProtobufSwerveModuleState_speed_tag 1 +#define wpi_proto_ProtobufSwerveModuleState_angle_tag 2 + +/* Struct field encoding specification for nanopb */ +#define wpi_proto_ProtobufChassisSpeeds_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, vx, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, vy, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, omega, 3) +#define wpi_proto_ProtobufChassisSpeeds_CALLBACK NULL +#define wpi_proto_ProtobufChassisSpeeds_DEFAULT NULL + +#define wpi_proto_ProtobufDifferentialDriveKinematics_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, track_width, 1) +#define wpi_proto_ProtobufDifferentialDriveKinematics_CALLBACK NULL +#define wpi_proto_ProtobufDifferentialDriveKinematics_DEFAULT NULL + +#define wpi_proto_ProtobufDifferentialDriveWheelSpeeds_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, left, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, right, 2) +#define wpi_proto_ProtobufDifferentialDriveWheelSpeeds_CALLBACK NULL +#define wpi_proto_ProtobufDifferentialDriveWheelSpeeds_DEFAULT NULL + +#define wpi_proto_ProtobufDifferentialDriveWheelPositions_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, left, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, right, 2) +#define wpi_proto_ProtobufDifferentialDriveWheelPositions_CALLBACK NULL +#define wpi_proto_ProtobufDifferentialDriveWheelPositions_DEFAULT NULL + +#define wpi_proto_ProtobufMecanumDriveKinematics_FIELDLIST(X, a) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, front_left, 1) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, front_right, 2) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, rear_left, 3) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, rear_right, 4) +#define wpi_proto_ProtobufMecanumDriveKinematics_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufMecanumDriveKinematics_DEFAULT NULL +#define wpi_proto_ProtobufMecanumDriveKinematics_front_left_MSGTYPE wpi_proto_ProtobufTranslation2d +#define wpi_proto_ProtobufMecanumDriveKinematics_front_right_MSGTYPE wpi_proto_ProtobufTranslation2d +#define wpi_proto_ProtobufMecanumDriveKinematics_rear_left_MSGTYPE wpi_proto_ProtobufTranslation2d +#define wpi_proto_ProtobufMecanumDriveKinematics_rear_right_MSGTYPE wpi_proto_ProtobufTranslation2d + +#define wpi_proto_ProtobufMecanumDriveMotorVoltages_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, front_left, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, front_right, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, rear_left, 3) \ +X(a, STATIC, SINGULAR, DOUBLE, rear_right, 4) +#define wpi_proto_ProtobufMecanumDriveMotorVoltages_CALLBACK NULL +#define wpi_proto_ProtobufMecanumDriveMotorVoltages_DEFAULT NULL + +#define wpi_proto_ProtobufMecanumDriveWheelPositions_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, front_left, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, front_right, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, rear_left, 3) \ +X(a, STATIC, SINGULAR, DOUBLE, rear_right, 4) +#define wpi_proto_ProtobufMecanumDriveWheelPositions_CALLBACK NULL +#define wpi_proto_ProtobufMecanumDriveWheelPositions_DEFAULT NULL + +#define wpi_proto_ProtobufMecanumDriveWheelSpeeds_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, front_left, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, front_right, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, rear_left, 3) \ +X(a, STATIC, SINGULAR, DOUBLE, rear_right, 4) +#define wpi_proto_ProtobufMecanumDriveWheelSpeeds_CALLBACK NULL +#define wpi_proto_ProtobufMecanumDriveWheelSpeeds_DEFAULT NULL + +#define wpi_proto_ProtobufSwerveDriveKinematics_FIELDLIST(X, a) \ +X(a, CALLBACK, REPEATED, MESSAGE, modules, 1) +#define wpi_proto_ProtobufSwerveDriveKinematics_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufSwerveDriveKinematics_DEFAULT NULL +#define wpi_proto_ProtobufSwerveDriveKinematics_modules_MSGTYPE wpi_proto_ProtobufTranslation2d + +#define wpi_proto_ProtobufSwerveModulePosition_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, distance, 1) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, angle, 2) +#define wpi_proto_ProtobufSwerveModulePosition_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufSwerveModulePosition_DEFAULT NULL +#define wpi_proto_ProtobufSwerveModulePosition_angle_MSGTYPE wpi_proto_ProtobufRotation2d + +#define wpi_proto_ProtobufSwerveModuleState_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, speed, 1) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, angle, 2) +#define wpi_proto_ProtobufSwerveModuleState_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufSwerveModuleState_DEFAULT NULL +#define wpi_proto_ProtobufSwerveModuleState_angle_MSGTYPE wpi_proto_ProtobufRotation2d + +/* Maximum encoded size of messages (where known) */ +/* wpi_proto_ProtobufMecanumDriveKinematics_size depends on runtime parameters */ +/* wpi_proto_ProtobufSwerveDriveKinematics_size depends on runtime parameters */ +/* wpi_proto_ProtobufSwerveModulePosition_size depends on runtime parameters */ +/* wpi_proto_ProtobufSwerveModuleState_size depends on runtime parameters */ +#define WPI_PROTO_KINEMATICS_NPB_H_MAX_SIZE wpi_proto_ProtobufMecanumDriveMotorVoltages_size +#define wpi_proto_ProtobufChassisSpeeds_size 27 +#define wpi_proto_ProtobufDifferentialDriveKinematics_size 9 +#define wpi_proto_ProtobufDifferentialDriveWheelPositions_size 18 +#define wpi_proto_ProtobufDifferentialDriveWheelSpeeds_size 18 +#define wpi_proto_ProtobufMecanumDriveMotorVoltages_size 36 +#define wpi_proto_ProtobufMecanumDriveWheelPositions_size 36 +#define wpi_proto_ProtobufMecanumDriveWheelSpeeds_size 36 + + +#endif diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/plant.npb.cpp b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/plant.npb.cpp new file mode 100644 index 0000000000..18198e37b1 --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/plant.npb.cpp @@ -0,0 +1,93 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb constant definitions */ +/* Generated by nanopb-0.4.9 */ + +#include "plant.npb.h" +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +#include +#include +static const uint8_t file_descriptor[] { +0x0a,0x0b,0x70,0x6c,0x61,0x6e,0x74,0x2e,0x70,0x72, +0x6f,0x74,0x6f,0x12,0x09,0x77,0x70,0x69,0x2e,0x70, +0x72,0x6f,0x74,0x6f,0x22,0xc4,0x01,0x0a,0x0f,0x50, +0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x44,0x43,0x4d, +0x6f,0x74,0x6f,0x72,0x12,0x27,0x0a,0x0f,0x6e,0x6f, +0x6d,0x69,0x6e,0x61,0x6c,0x5f,0x76,0x6f,0x6c,0x74, +0x61,0x67,0x65,0x18,0x01,0x20,0x01,0x28,0x01,0x52, +0x0e,0x6e,0x6f,0x6d,0x69,0x6e,0x61,0x6c,0x56,0x6f, +0x6c,0x74,0x61,0x67,0x65,0x12,0x21,0x0a,0x0c,0x73, +0x74,0x61,0x6c,0x6c,0x5f,0x74,0x6f,0x72,0x71,0x75, +0x65,0x18,0x02,0x20,0x01,0x28,0x01,0x52,0x0b,0x73, +0x74,0x61,0x6c,0x6c,0x54,0x6f,0x72,0x71,0x75,0x65, +0x12,0x23,0x0a,0x0d,0x73,0x74,0x61,0x6c,0x6c,0x5f, +0x63,0x75,0x72,0x72,0x65,0x6e,0x74,0x18,0x03,0x20, +0x01,0x28,0x01,0x52,0x0c,0x73,0x74,0x61,0x6c,0x6c, +0x43,0x75,0x72,0x72,0x65,0x6e,0x74,0x12,0x21,0x0a, +0x0c,0x66,0x72,0x65,0x65,0x5f,0x63,0x75,0x72,0x72, +0x65,0x6e,0x74,0x18,0x04,0x20,0x01,0x28,0x01,0x52, +0x0b,0x66,0x72,0x65,0x65,0x43,0x75,0x72,0x72,0x65, +0x6e,0x74,0x12,0x1d,0x0a,0x0a,0x66,0x72,0x65,0x65, +0x5f,0x73,0x70,0x65,0x65,0x64,0x18,0x05,0x20,0x01, +0x28,0x01,0x52,0x09,0x66,0x72,0x65,0x65,0x53,0x70, +0x65,0x65,0x64,0x42,0x1a,0x0a,0x18,0x65,0x64,0x75, +0x2e,0x77,0x70,0x69,0x2e,0x66,0x69,0x72,0x73,0x74, +0x2e,0x6d,0x61,0x74,0x68,0x2e,0x70,0x72,0x6f,0x74, +0x6f,0x4a,0xdc,0x02,0x0a,0x06,0x12,0x04,0x00,0x00, +0x0c,0x01,0x0a,0x08,0x0a,0x01,0x0c,0x12,0x03,0x00, +0x00,0x12,0x0a,0x08,0x0a,0x01,0x02,0x12,0x03,0x02, +0x00,0x12,0x0a,0x08,0x0a,0x01,0x08,0x12,0x03,0x04, +0x00,0x31,0x0a,0x09,0x0a,0x02,0x08,0x01,0x12,0x03, +0x04,0x00,0x31,0x0a,0x0a,0x0a,0x02,0x04,0x00,0x12, +0x04,0x06,0x00,0x0c,0x01,0x0a,0x0a,0x0a,0x03,0x04, +0x00,0x01,0x12,0x03,0x06,0x08,0x17,0x0a,0x0b,0x0a, +0x04,0x04,0x00,0x02,0x00,0x12,0x03,0x07,0x02,0x1d, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x00,0x05,0x12, +0x03,0x07,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x00, +0x02,0x00,0x01,0x12,0x03,0x07,0x09,0x18,0x0a,0x0c, +0x0a,0x05,0x04,0x00,0x02,0x00,0x03,0x12,0x03,0x07, +0x1b,0x1c,0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02,0x01, +0x12,0x03,0x08,0x02,0x1a,0x0a,0x0c,0x0a,0x05,0x04, +0x00,0x02,0x01,0x05,0x12,0x03,0x08,0x02,0x08,0x0a, +0x0c,0x0a,0x05,0x04,0x00,0x02,0x01,0x01,0x12,0x03, +0x08,0x09,0x15,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02, +0x01,0x03,0x12,0x03,0x08,0x18,0x19,0x0a,0x0b,0x0a, +0x04,0x04,0x00,0x02,0x02,0x12,0x03,0x09,0x02,0x1b, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x02,0x05,0x12, +0x03,0x09,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x00, +0x02,0x02,0x01,0x12,0x03,0x09,0x09,0x16,0x0a,0x0c, +0x0a,0x05,0x04,0x00,0x02,0x02,0x03,0x12,0x03,0x09, +0x19,0x1a,0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02,0x03, +0x12,0x03,0x0a,0x02,0x1a,0x0a,0x0c,0x0a,0x05,0x04, +0x00,0x02,0x03,0x05,0x12,0x03,0x0a,0x02,0x08,0x0a, +0x0c,0x0a,0x05,0x04,0x00,0x02,0x03,0x01,0x12,0x03, +0x0a,0x09,0x15,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02, +0x03,0x03,0x12,0x03,0x0a,0x18,0x19,0x0a,0x0b,0x0a, +0x04,0x04,0x00,0x02,0x04,0x12,0x03,0x0b,0x02,0x18, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x04,0x05,0x12, +0x03,0x0b,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x00, +0x02,0x04,0x01,0x12,0x03,0x0b,0x09,0x13,0x0a,0x0c, +0x0a,0x05,0x04,0x00,0x02,0x04,0x03,0x12,0x03,0x0b, +0x16,0x17,0x62,0x06,0x70,0x72,0x6f,0x74,0x6f,0x33, + +}; +static const char file_name[] = "plant.proto"; +static const char wpi_proto_ProtobufDCMotor_name[] = "wpi.proto.ProtobufDCMotor"; +std::string_view wpi_proto_ProtobufDCMotor::msg_name(void) noexcept { return wpi_proto_ProtobufDCMotor_name; } +pb_filedesc_t wpi_proto_ProtobufDCMotor::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufDCMotor, wpi_proto_ProtobufDCMotor, AUTO) + + + +#ifndef PB_CONVERT_DOUBLE_FLOAT +/* On some platforms (such as AVR), double is really float. + * To be able to encode/decode double on these platforms, you need. + * to define PB_CONVERT_DOUBLE_FLOAT in pb.h or compiler command line. + */ +PB_STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES) +#endif + diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/plant.npb.h b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/plant.npb.h new file mode 100644 index 0000000000..47e14486ae --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/plant.npb.h @@ -0,0 +1,57 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb header */ +/* Generated by nanopb-0.4.9 */ + +#ifndef PB_WPI_PROTO_PLANT_NPB_H_INCLUDED +#define PB_WPI_PROTO_PLANT_NPB_H_INCLUDED +#include +#include +#include + +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +/* Struct definitions */ +typedef struct _wpi_proto_ProtobufDCMotor { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double nominal_voltage; + double stall_torque; + double stall_current; + double free_current; + double free_speed; +} wpi_proto_ProtobufDCMotor; + + +/* Initializer values for message structs */ +#define wpi_proto_ProtobufDCMotor_init_default {0, 0, 0, 0, 0} +#define wpi_proto_ProtobufDCMotor_init_zero {0, 0, 0, 0, 0} + +/* Field tags (for use in manual encoding/decoding) */ +#define wpi_proto_ProtobufDCMotor_nominal_voltage_tag 1 +#define wpi_proto_ProtobufDCMotor_stall_torque_tag 2 +#define wpi_proto_ProtobufDCMotor_stall_current_tag 3 +#define wpi_proto_ProtobufDCMotor_free_current_tag 4 +#define wpi_proto_ProtobufDCMotor_free_speed_tag 5 + +/* Struct field encoding specification for nanopb */ +#define wpi_proto_ProtobufDCMotor_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, nominal_voltage, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, stall_torque, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, stall_current, 3) \ +X(a, STATIC, SINGULAR, DOUBLE, free_current, 4) \ +X(a, STATIC, SINGULAR, DOUBLE, free_speed, 5) +#define wpi_proto_ProtobufDCMotor_CALLBACK NULL +#define wpi_proto_ProtobufDCMotor_DEFAULT NULL + +/* Maximum encoded size of messages (where known) */ +#define WPI_PROTO_PLANT_NPB_H_MAX_SIZE wpi_proto_ProtobufDCMotor_size +#define wpi_proto_ProtobufDCMotor_size 45 + + +#endif diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/spline.npb.cpp b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/spline.npb.cpp new file mode 100644 index 0000000000..b49693b396 --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/spline.npb.cpp @@ -0,0 +1,137 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb constant definitions */ +/* Generated by nanopb-0.4.9 */ + +#include "spline.npb.h" +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +#include +#include +static const uint8_t file_descriptor[] { +0x0a,0x0c,0x73,0x70,0x6c,0x69,0x6e,0x65,0x2e,0x70, +0x72,0x6f,0x74,0x6f,0x12,0x09,0x77,0x70,0x69,0x2e, +0x70,0x72,0x6f,0x74,0x6f,0x22,0x88,0x01,0x0a,0x1a, +0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x43,0x75, +0x62,0x69,0x63,0x48,0x65,0x72,0x6d,0x69,0x74,0x65, +0x53,0x70,0x6c,0x69,0x6e,0x65,0x12,0x1b,0x0a,0x09, +0x78,0x5f,0x69,0x6e,0x69,0x74,0x69,0x61,0x6c,0x18, +0x01,0x20,0x03,0x28,0x01,0x52,0x08,0x78,0x49,0x6e, +0x69,0x74,0x69,0x61,0x6c,0x12,0x17,0x0a,0x07,0x78, +0x5f,0x66,0x69,0x6e,0x61,0x6c,0x18,0x02,0x20,0x03, +0x28,0x01,0x52,0x06,0x78,0x46,0x69,0x6e,0x61,0x6c, +0x12,0x1b,0x0a,0x09,0x79,0x5f,0x69,0x6e,0x69,0x74, +0x69,0x61,0x6c,0x18,0x03,0x20,0x03,0x28,0x01,0x52, +0x08,0x79,0x49,0x6e,0x69,0x74,0x69,0x61,0x6c,0x12, +0x17,0x0a,0x07,0x79,0x5f,0x66,0x69,0x6e,0x61,0x6c, +0x18,0x04,0x20,0x03,0x28,0x01,0x52,0x06,0x79,0x46, +0x69,0x6e,0x61,0x6c,0x22,0x8a,0x01,0x0a,0x1c,0x50, +0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x51,0x75,0x69, +0x6e,0x74,0x69,0x63,0x48,0x65,0x72,0x6d,0x69,0x74, +0x65,0x53,0x70,0x6c,0x69,0x6e,0x65,0x12,0x1b,0x0a, +0x09,0x78,0x5f,0x69,0x6e,0x69,0x74,0x69,0x61,0x6c, +0x18,0x01,0x20,0x03,0x28,0x01,0x52,0x08,0x78,0x49, +0x6e,0x69,0x74,0x69,0x61,0x6c,0x12,0x17,0x0a,0x07, +0x78,0x5f,0x66,0x69,0x6e,0x61,0x6c,0x18,0x02,0x20, +0x03,0x28,0x01,0x52,0x06,0x78,0x46,0x69,0x6e,0x61, +0x6c,0x12,0x1b,0x0a,0x09,0x79,0x5f,0x69,0x6e,0x69, +0x74,0x69,0x61,0x6c,0x18,0x03,0x20,0x03,0x28,0x01, +0x52,0x08,0x79,0x49,0x6e,0x69,0x74,0x69,0x61,0x6c, +0x12,0x17,0x0a,0x07,0x79,0x5f,0x66,0x69,0x6e,0x61, +0x6c,0x18,0x04,0x20,0x03,0x28,0x01,0x52,0x06,0x79, +0x46,0x69,0x6e,0x61,0x6c,0x42,0x1a,0x0a,0x18,0x65, +0x64,0x75,0x2e,0x77,0x70,0x69,0x2e,0x66,0x69,0x72, +0x73,0x74,0x2e,0x6d,0x61,0x74,0x68,0x2e,0x70,0x72, +0x6f,0x74,0x6f,0x4a,0x89,0x05,0x0a,0x06,0x12,0x04, +0x00,0x00,0x12,0x01,0x0a,0x08,0x0a,0x01,0x0c,0x12, +0x03,0x00,0x00,0x12,0x0a,0x08,0x0a,0x01,0x02,0x12, +0x03,0x02,0x00,0x12,0x0a,0x08,0x0a,0x01,0x08,0x12, +0x03,0x04,0x00,0x31,0x0a,0x09,0x0a,0x02,0x08,0x01, +0x12,0x03,0x04,0x00,0x31,0x0a,0x0a,0x0a,0x02,0x04, +0x00,0x12,0x04,0x06,0x00,0x0b,0x01,0x0a,0x0a,0x0a, +0x03,0x04,0x00,0x01,0x12,0x03,0x06,0x08,0x22,0x0a, +0x0b,0x0a,0x04,0x04,0x00,0x02,0x00,0x12,0x03,0x07, +0x02,0x20,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x00, +0x04,0x12,0x03,0x07,0x02,0x0a,0x0a,0x0c,0x0a,0x05, +0x04,0x00,0x02,0x00,0x05,0x12,0x03,0x07,0x0b,0x11, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x00,0x01,0x12, +0x03,0x07,0x12,0x1b,0x0a,0x0c,0x0a,0x05,0x04,0x00, +0x02,0x00,0x03,0x12,0x03,0x07,0x1e,0x1f,0x0a,0x0b, +0x0a,0x04,0x04,0x00,0x02,0x01,0x12,0x03,0x08,0x02, +0x1e,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x01,0x04, +0x12,0x03,0x08,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04, +0x00,0x02,0x01,0x05,0x12,0x03,0x08,0x0b,0x11,0x0a, +0x0c,0x0a,0x05,0x04,0x00,0x02,0x01,0x01,0x12,0x03, +0x08,0x12,0x19,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02, +0x01,0x03,0x12,0x03,0x08,0x1c,0x1d,0x0a,0x0b,0x0a, +0x04,0x04,0x00,0x02,0x02,0x12,0x03,0x09,0x02,0x20, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x02,0x04,0x12, +0x03,0x09,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x00, +0x02,0x02,0x05,0x12,0x03,0x09,0x0b,0x11,0x0a,0x0c, +0x0a,0x05,0x04,0x00,0x02,0x02,0x01,0x12,0x03,0x09, +0x12,0x1b,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x02, +0x03,0x12,0x03,0x09,0x1e,0x1f,0x0a,0x0b,0x0a,0x04, +0x04,0x00,0x02,0x03,0x12,0x03,0x0a,0x02,0x1e,0x0a, +0x0c,0x0a,0x05,0x04,0x00,0x02,0x03,0x04,0x12,0x03, +0x0a,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02, +0x03,0x05,0x12,0x03,0x0a,0x0b,0x11,0x0a,0x0c,0x0a, +0x05,0x04,0x00,0x02,0x03,0x01,0x12,0x03,0x0a,0x12, +0x19,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x03,0x03, +0x12,0x03,0x0a,0x1c,0x1d,0x0a,0x0a,0x0a,0x02,0x04, +0x01,0x12,0x04,0x0d,0x00,0x12,0x01,0x0a,0x0a,0x0a, +0x03,0x04,0x01,0x01,0x12,0x03,0x0d,0x08,0x24,0x0a, +0x0b,0x0a,0x04,0x04,0x01,0x02,0x00,0x12,0x03,0x0e, +0x02,0x20,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x00, +0x04,0x12,0x03,0x0e,0x02,0x0a,0x0a,0x0c,0x0a,0x05, +0x04,0x01,0x02,0x00,0x05,0x12,0x03,0x0e,0x0b,0x11, +0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x00,0x01,0x12, +0x03,0x0e,0x12,0x1b,0x0a,0x0c,0x0a,0x05,0x04,0x01, +0x02,0x00,0x03,0x12,0x03,0x0e,0x1e,0x1f,0x0a,0x0b, +0x0a,0x04,0x04,0x01,0x02,0x01,0x12,0x03,0x0f,0x02, +0x1e,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x01,0x04, +0x12,0x03,0x0f,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04, +0x01,0x02,0x01,0x05,0x12,0x03,0x0f,0x0b,0x11,0x0a, +0x0c,0x0a,0x05,0x04,0x01,0x02,0x01,0x01,0x12,0x03, +0x0f,0x12,0x19,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02, +0x01,0x03,0x12,0x03,0x0f,0x1c,0x1d,0x0a,0x0b,0x0a, +0x04,0x04,0x01,0x02,0x02,0x12,0x03,0x10,0x02,0x20, +0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x02,0x04,0x12, +0x03,0x10,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x01, +0x02,0x02,0x05,0x12,0x03,0x10,0x0b,0x11,0x0a,0x0c, +0x0a,0x05,0x04,0x01,0x02,0x02,0x01,0x12,0x03,0x10, +0x12,0x1b,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x02, +0x03,0x12,0x03,0x10,0x1e,0x1f,0x0a,0x0b,0x0a,0x04, +0x04,0x01,0x02,0x03,0x12,0x03,0x11,0x02,0x1e,0x0a, +0x0c,0x0a,0x05,0x04,0x01,0x02,0x03,0x04,0x12,0x03, +0x11,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02, +0x03,0x05,0x12,0x03,0x11,0x0b,0x11,0x0a,0x0c,0x0a, +0x05,0x04,0x01,0x02,0x03,0x01,0x12,0x03,0x11,0x12, +0x19,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x03,0x03, +0x12,0x03,0x11,0x1c,0x1d,0x62,0x06,0x70,0x72,0x6f, +0x74,0x6f,0x33, +}; +static const char file_name[] = "spline.proto"; +static const char wpi_proto_ProtobufCubicHermiteSpline_name[] = "wpi.proto.ProtobufCubicHermiteSpline"; +std::string_view wpi_proto_ProtobufCubicHermiteSpline::msg_name(void) noexcept { return wpi_proto_ProtobufCubicHermiteSpline_name; } +pb_filedesc_t wpi_proto_ProtobufCubicHermiteSpline::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufCubicHermiteSpline, wpi_proto_ProtobufCubicHermiteSpline, AUTO) + + +static const char wpi_proto_ProtobufQuinticHermiteSpline_name[] = "wpi.proto.ProtobufQuinticHermiteSpline"; +std::string_view wpi_proto_ProtobufQuinticHermiteSpline::msg_name(void) noexcept { return wpi_proto_ProtobufQuinticHermiteSpline_name; } +pb_filedesc_t wpi_proto_ProtobufQuinticHermiteSpline::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufQuinticHermiteSpline, wpi_proto_ProtobufQuinticHermiteSpline, AUTO) + + + +#ifndef PB_CONVERT_DOUBLE_FLOAT +/* On some platforms (such as AVR), double is really float. + * To be able to encode/decode double on these platforms, you need. + * to define PB_CONVERT_DOUBLE_FLOAT in pb.h or compiler command line. + */ +PB_STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES) +#endif + diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/spline.npb.h b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/spline.npb.h new file mode 100644 index 0000000000..411f977e28 --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/spline.npb.h @@ -0,0 +1,79 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb header */ +/* Generated by nanopb-0.4.9 */ + +#ifndef PB_WPI_PROTO_SPLINE_NPB_H_INCLUDED +#define PB_WPI_PROTO_SPLINE_NPB_H_INCLUDED +#include +#include +#include + +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +/* Struct definitions */ +typedef struct _wpi_proto_ProtobufCubicHermiteSpline { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + pb_callback_t x_initial; + pb_callback_t x_final; + pb_callback_t y_initial; + pb_callback_t y_final; +} wpi_proto_ProtobufCubicHermiteSpline; + +typedef struct _wpi_proto_ProtobufQuinticHermiteSpline { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + pb_callback_t x_initial; + pb_callback_t x_final; + pb_callback_t y_initial; + pb_callback_t y_final; +} wpi_proto_ProtobufQuinticHermiteSpline; + + +/* Initializer values for message structs */ +#define wpi_proto_ProtobufCubicHermiteSpline_init_default {{{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_ProtobufQuinticHermiteSpline_init_default {{{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_ProtobufCubicHermiteSpline_init_zero {{{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_ProtobufQuinticHermiteSpline_init_zero {{{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}} + +/* Field tags (for use in manual encoding/decoding) */ +#define wpi_proto_ProtobufCubicHermiteSpline_x_initial_tag 1 +#define wpi_proto_ProtobufCubicHermiteSpline_x_final_tag 2 +#define wpi_proto_ProtobufCubicHermiteSpline_y_initial_tag 3 +#define wpi_proto_ProtobufCubicHermiteSpline_y_final_tag 4 +#define wpi_proto_ProtobufQuinticHermiteSpline_x_initial_tag 1 +#define wpi_proto_ProtobufQuinticHermiteSpline_x_final_tag 2 +#define wpi_proto_ProtobufQuinticHermiteSpline_y_initial_tag 3 +#define wpi_proto_ProtobufQuinticHermiteSpline_y_final_tag 4 + +/* Struct field encoding specification for nanopb */ +#define wpi_proto_ProtobufCubicHermiteSpline_FIELDLIST(X, a) \ +X(a, CALLBACK, REPEATED, DOUBLE, x_initial, 1) \ +X(a, CALLBACK, REPEATED, DOUBLE, x_final, 2) \ +X(a, CALLBACK, REPEATED, DOUBLE, y_initial, 3) \ +X(a, CALLBACK, REPEATED, DOUBLE, y_final, 4) +#define wpi_proto_ProtobufCubicHermiteSpline_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufCubicHermiteSpline_DEFAULT NULL + +#define wpi_proto_ProtobufQuinticHermiteSpline_FIELDLIST(X, a) \ +X(a, CALLBACK, REPEATED, DOUBLE, x_initial, 1) \ +X(a, CALLBACK, REPEATED, DOUBLE, x_final, 2) \ +X(a, CALLBACK, REPEATED, DOUBLE, y_initial, 3) \ +X(a, CALLBACK, REPEATED, DOUBLE, y_final, 4) +#define wpi_proto_ProtobufQuinticHermiteSpline_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufQuinticHermiteSpline_DEFAULT NULL + +/* Maximum encoded size of messages (where known) */ +/* wpi_proto_ProtobufCubicHermiteSpline_size depends on runtime parameters */ +/* wpi_proto_ProtobufQuinticHermiteSpline_size depends on runtime parameters */ + + +#endif diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/system.npb.cpp b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/system.npb.cpp new file mode 100644 index 0000000000..edf45ec4b8 --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/system.npb.cpp @@ -0,0 +1,107 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb constant definitions */ +/* Generated by nanopb-0.4.9 */ + +#include "system.npb.h" +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +#include +#include +static const uint8_t file_descriptor[] { +0x0a,0x0c,0x73,0x79,0x73,0x74,0x65,0x6d,0x2e,0x70, +0x72,0x6f,0x74,0x6f,0x12,0x09,0x77,0x70,0x69,0x2e, +0x70,0x72,0x6f,0x74,0x6f,0x1a,0x0d,0x77,0x70,0x69, +0x6d,0x61,0x74,0x68,0x2e,0x70,0x72,0x6f,0x74,0x6f, +0x22,0x99,0x02,0x0a,0x14,0x50,0x72,0x6f,0x74,0x6f, +0x62,0x75,0x66,0x4c,0x69,0x6e,0x65,0x61,0x72,0x53, +0x79,0x73,0x74,0x65,0x6d,0x12,0x1d,0x0a,0x0a,0x6e, +0x75,0x6d,0x5f,0x73,0x74,0x61,0x74,0x65,0x73,0x18, +0x01,0x20,0x01,0x28,0x0d,0x52,0x09,0x6e,0x75,0x6d, +0x53,0x74,0x61,0x74,0x65,0x73,0x12,0x1d,0x0a,0x0a, +0x6e,0x75,0x6d,0x5f,0x69,0x6e,0x70,0x75,0x74,0x73, +0x18,0x02,0x20,0x01,0x28,0x0d,0x52,0x09,0x6e,0x75, +0x6d,0x49,0x6e,0x70,0x75,0x74,0x73,0x12,0x1f,0x0a, +0x0b,0x6e,0x75,0x6d,0x5f,0x6f,0x75,0x74,0x70,0x75, +0x74,0x73,0x18,0x03,0x20,0x01,0x28,0x0d,0x52,0x0a, +0x6e,0x75,0x6d,0x4f,0x75,0x74,0x70,0x75,0x74,0x73, +0x12,0x27,0x0a,0x01,0x61,0x18,0x04,0x20,0x01,0x28, +0x0b,0x32,0x19,0x2e,0x77,0x70,0x69,0x2e,0x70,0x72, +0x6f,0x74,0x6f,0x2e,0x50,0x72,0x6f,0x74,0x6f,0x62, +0x75,0x66,0x4d,0x61,0x74,0x72,0x69,0x78,0x52,0x01, +0x61,0x12,0x27,0x0a,0x01,0x62,0x18,0x05,0x20,0x01, +0x28,0x0b,0x32,0x19,0x2e,0x77,0x70,0x69,0x2e,0x70, +0x72,0x6f,0x74,0x6f,0x2e,0x50,0x72,0x6f,0x74,0x6f, +0x62,0x75,0x66,0x4d,0x61,0x74,0x72,0x69,0x78,0x52, +0x01,0x62,0x12,0x27,0x0a,0x01,0x63,0x18,0x06,0x20, +0x01,0x28,0x0b,0x32,0x19,0x2e,0x77,0x70,0x69,0x2e, +0x70,0x72,0x6f,0x74,0x6f,0x2e,0x50,0x72,0x6f,0x74, +0x6f,0x62,0x75,0x66,0x4d,0x61,0x74,0x72,0x69,0x78, +0x52,0x01,0x63,0x12,0x27,0x0a,0x01,0x64,0x18,0x07, +0x20,0x01,0x28,0x0b,0x32,0x19,0x2e,0x77,0x70,0x69, +0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e,0x50,0x72,0x6f, +0x74,0x6f,0x62,0x75,0x66,0x4d,0x61,0x74,0x72,0x69, +0x78,0x52,0x01,0x64,0x42,0x1a,0x0a,0x18,0x65,0x64, +0x75,0x2e,0x77,0x70,0x69,0x2e,0x66,0x69,0x72,0x73, +0x74,0x2e,0x6d,0x61,0x74,0x68,0x2e,0x70,0x72,0x6f, +0x74,0x6f,0x4a,0xd5,0x03,0x0a,0x06,0x12,0x04,0x00, +0x00,0x10,0x01,0x0a,0x08,0x0a,0x01,0x0c,0x12,0x03, +0x00,0x00,0x12,0x0a,0x08,0x0a,0x01,0x02,0x12,0x03, +0x02,0x00,0x12,0x0a,0x09,0x0a,0x02,0x03,0x00,0x12, +0x03,0x04,0x00,0x17,0x0a,0x08,0x0a,0x01,0x08,0x12, +0x03,0x06,0x00,0x31,0x0a,0x09,0x0a,0x02,0x08,0x01, +0x12,0x03,0x06,0x00,0x31,0x0a,0x0a,0x0a,0x02,0x04, +0x00,0x12,0x04,0x08,0x00,0x10,0x01,0x0a,0x0a,0x0a, +0x03,0x04,0x00,0x01,0x12,0x03,0x08,0x08,0x1c,0x0a, +0x0b,0x0a,0x04,0x04,0x00,0x02,0x00,0x12,0x03,0x09, +0x02,0x18,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x00, +0x05,0x12,0x03,0x09,0x02,0x08,0x0a,0x0c,0x0a,0x05, +0x04,0x00,0x02,0x00,0x01,0x12,0x03,0x09,0x09,0x13, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x00,0x03,0x12, +0x03,0x09,0x16,0x17,0x0a,0x0b,0x0a,0x04,0x04,0x00, +0x02,0x01,0x12,0x03,0x0a,0x02,0x18,0x0a,0x0c,0x0a, +0x05,0x04,0x00,0x02,0x01,0x05,0x12,0x03,0x0a,0x02, +0x08,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x01,0x01, +0x12,0x03,0x0a,0x09,0x13,0x0a,0x0c,0x0a,0x05,0x04, +0x00,0x02,0x01,0x03,0x12,0x03,0x0a,0x16,0x17,0x0a, +0x0b,0x0a,0x04,0x04,0x00,0x02,0x02,0x12,0x03,0x0b, +0x02,0x19,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x02, +0x05,0x12,0x03,0x0b,0x02,0x08,0x0a,0x0c,0x0a,0x05, +0x04,0x00,0x02,0x02,0x01,0x12,0x03,0x0b,0x09,0x14, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x02,0x03,0x12, +0x03,0x0b,0x17,0x18,0x0a,0x0b,0x0a,0x04,0x04,0x00, +0x02,0x03,0x12,0x03,0x0c,0x02,0x17,0x0a,0x0c,0x0a, +0x05,0x04,0x00,0x02,0x03,0x06,0x12,0x03,0x0c,0x02, +0x10,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x03,0x01, +0x12,0x03,0x0c,0x11,0x12,0x0a,0x0c,0x0a,0x05,0x04, +0x00,0x02,0x03,0x03,0x12,0x03,0x0c,0x15,0x16,0x0a, +0x0b,0x0a,0x04,0x04,0x00,0x02,0x04,0x12,0x03,0x0d, +0x02,0x17,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x04, +0x06,0x12,0x03,0x0d,0x02,0x10,0x0a,0x0c,0x0a,0x05, +0x04,0x00,0x02,0x04,0x01,0x12,0x03,0x0d,0x11,0x12, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x04,0x03,0x12, +0x03,0x0d,0x15,0x16,0x0a,0x0b,0x0a,0x04,0x04,0x00, +0x02,0x05,0x12,0x03,0x0e,0x02,0x17,0x0a,0x0c,0x0a, +0x05,0x04,0x00,0x02,0x05,0x06,0x12,0x03,0x0e,0x02, +0x10,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x05,0x01, +0x12,0x03,0x0e,0x11,0x12,0x0a,0x0c,0x0a,0x05,0x04, +0x00,0x02,0x05,0x03,0x12,0x03,0x0e,0x15,0x16,0x0a, +0x0b,0x0a,0x04,0x04,0x00,0x02,0x06,0x12,0x03,0x0f, +0x02,0x17,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x06, +0x06,0x12,0x03,0x0f,0x02,0x10,0x0a,0x0c,0x0a,0x05, +0x04,0x00,0x02,0x06,0x01,0x12,0x03,0x0f,0x11,0x12, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x06,0x03,0x12, +0x03,0x0f,0x15,0x16,0x62,0x06,0x70,0x72,0x6f,0x74, +0x6f,0x33, +}; +static const char file_name[] = "system.proto"; +static const char wpi_proto_ProtobufLinearSystem_name[] = "wpi.proto.ProtobufLinearSystem"; +std::string_view wpi_proto_ProtobufLinearSystem::msg_name(void) noexcept { return wpi_proto_ProtobufLinearSystem_name; } +pb_filedesc_t wpi_proto_ProtobufLinearSystem::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufLinearSystem, wpi_proto_ProtobufLinearSystem, AUTO) + + + diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/system.npb.h b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/system.npb.h new file mode 100644 index 0000000000..2f7b40f3d9 --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/system.npb.h @@ -0,0 +1,67 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb header */ +/* Generated by nanopb-0.4.9 */ + +#ifndef PB_WPI_PROTO_SYSTEM_NPB_H_INCLUDED +#define PB_WPI_PROTO_SYSTEM_NPB_H_INCLUDED +#include +#include +#include +#include "wpimath.npb.h" + +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +/* Struct definitions */ +typedef struct _wpi_proto_ProtobufLinearSystem { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + uint32_t num_states; + uint32_t num_inputs; + uint32_t num_outputs; + pb_callback_t a; + pb_callback_t b; + pb_callback_t c; + pb_callback_t d; +} wpi_proto_ProtobufLinearSystem; + + +/* Initializer values for message structs */ +#define wpi_proto_ProtobufLinearSystem_init_default {0, 0, 0, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_ProtobufLinearSystem_init_zero {0, 0, 0, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}} + +/* Field tags (for use in manual encoding/decoding) */ +#define wpi_proto_ProtobufLinearSystem_num_states_tag 1 +#define wpi_proto_ProtobufLinearSystem_num_inputs_tag 2 +#define wpi_proto_ProtobufLinearSystem_num_outputs_tag 3 +#define wpi_proto_ProtobufLinearSystem_a_tag 4 +#define wpi_proto_ProtobufLinearSystem_b_tag 5 +#define wpi_proto_ProtobufLinearSystem_c_tag 6 +#define wpi_proto_ProtobufLinearSystem_d_tag 7 + +/* Struct field encoding specification for nanopb */ +#define wpi_proto_ProtobufLinearSystem_FIELDLIST(X, a_) \ +X(a_, STATIC, SINGULAR, UINT32, num_states, 1) \ +X(a_, STATIC, SINGULAR, UINT32, num_inputs, 2) \ +X(a_, STATIC, SINGULAR, UINT32, num_outputs, 3) \ +X(a_, CALLBACK, OPTIONAL, MESSAGE, a, 4) \ +X(a_, CALLBACK, OPTIONAL, MESSAGE, b, 5) \ +X(a_, CALLBACK, OPTIONAL, MESSAGE, c, 6) \ +X(a_, CALLBACK, OPTIONAL, MESSAGE, d, 7) +#define wpi_proto_ProtobufLinearSystem_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufLinearSystem_DEFAULT NULL +#define wpi_proto_ProtobufLinearSystem_a_MSGTYPE wpi_proto_ProtobufMatrix +#define wpi_proto_ProtobufLinearSystem_b_MSGTYPE wpi_proto_ProtobufMatrix +#define wpi_proto_ProtobufLinearSystem_c_MSGTYPE wpi_proto_ProtobufMatrix +#define wpi_proto_ProtobufLinearSystem_d_MSGTYPE wpi_proto_ProtobufMatrix + +/* Maximum encoded size of messages (where known) */ +/* wpi_proto_ProtobufLinearSystem_size depends on runtime parameters */ + + +#endif diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/trajectory.npb.cpp b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/trajectory.npb.cpp new file mode 100644 index 0000000000..cf66d5befd --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/trajectory.npb.cpp @@ -0,0 +1,118 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb constant definitions */ +/* Generated by nanopb-0.4.9 */ + +#include "trajectory.npb.h" +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +#include +#include +static const uint8_t file_descriptor[] { +0x0a,0x10,0x74,0x72,0x61,0x6a,0x65,0x63,0x74,0x6f, +0x72,0x79,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x12,0x09, +0x77,0x70,0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x1a, +0x10,0x67,0x65,0x6f,0x6d,0x65,0x74,0x72,0x79,0x32, +0x64,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x22,0xba,0x01, +0x0a,0x17,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66, +0x54,0x72,0x61,0x6a,0x65,0x63,0x74,0x6f,0x72,0x79, +0x53,0x74,0x61,0x74,0x65,0x12,0x12,0x0a,0x04,0x74, +0x69,0x6d,0x65,0x18,0x01,0x20,0x01,0x28,0x01,0x52, +0x04,0x74,0x69,0x6d,0x65,0x12,0x1a,0x0a,0x08,0x76, +0x65,0x6c,0x6f,0x63,0x69,0x74,0x79,0x18,0x02,0x20, +0x01,0x28,0x01,0x52,0x08,0x76,0x65,0x6c,0x6f,0x63, +0x69,0x74,0x79,0x12,0x22,0x0a,0x0c,0x61,0x63,0x63, +0x65,0x6c,0x65,0x72,0x61,0x74,0x69,0x6f,0x6e,0x18, +0x03,0x20,0x01,0x28,0x01,0x52,0x0c,0x61,0x63,0x63, +0x65,0x6c,0x65,0x72,0x61,0x74,0x69,0x6f,0x6e,0x12, +0x2d,0x0a,0x04,0x70,0x6f,0x73,0x65,0x18,0x04,0x20, +0x01,0x28,0x0b,0x32,0x19,0x2e,0x77,0x70,0x69,0x2e, +0x70,0x72,0x6f,0x74,0x6f,0x2e,0x50,0x72,0x6f,0x74, +0x6f,0x62,0x75,0x66,0x50,0x6f,0x73,0x65,0x32,0x64, +0x52,0x04,0x70,0x6f,0x73,0x65,0x12,0x1c,0x0a,0x09, +0x63,0x75,0x72,0x76,0x61,0x74,0x75,0x72,0x65,0x18, +0x05,0x20,0x01,0x28,0x01,0x52,0x09,0x63,0x75,0x72, +0x76,0x61,0x74,0x75,0x72,0x65,0x22,0x50,0x0a,0x12, +0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x54,0x72, +0x61,0x6a,0x65,0x63,0x74,0x6f,0x72,0x79,0x12,0x3a, +0x0a,0x06,0x73,0x74,0x61,0x74,0x65,0x73,0x18,0x02, +0x20,0x03,0x28,0x0b,0x32,0x22,0x2e,0x77,0x70,0x69, +0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e,0x50,0x72,0x6f, +0x74,0x6f,0x62,0x75,0x66,0x54,0x72,0x61,0x6a,0x65, +0x63,0x74,0x6f,0x72,0x79,0x53,0x74,0x61,0x74,0x65, +0x52,0x06,0x73,0x74,0x61,0x74,0x65,0x73,0x42,0x1a, +0x0a,0x18,0x65,0x64,0x75,0x2e,0x77,0x70,0x69,0x2e, +0x66,0x69,0x72,0x73,0x74,0x2e,0x6d,0x61,0x74,0x68, +0x2e,0x70,0x72,0x6f,0x74,0x6f,0x4a,0xc4,0x03,0x0a, +0x06,0x12,0x04,0x00,0x00,0x12,0x01,0x0a,0x08,0x0a, +0x01,0x0c,0x12,0x03,0x00,0x00,0x12,0x0a,0x08,0x0a, +0x01,0x02,0x12,0x03,0x02,0x00,0x12,0x0a,0x09,0x0a, +0x02,0x03,0x00,0x12,0x03,0x04,0x00,0x1a,0x0a,0x08, +0x0a,0x01,0x08,0x12,0x03,0x06,0x00,0x31,0x0a,0x09, +0x0a,0x02,0x08,0x01,0x12,0x03,0x06,0x00,0x31,0x0a, +0x0a,0x0a,0x02,0x04,0x00,0x12,0x04,0x08,0x00,0x0e, +0x01,0x0a,0x0a,0x0a,0x03,0x04,0x00,0x01,0x12,0x03, +0x08,0x08,0x1f,0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02, +0x00,0x12,0x03,0x09,0x02,0x12,0x0a,0x0c,0x0a,0x05, +0x04,0x00,0x02,0x00,0x05,0x12,0x03,0x09,0x02,0x08, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x00,0x01,0x12, +0x03,0x09,0x09,0x0d,0x0a,0x0c,0x0a,0x05,0x04,0x00, +0x02,0x00,0x03,0x12,0x03,0x09,0x10,0x11,0x0a,0x0b, +0x0a,0x04,0x04,0x00,0x02,0x01,0x12,0x03,0x0a,0x02, +0x16,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x01,0x05, +0x12,0x03,0x0a,0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04, +0x00,0x02,0x01,0x01,0x12,0x03,0x0a,0x09,0x11,0x0a, +0x0c,0x0a,0x05,0x04,0x00,0x02,0x01,0x03,0x12,0x03, +0x0a,0x14,0x15,0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02, +0x02,0x12,0x03,0x0b,0x02,0x1a,0x0a,0x0c,0x0a,0x05, +0x04,0x00,0x02,0x02,0x05,0x12,0x03,0x0b,0x02,0x08, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x02,0x01,0x12, +0x03,0x0b,0x09,0x15,0x0a,0x0c,0x0a,0x05,0x04,0x00, +0x02,0x02,0x03,0x12,0x03,0x0b,0x18,0x19,0x0a,0x0b, +0x0a,0x04,0x04,0x00,0x02,0x03,0x12,0x03,0x0c,0x02, +0x1a,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x03,0x06, +0x12,0x03,0x0c,0x02,0x10,0x0a,0x0c,0x0a,0x05,0x04, +0x00,0x02,0x03,0x01,0x12,0x03,0x0c,0x11,0x15,0x0a, +0x0c,0x0a,0x05,0x04,0x00,0x02,0x03,0x03,0x12,0x03, +0x0c,0x18,0x19,0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02, +0x04,0x12,0x03,0x0d,0x02,0x17,0x0a,0x0c,0x0a,0x05, +0x04,0x00,0x02,0x04,0x05,0x12,0x03,0x0d,0x02,0x08, +0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x04,0x01,0x12, +0x03,0x0d,0x09,0x12,0x0a,0x0c,0x0a,0x05,0x04,0x00, +0x02,0x04,0x03,0x12,0x03,0x0d,0x15,0x16,0x0a,0x0a, +0x0a,0x02,0x04,0x01,0x12,0x04,0x10,0x00,0x12,0x01, +0x0a,0x0a,0x0a,0x03,0x04,0x01,0x01,0x12,0x03,0x10, +0x08,0x1a,0x0a,0x0b,0x0a,0x04,0x04,0x01,0x02,0x00, +0x12,0x03,0x11,0x02,0x2e,0x0a,0x0c,0x0a,0x05,0x04, +0x01,0x02,0x00,0x04,0x12,0x03,0x11,0x02,0x0a,0x0a, +0x0c,0x0a,0x05,0x04,0x01,0x02,0x00,0x06,0x12,0x03, +0x11,0x0b,0x22,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02, +0x00,0x01,0x12,0x03,0x11,0x23,0x29,0x0a,0x0c,0x0a, +0x05,0x04,0x01,0x02,0x00,0x03,0x12,0x03,0x11,0x2c, +0x2d,0x62,0x06,0x70,0x72,0x6f,0x74,0x6f,0x33, +}; +static const char file_name[] = "trajectory.proto"; +static const char wpi_proto_ProtobufTrajectoryState_name[] = "wpi.proto.ProtobufTrajectoryState"; +std::string_view wpi_proto_ProtobufTrajectoryState::msg_name(void) noexcept { return wpi_proto_ProtobufTrajectoryState_name; } +pb_filedesc_t wpi_proto_ProtobufTrajectoryState::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufTrajectoryState, wpi_proto_ProtobufTrajectoryState, AUTO) + + +static const char wpi_proto_ProtobufTrajectory_name[] = "wpi.proto.ProtobufTrajectory"; +std::string_view wpi_proto_ProtobufTrajectory::msg_name(void) noexcept { return wpi_proto_ProtobufTrajectory_name; } +pb_filedesc_t wpi_proto_ProtobufTrajectory::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufTrajectory, wpi_proto_ProtobufTrajectory, AUTO) + + + +#ifndef PB_CONVERT_DOUBLE_FLOAT +/* On some platforms (such as AVR), double is really float. + * To be able to encode/decode double on these platforms, you need. + * to define PB_CONVERT_DOUBLE_FLOAT in pb.h or compiler command line. + */ +PB_STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES) +#endif + diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/trajectory.npb.h b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/trajectory.npb.h new file mode 100644 index 0000000000..87494e31a2 --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/trajectory.npb.h @@ -0,0 +1,76 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb header */ +/* Generated by nanopb-0.4.9 */ + +#ifndef PB_WPI_PROTO_TRAJECTORY_NPB_H_INCLUDED +#define PB_WPI_PROTO_TRAJECTORY_NPB_H_INCLUDED +#include +#include +#include +#include "geometry2d.npb.h" + +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +/* Struct definitions */ +typedef struct _wpi_proto_ProtobufTrajectoryState { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double time; + double velocity; + double acceleration; + pb_callback_t pose; + double curvature; +} wpi_proto_ProtobufTrajectoryState; + +typedef struct _wpi_proto_ProtobufTrajectory { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + pb_callback_t states; +} wpi_proto_ProtobufTrajectory; + + +/* Initializer values for message structs */ +#define wpi_proto_ProtobufTrajectoryState_init_default {0, 0, 0, {{NULL}, NULL}, 0} +#define wpi_proto_ProtobufTrajectory_init_default {{{NULL}, NULL}} +#define wpi_proto_ProtobufTrajectoryState_init_zero {0, 0, 0, {{NULL}, NULL}, 0} +#define wpi_proto_ProtobufTrajectory_init_zero {{{NULL}, NULL}} + +/* Field tags (for use in manual encoding/decoding) */ +#define wpi_proto_ProtobufTrajectoryState_time_tag 1 +#define wpi_proto_ProtobufTrajectoryState_velocity_tag 2 +#define wpi_proto_ProtobufTrajectoryState_acceleration_tag 3 +#define wpi_proto_ProtobufTrajectoryState_pose_tag 4 +#define wpi_proto_ProtobufTrajectoryState_curvature_tag 5 +#define wpi_proto_ProtobufTrajectory_states_tag 2 + +/* Struct field encoding specification for nanopb */ +#define wpi_proto_ProtobufTrajectoryState_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, time, 1) \ +X(a, STATIC, SINGULAR, DOUBLE, velocity, 2) \ +X(a, STATIC, SINGULAR, DOUBLE, acceleration, 3) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, pose, 4) \ +X(a, STATIC, SINGULAR, DOUBLE, curvature, 5) +#define wpi_proto_ProtobufTrajectoryState_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufTrajectoryState_DEFAULT NULL +#define wpi_proto_ProtobufTrajectoryState_pose_MSGTYPE wpi_proto_ProtobufPose2d + +#define wpi_proto_ProtobufTrajectory_FIELDLIST(X, a) \ +X(a, CALLBACK, REPEATED, MESSAGE, states, 2) +#define wpi_proto_ProtobufTrajectory_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufTrajectory_DEFAULT NULL +#define wpi_proto_ProtobufTrajectory_states_MSGTYPE wpi_proto_ProtobufTrajectoryState + +/* Maximum encoded size of messages (where known) */ +/* wpi_proto_ProtobufTrajectoryState_size depends on runtime parameters */ +/* wpi_proto_ProtobufTrajectory_size depends on runtime parameters */ + + +#endif diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/wpimath.npb.cpp b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/wpimath.npb.cpp new file mode 100644 index 0000000000..d180c7e271 --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/wpimath.npb.cpp @@ -0,0 +1,92 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb constant definitions */ +/* Generated by nanopb-0.4.9 */ + +#include "wpimath.npb.h" +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +#include +#include +static const uint8_t file_descriptor[] { +0x0a,0x0d,0x77,0x70,0x69,0x6d,0x61,0x74,0x68,0x2e, +0x70,0x72,0x6f,0x74,0x6f,0x12,0x09,0x77,0x70,0x69, +0x2e,0x70,0x72,0x6f,0x74,0x6f,0x22,0x5a,0x0a,0x0e, +0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66,0x4d,0x61, +0x74,0x72,0x69,0x78,0x12,0x19,0x0a,0x08,0x6e,0x75, +0x6d,0x5f,0x72,0x6f,0x77,0x73,0x18,0x01,0x20,0x01, +0x28,0x0d,0x52,0x07,0x6e,0x75,0x6d,0x52,0x6f,0x77, +0x73,0x12,0x19,0x0a,0x08,0x6e,0x75,0x6d,0x5f,0x63, +0x6f,0x6c,0x73,0x18,0x02,0x20,0x01,0x28,0x0d,0x52, +0x07,0x6e,0x75,0x6d,0x43,0x6f,0x6c,0x73,0x12,0x12, +0x0a,0x04,0x64,0x61,0x74,0x61,0x18,0x03,0x20,0x03, +0x28,0x01,0x52,0x04,0x64,0x61,0x74,0x61,0x22,0x24, +0x0a,0x0e,0x50,0x72,0x6f,0x74,0x6f,0x62,0x75,0x66, +0x56,0x65,0x63,0x74,0x6f,0x72,0x12,0x12,0x0a,0x04, +0x72,0x6f,0x77,0x73,0x18,0x01,0x20,0x03,0x28,0x01, +0x52,0x04,0x72,0x6f,0x77,0x73,0x42,0x1a,0x0a,0x18, +0x65,0x64,0x75,0x2e,0x77,0x70,0x69,0x2e,0x66,0x69, +0x72,0x73,0x74,0x2e,0x6d,0x61,0x74,0x68,0x2e,0x70, +0x72,0x6f,0x74,0x6f,0x4a,0xd9,0x02,0x0a,0x06,0x12, +0x04,0x00,0x00,0x0e,0x01,0x0a,0x08,0x0a,0x01,0x0c, +0x12,0x03,0x00,0x00,0x12,0x0a,0x08,0x0a,0x01,0x02, +0x12,0x03,0x02,0x00,0x12,0x0a,0x08,0x0a,0x01,0x08, +0x12,0x03,0x04,0x00,0x31,0x0a,0x09,0x0a,0x02,0x08, +0x01,0x12,0x03,0x04,0x00,0x31,0x0a,0x0a,0x0a,0x02, +0x04,0x00,0x12,0x04,0x06,0x00,0x0a,0x01,0x0a,0x0a, +0x0a,0x03,0x04,0x00,0x01,0x12,0x03,0x06,0x08,0x16, +0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02,0x00,0x12,0x03, +0x07,0x02,0x16,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02, +0x00,0x05,0x12,0x03,0x07,0x02,0x08,0x0a,0x0c,0x0a, +0x05,0x04,0x00,0x02,0x00,0x01,0x12,0x03,0x07,0x09, +0x11,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x00,0x03, +0x12,0x03,0x07,0x14,0x15,0x0a,0x0b,0x0a,0x04,0x04, +0x00,0x02,0x01,0x12,0x03,0x08,0x02,0x16,0x0a,0x0c, +0x0a,0x05,0x04,0x00,0x02,0x01,0x05,0x12,0x03,0x08, +0x02,0x08,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x01, +0x01,0x12,0x03,0x08,0x09,0x11,0x0a,0x0c,0x0a,0x05, +0x04,0x00,0x02,0x01,0x03,0x12,0x03,0x08,0x14,0x15, +0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02,0x02,0x12,0x03, +0x09,0x02,0x1b,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02, +0x02,0x04,0x12,0x03,0x09,0x02,0x0a,0x0a,0x0c,0x0a, +0x05,0x04,0x00,0x02,0x02,0x05,0x12,0x03,0x09,0x0b, +0x11,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x02,0x01, +0x12,0x03,0x09,0x12,0x16,0x0a,0x0c,0x0a,0x05,0x04, +0x00,0x02,0x02,0x03,0x12,0x03,0x09,0x19,0x1a,0x0a, +0x0a,0x0a,0x02,0x04,0x01,0x12,0x04,0x0c,0x00,0x0e, +0x01,0x0a,0x0a,0x0a,0x03,0x04,0x01,0x01,0x12,0x03, +0x0c,0x08,0x16,0x0a,0x0b,0x0a,0x04,0x04,0x01,0x02, +0x00,0x12,0x03,0x0d,0x02,0x1b,0x0a,0x0c,0x0a,0x05, +0x04,0x01,0x02,0x00,0x04,0x12,0x03,0x0d,0x02,0x0a, +0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x00,0x05,0x12, +0x03,0x0d,0x0b,0x11,0x0a,0x0c,0x0a,0x05,0x04,0x01, +0x02,0x00,0x01,0x12,0x03,0x0d,0x12,0x16,0x0a,0x0c, +0x0a,0x05,0x04,0x01,0x02,0x00,0x03,0x12,0x03,0x0d, +0x19,0x1a,0x62,0x06,0x70,0x72,0x6f,0x74,0x6f,0x33, + +}; +static const char file_name[] = "wpimath.proto"; +static const char wpi_proto_ProtobufMatrix_name[] = "wpi.proto.ProtobufMatrix"; +std::string_view wpi_proto_ProtobufMatrix::msg_name(void) noexcept { return wpi_proto_ProtobufMatrix_name; } +pb_filedesc_t wpi_proto_ProtobufMatrix::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufMatrix, wpi_proto_ProtobufMatrix, AUTO) + + +static const char wpi_proto_ProtobufVector_name[] = "wpi.proto.ProtobufVector"; +std::string_view wpi_proto_ProtobufVector::msg_name(void) noexcept { return wpi_proto_ProtobufVector_name; } +pb_filedesc_t wpi_proto_ProtobufVector::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_ProtobufVector, wpi_proto_ProtobufVector, AUTO) + + + +#ifndef PB_CONVERT_DOUBLE_FLOAT +/* On some platforms (such as AVR), double is really float. + * To be able to encode/decode double on these platforms, you need. + * to define PB_CONVERT_DOUBLE_FLOAT in pb.h or compiler command line. + */ +PB_STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES) +#endif + diff --git a/wpimath/src/generated/main/native/cpp/wpimath/protobuf/wpimath.npb.h b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/wpimath.npb.h new file mode 100644 index 0000000000..c704c44b50 --- /dev/null +++ b/wpimath/src/generated/main/native/cpp/wpimath/protobuf/wpimath.npb.h @@ -0,0 +1,67 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb header */ +/* Generated by nanopb-0.4.9 */ + +#ifndef PB_WPI_PROTO_WPIMATH_NPB_H_INCLUDED +#define PB_WPI_PROTO_WPIMATH_NPB_H_INCLUDED +#include +#include +#include + +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +/* Struct definitions */ +typedef struct _wpi_proto_ProtobufMatrix { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + uint32_t num_rows; + uint32_t num_cols; + pb_callback_t data; +} wpi_proto_ProtobufMatrix; + +typedef struct _wpi_proto_ProtobufVector { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + pb_callback_t rows; +} wpi_proto_ProtobufVector; + + +/* Initializer values for message structs */ +#define wpi_proto_ProtobufMatrix_init_default {0, 0, {{NULL}, NULL}} +#define wpi_proto_ProtobufVector_init_default {{{NULL}, NULL}} +#define wpi_proto_ProtobufMatrix_init_zero {0, 0, {{NULL}, NULL}} +#define wpi_proto_ProtobufVector_init_zero {{{NULL}, NULL}} + +/* Field tags (for use in manual encoding/decoding) */ +#define wpi_proto_ProtobufMatrix_num_rows_tag 1 +#define wpi_proto_ProtobufMatrix_num_cols_tag 2 +#define wpi_proto_ProtobufMatrix_data_tag 3 +#define wpi_proto_ProtobufVector_rows_tag 1 + +/* Struct field encoding specification for nanopb */ +#define wpi_proto_ProtobufMatrix_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, UINT32, num_rows, 1) \ +X(a, STATIC, SINGULAR, UINT32, num_cols, 2) \ +X(a, CALLBACK, REPEATED, DOUBLE, data, 3) +#define wpi_proto_ProtobufMatrix_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufMatrix_DEFAULT NULL + +#define wpi_proto_ProtobufVector_FIELDLIST(X, a) \ +X(a, CALLBACK, REPEATED, DOUBLE, rows, 1) +#define wpi_proto_ProtobufVector_CALLBACK pb_default_field_callback +#define wpi_proto_ProtobufVector_DEFAULT NULL + +/* Maximum encoded size of messages (where known) */ +/* wpi_proto_ProtobufMatrix_size depends on runtime parameters */ +/* wpi_proto_ProtobufVector_size depends on runtime parameters */ + + +#endif diff --git a/wpimath/src/main/native/cpp/controller/proto/ArmFeedforwardProto.cpp b/wpimath/src/main/native/cpp/controller/proto/ArmFeedforwardProto.cpp index 39c3ab8693..2468571876 100644 --- a/wpimath/src/main/native/cpp/controller/proto/ArmFeedforwardProto.cpp +++ b/wpimath/src/main/native/cpp/controller/proto/ArmFeedforwardProto.cpp @@ -4,31 +4,33 @@ #include "frc/controller/proto/ArmFeedforwardProto.h" -#include +#include -#include "controller.pb.h" +#include "wpimath/protobuf/controller.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi_proto_ProtobufArmFeedforward msg; + if (!stream.Decode(msg)) { + return {}; + } -frc::ArmFeedforward wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::ArmFeedforward{ - units::volt_t{m->ks()}, - units::volt_t{m->kg()}, - units::unit_t{m->kv()}, - units::unit_t{m->ka()}, + units::volt_t{msg.ks}, + units::volt_t{msg.kg}, + units::unit_t{msg.kv}, + units::unit_t{msg.ka}, }; } -void wpi::Protobuf::Pack( - google::protobuf::Message* msg, const frc::ArmFeedforward& value) { - auto m = static_cast(msg); - m->set_ks(value.GetKs().value()); - m->set_kg(value.GetKg().value()); - m->set_kv(value.GetKv().value()); - m->set_ka(value.GetKa().value()); +bool wpi::Protobuf::Pack( + OutputStream& stream, const frc::ArmFeedforward& value) { + wpi_proto_ProtobufArmFeedforward msg{ + .ks = value.GetKs().value(), + .kg = value.GetKg().value(), + .kv = value.GetKv().value(), + .ka = value.GetKa().value(), + .dt = 0, + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveFeedforwardProto.cpp b/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveFeedforwardProto.cpp index 4a5876d93a..40a39c0e81 100644 --- a/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveFeedforwardProto.cpp +++ b/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveFeedforwardProto.cpp @@ -4,33 +4,30 @@ #include "frc/controller/proto/DifferentialDriveFeedforwardProto.h" -#include +#include "wpimath/protobuf/controller.npb.h" -#include "controller.pb.h" +std::optional +wpi::Protobuf::Unpack(InputStream& stream) { + wpi_proto_ProtobufDifferentialDriveFeedforward msg; + if (!stream.Decode(msg)) { + return {}; + } -google::protobuf::Message* wpi::Protobuf< - frc::DifferentialDriveFeedforward>::New(google::protobuf::Arena* arena) { - return wpi::CreateMessage( - arena); + return frc::DifferentialDriveFeedforward{ + decltype(1_V / 1_mps){msg.kv_linear}, + decltype(1_V / 1_mps_sq){msg.ka_linear}, + decltype(1_V / 1_mps){msg.kv_angular}, + decltype(1_V / 1_mps_sq){msg.ka_angular}, + }; } -frc::DifferentialDriveFeedforward -wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast( - &msg); - return {decltype(1_V / 1_mps){m->kv_linear()}, - decltype(1_V / 1_mps_sq){m->ka_linear()}, - decltype(1_V / 1_mps){m->kv_angular()}, - decltype(1_V / 1_mps_sq){m->ka_angular()}}; -} - -void wpi::Protobuf::Pack( - google::protobuf::Message* msg, - const frc::DifferentialDriveFeedforward& value) { - auto m = static_cast(msg); - m->set_kv_linear(value.m_kVLinear.value()); - m->set_ka_linear(value.m_kALinear.value()); - m->set_kv_angular(value.m_kVAngular.value()); - m->set_ka_angular(value.m_kAAngular.value()); +bool wpi::Protobuf::Pack( + OutputStream& stream, const frc::DifferentialDriveFeedforward& value) { + wpi_proto_ProtobufDifferentialDriveFeedforward msg{ + .kv_linear = value.m_kVLinear.value(), + .ka_linear = value.m_kALinear.value(), + .kv_angular = value.m_kVAngular.value(), + .ka_angular = value.m_kAAngular.value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProto.cpp b/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProto.cpp index 523e67798d..eebe9654a9 100644 --- a/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProto.cpp +++ b/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProto.cpp @@ -4,33 +4,28 @@ #include "frc/controller/proto/DifferentialDriveWheelVoltagesProto.h" -#include +#include -#include "controller.pb.h" +#include "wpimath/protobuf/controller.npb.h" -google::protobuf::Message* wpi::Protobuf< - frc::DifferentialDriveWheelVoltages>::New(google::protobuf::Arena* arena) { - return wpi::CreateMessage( - arena); -} +std::optional wpi::Protobuf< + frc::DifferentialDriveWheelVoltages>::Unpack(InputStream& stream) { + wpi_proto_ProtobufDifferentialDriveWheelVoltages msg; + if (!stream.Decode(msg)) { + return {}; + } -frc::DifferentialDriveWheelVoltages -wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = - static_cast( - &msg); return frc::DifferentialDriveWheelVoltages{ - units::volt_t{m->left()}, - units::volt_t{m->right()}, + units::volt_t{msg.left}, + units::volt_t{msg.right}, }; } -void wpi::Protobuf::Pack( - google::protobuf::Message* msg, - const frc::DifferentialDriveWheelVoltages& value) { - auto m = - static_cast(msg); - m->set_left(value.left.value()); - m->set_right(value.right.value()); +bool wpi::Protobuf::Pack( + OutputStream& stream, const frc::DifferentialDriveWheelVoltages& value) { + wpi_proto_ProtobufDifferentialDriveWheelVoltages msg{ + .left = value.left.value(), + .right = value.right.value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/controller/proto/ElevatorFeedforwardProto.cpp b/wpimath/src/main/native/cpp/controller/proto/ElevatorFeedforwardProto.cpp index 1eb8c3d0f7..d96f7fee98 100644 --- a/wpimath/src/main/native/cpp/controller/proto/ElevatorFeedforwardProto.cpp +++ b/wpimath/src/main/native/cpp/controller/proto/ElevatorFeedforwardProto.cpp @@ -4,31 +4,33 @@ #include "frc/controller/proto/ElevatorFeedforwardProto.h" -#include +#include -#include "controller.pb.h" +#include "wpimath/protobuf/controller.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +std::optional +wpi::Protobuf::Unpack(InputStream& stream) { + wpi_proto_ProtobufElevatorFeedforward msg; + if (!stream.Decode(msg)) { + return {}; + } -frc::ElevatorFeedforward wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::ElevatorFeedforward{ - units::volt_t{m->ks()}, - units::volt_t{m->kg()}, - units::unit_t{m->kv()}, - units::unit_t{m->ka()}, + units::volt_t{msg.ks}, + units::volt_t{msg.kg}, + units::unit_t{msg.kv}, + units::unit_t{msg.ka}, }; } -void wpi::Protobuf::Pack( - google::protobuf::Message* msg, const frc::ElevatorFeedforward& value) { - auto m = static_cast(msg); - m->set_ks(value.GetKs().value()); - m->set_kg(value.GetKg().value()); - m->set_kv(value.GetKv().value()); - m->set_ka(value.GetKa().value()); +bool wpi::Protobuf::Pack( + OutputStream& stream, const frc::ElevatorFeedforward& value) { + wpi_proto_ProtobufElevatorFeedforward msg{ + .ks = value.GetKs().value(), + .kg = value.GetKg().value(), + .kv = value.GetKv().value(), + .ka = value.GetKa().value(), + .dt = 0, + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/geometry/proto/Ellipse2dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Ellipse2dProto.cpp index e8bd59f70b..348bcae9ee 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Ellipse2dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Ellipse2dProto.cpp @@ -4,29 +4,42 @@ #include "frc/geometry/proto/Ellipse2dProto.h" -#include +#include -#include "geometry2d.pb.h" +#include "wpimath/protobuf/geometry2d.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi::UnpackCallback pose; + wpi_proto_ProtobufEllipse2d msg{ + .center = pose.Callback(), + .xSemiAxis = 0, + .ySemiAxis = 0, + }; + if (!stream.Decode(msg)) { + return {}; + } + + auto ipose = pose.Items(); + + if (ipose.empty()) { + return {}; + } -frc::Ellipse2d wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::Ellipse2d{ - wpi::UnpackProtobuf(m->wpi_center()), - units::meter_t{m->xsemiaxis()}, - units::meter_t{m->ysemiaxis()}, + ipose[0], + units::meter_t{msg.xSemiAxis}, + units::meter_t{msg.ySemiAxis}, }; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::Ellipse2d& value) { - auto m = static_cast(msg); - wpi::PackProtobuf(m->mutable_center(), value.Center()); - m->set_xsemiaxis(value.XSemiAxis().value()); - m->set_ysemiaxis(value.YSemiAxis().value()); + wpi::PackCallback pose{&value.Center()}; + wpi_proto_ProtobufEllipse2d msg{ + .center = pose.Callback(), + .xSemiAxis = value.XSemiAxis().value(), + .ySemiAxis = value.YSemiAxis().value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/geometry/proto/Pose2dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Pose2dProto.cpp index 3e9a2342f4..221b25f99d 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Pose2dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Pose2dProto.cpp @@ -4,27 +4,42 @@ #include "frc/geometry/proto/Pose2dProto.h" -#include +#include -#include "geometry2d.pb.h" +#include "wpimath/protobuf/geometry2d.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi::UnpackCallback tsln; + wpi::UnpackCallback rot; + wpi_proto_ProtobufPose2d msg{ + .translation = tsln.Callback(), + .rotation = rot.Callback(), + }; + if (!stream.Decode(msg)) { + return {}; + } + + auto itsln = tsln.Items(); + auto irot = rot.Items(); + + if (itsln.empty() || irot.empty()) { + return {}; + } -frc::Pose2d wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::Pose2d{ - wpi::UnpackProtobuf(m->wpi_translation()), - wpi::UnpackProtobuf(m->wpi_rotation()), + itsln[0], + irot[0], }; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::Pose2d& value) { - auto m = static_cast(msg); - wpi::PackProtobuf(m->mutable_translation(), value.Translation()); - wpi::PackProtobuf(m->mutable_rotation(), value.Rotation()); + wpi::PackCallback tsln{&value.Translation()}; + wpi::PackCallback rot{&value.Rotation()}; + wpi_proto_ProtobufPose2d msg{ + .translation = tsln.Callback(), + .rotation = rot.Callback(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/geometry/proto/Pose3dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Pose3dProto.cpp index 763f5146c0..e03936773d 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Pose3dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Pose3dProto.cpp @@ -4,27 +4,44 @@ #include "frc/geometry/proto/Pose3dProto.h" -#include +#include +#include -#include "geometry3d.pb.h" +#include "frc/geometry/Pose3d.h" +#include "wpimath/protobuf/geometry3d.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi::UnpackCallback tsln; + wpi::UnpackCallback rot; + wpi_proto_ProtobufPose3d msg{ + .translation = tsln.Callback(), + .rotation = rot.Callback(), + }; + if (!stream.Decode(msg)) { + return {}; + } + + auto itsln = tsln.Items(); + auto irot = rot.Items(); + + if (itsln.empty() || irot.empty()) { + return {}; + } -frc::Pose3d wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::Pose3d{ - wpi::UnpackProtobuf(m->wpi_translation()), - wpi::UnpackProtobuf(m->wpi_rotation()), + itsln[0], + irot[0], }; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::Pose3d& value) { - auto m = static_cast(msg); - wpi::PackProtobuf(m->mutable_translation(), value.Translation()); - wpi::PackProtobuf(m->mutable_rotation(), value.Rotation()); + wpi::PackCallback tsln{&value.Translation()}; + wpi::PackCallback rot{&value.Rotation()}; + wpi_proto_ProtobufPose3d msg{ + .translation = tsln.Callback(), + .rotation = rot.Callback(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/geometry/proto/QuaternionProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/QuaternionProto.cpp index c979c88a9c..9b0922316a 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/QuaternionProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/QuaternionProto.cpp @@ -4,31 +4,30 @@ #include "frc/geometry/proto/QuaternionProto.h" -#include +#include "wpimath/protobuf/geometry3d.npb.h" -#include "geometry3d.pb.h" +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi_proto_ProtobufQuaternion msg; + if (!stream.Decode(msg)) { + return {}; + } -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} - -frc::Quaternion wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::Quaternion{ - m->w(), - m->x(), - m->y(), - m->z(), + msg.w, + msg.x, + msg.y, + msg.z, }; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::Quaternion& value) { - auto m = static_cast(msg); - m->set_w(value.W()); - m->set_x(value.X()); - m->set_y(value.Y()); - m->set_z(value.Z()); + wpi_proto_ProtobufQuaternion msg{ + .w = value.W(), + .x = value.X(), + .y = value.Y(), + .z = value.Z(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/geometry/proto/Rectangle2dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Rectangle2dProto.cpp index ac6e411ba5..deccccac69 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Rectangle2dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Rectangle2dProto.cpp @@ -4,29 +4,42 @@ #include "frc/geometry/proto/Rectangle2dProto.h" -#include +#include -#include "geometry2d.pb.h" +#include "wpimath/protobuf/geometry2d.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi::UnpackCallback pose; + wpi_proto_ProtobufRectangle2d msg{ + .center = pose.Callback(), + .xWidth = 0, + .yWidth = 0, + }; + if (!stream.Decode(msg)) { + return {}; + } + + auto ipose = pose.Items(); + + if (ipose.empty()) { + return {}; + } -frc::Rectangle2d wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::Rectangle2d{ - wpi::UnpackProtobuf(m->wpi_center()), - units::meter_t{m->xwidth()}, - units::meter_t{m->ywidth()}, + ipose[0], + units::meter_t{msg.xWidth}, + units::meter_t{msg.yWidth}, }; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::Rectangle2d& value) { - auto m = static_cast(msg); - wpi::PackProtobuf(m->mutable_center(), value.Center()); - m->set_xwidth(value.XWidth().value()); - m->set_ywidth(value.YWidth().value()); + wpi::PackCallback pose{&value.Center()}; + wpi_proto_ProtobufRectangle2d msg{ + .center = pose.Callback(), + .xWidth = value.XWidth().value(), + .yWidth = value.YWidth().value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/geometry/proto/Rotation2dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Rotation2dProto.cpp index da44ab8137..34f2e933d8 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Rotation2dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Rotation2dProto.cpp @@ -4,25 +4,24 @@ #include "frc/geometry/proto/Rotation2dProto.h" -#include +#include "wpimath/protobuf/geometry2d.npb.h" -#include "geometry2d.pb.h" +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi_proto_ProtobufRotation2d msg; + if (!stream.Decode(msg)) { + return {}; + } -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} - -frc::Rotation2d wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::Rotation2d{ - units::radian_t{m->value()}, + units::radian_t{msg.value}, }; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::Rotation2d& value) { - auto m = static_cast(msg); - m->set_value(value.Radians().value()); + wpi_proto_ProtobufRotation2d msg{ + .value = value.Radians().value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/geometry/proto/Rotation3dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Rotation3dProto.cpp index 10583bfd75..86f30c9068 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Rotation3dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Rotation3dProto.cpp @@ -4,25 +4,36 @@ #include "frc/geometry/proto/Rotation3dProto.h" -#include +#include -#include "geometry3d.pb.h" +#include "wpimath/protobuf/geometry3d.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi::UnpackCallback quat; + wpi_proto_ProtobufRotation3d msg{ + .q = quat.Callback(), + }; + if (!stream.Decode(msg)) { + return {}; + } + + auto iquat = quat.Items(); + + if (iquat.empty()) { + return {}; + } -frc::Rotation3d wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::Rotation3d{ - wpi::UnpackProtobuf(m->wpi_q()), + iquat[0], }; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::Rotation3d& value) { - auto m = static_cast(msg); - wpi::PackProtobuf(m->mutable_q(), value.GetQuaternion()); + wpi::PackCallback quat{&value.GetQuaternion()}; + wpi_proto_ProtobufRotation3d msg{ + .q = quat.Callback(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/geometry/proto/Transform2dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Transform2dProto.cpp index a4a56d72d3..d12063829c 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Transform2dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Transform2dProto.cpp @@ -4,27 +4,42 @@ #include "frc/geometry/proto/Transform2dProto.h" -#include +#include -#include "geometry2d.pb.h" +#include "wpimath/protobuf/geometry2d.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi::UnpackCallback tsln; + wpi::UnpackCallback rot; + wpi_proto_ProtobufTransform2d msg{ + .translation = tsln.Callback(), + .rotation = rot.Callback(), + }; + if (!stream.Decode(msg)) { + return {}; + } + + auto itsln = tsln.Items(); + auto irot = rot.Items(); + + if (itsln.empty() || irot.empty()) { + return {}; + } -frc::Transform2d wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::Transform2d{ - wpi::UnpackProtobuf(m->wpi_translation()), - wpi::UnpackProtobuf(m->wpi_rotation()), + itsln[0], + irot[0], }; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::Transform2d& value) { - auto m = static_cast(msg); - wpi::PackProtobuf(m->mutable_translation(), value.Translation()); - wpi::PackProtobuf(m->mutable_rotation(), value.Rotation()); + wpi::PackCallback tsln{&value.Translation()}; + wpi::PackCallback rot{&value.Rotation()}; + wpi_proto_ProtobufTransform2d msg{ + .translation = tsln.Callback(), + .rotation = rot.Callback(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/geometry/proto/Transform3dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Transform3dProto.cpp index c7c4bb2bc6..9c8a76a731 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Transform3dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Transform3dProto.cpp @@ -4,27 +4,42 @@ #include "frc/geometry/proto/Transform3dProto.h" -#include +#include -#include "geometry3d.pb.h" +#include "wpimath/protobuf/geometry3d.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi::UnpackCallback tsln; + wpi::UnpackCallback rot; + wpi_proto_ProtobufTransform3d msg{ + .translation = tsln.Callback(), + .rotation = rot.Callback(), + }; + if (!stream.Decode(msg)) { + return {}; + } + + auto itsln = tsln.Items(); + auto irot = rot.Items(); + + if (itsln.empty() || irot.empty()) { + return {}; + } -frc::Transform3d wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::Transform3d{ - wpi::UnpackProtobuf(m->wpi_translation()), - wpi::UnpackProtobuf(m->wpi_rotation()), + itsln[0], + irot[0], }; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::Transform3d& value) { - auto m = static_cast(msg); - wpi::PackProtobuf(m->mutable_translation(), value.Translation()); - wpi::PackProtobuf(m->mutable_rotation(), value.Rotation()); + wpi::PackCallback tsln{&value.Translation()}; + wpi::PackCallback rot{&value.Rotation()}; + wpi_proto_ProtobufTransform3d msg{ + .translation = tsln.Callback(), + .rotation = rot.Callback(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/geometry/proto/Translation2dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Translation2dProto.cpp index 47d7efa925..e1af88e988 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Translation2dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Translation2dProto.cpp @@ -4,27 +4,26 @@ #include "frc/geometry/proto/Translation2dProto.h" -#include +#include "wpimath/protobuf/geometry2d.npb.h" -#include "geometry2d.pb.h" +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi_proto_ProtobufTranslation2d msg; + if (!stream.Decode(msg)) { + return {}; + } -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} - -frc::Translation2d wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::Translation2d{ - units::meter_t{m->x()}, - units::meter_t{m->y()}, + units::meter_t{msg.x}, + units::meter_t{msg.y}, }; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::Translation2d& value) { - auto m = static_cast(msg); - m->set_x(value.X().value()); - m->set_y(value.Y().value()); + wpi_proto_ProtobufTranslation2d msg{ + .x = value.X().value(), + .y = value.Y().value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/geometry/proto/Translation3dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Translation3dProto.cpp index 1ae55ee1ee..d58d700ef4 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Translation3dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Translation3dProto.cpp @@ -4,29 +4,28 @@ #include "frc/geometry/proto/Translation3dProto.h" -#include +#include "wpimath/protobuf/geometry3d.npb.h" -#include "geometry3d.pb.h" +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi_proto_ProtobufTranslation3d msg; + if (!stream.Decode(msg)) { + return {}; + } -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} - -frc::Translation3d wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::Translation3d{ - units::meter_t{m->x()}, - units::meter_t{m->y()}, - units::meter_t{m->z()}, + units::meter_t{msg.x}, + units::meter_t{msg.y}, + units::meter_t{msg.z}, }; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::Translation3d& value) { - auto m = static_cast(msg); - m->set_x(value.X().value()); - m->set_y(value.Y().value()); - m->set_z(value.Z().value()); + wpi_proto_ProtobufTranslation3d msg{ + .x = value.X().value(), + .y = value.Y().value(), + .z = value.Z().value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/geometry/proto/Twist2dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Twist2dProto.cpp index 76ece7f001..f38868c262 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Twist2dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Twist2dProto.cpp @@ -4,29 +4,28 @@ #include "frc/geometry/proto/Twist2dProto.h" -#include +#include "wpimath/protobuf/geometry2d.npb.h" -#include "geometry2d.pb.h" +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi_proto_ProtobufTwist2d msg; + if (!stream.Decode(msg)) { + return {}; + } -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} - -frc::Twist2d wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::Twist2d{ - units::meter_t{m->dx()}, - units::meter_t{m->dy()}, - units::radian_t{m->dtheta()}, + units::meter_t{msg.dx}, + units::meter_t{msg.dy}, + units::radian_t{msg.dtheta}, }; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::Twist2d& value) { - auto m = static_cast(msg); - m->set_dx(value.dx.value()); - m->set_dy(value.dy.value()); - m->set_dtheta(value.dtheta.value()); + wpi_proto_ProtobufTwist2d msg{ + .dx = value.dx.value(), + .dy = value.dy.value(), + .dtheta = value.dtheta.value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/geometry/proto/Twist3dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Twist3dProto.cpp index d89eb9cb7c..315c37ff4f 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Twist3dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Twist3dProto.cpp @@ -4,32 +4,30 @@ #include "frc/geometry/proto/Twist3dProto.h" -#include +#include "wpimath/protobuf/geometry3d.npb.h" -#include "geometry3d.pb.h" +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi_proto_ProtobufTwist3d msg; + if (!stream.Decode(msg)) { + return {}; + } -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} - -frc::Twist3d wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::Twist3d{ - units::meter_t{m->dx()}, units::meter_t{m->dy()}, - units::meter_t{m->dz()}, units::radian_t{m->rx()}, - units::radian_t{m->ry()}, units::radian_t{m->rz()}, + units::meter_t{msg.dx}, units::meter_t{msg.dy}, units::meter_t{msg.dz}, + units::radian_t{msg.rx}, units::radian_t{msg.ry}, units::radian_t{msg.rz}, }; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::Twist3d& value) { - auto m = static_cast(msg); - m->set_dx(value.dx.value()); - m->set_dy(value.dy.value()); - m->set_dz(value.dz.value()); - m->set_rx(value.rx.value()); - m->set_ry(value.ry.value()); - m->set_rz(value.rz.value()); + wpi_proto_ProtobufTwist3d msg{ + .dx = value.dx.value(), + .dy = value.dy.value(), + .dz = value.dz.value(), + .rx = value.rx.value(), + .ry = value.ry.value(), + .rz = value.rz.value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/kinematics/proto/ChassisSpeedsProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/ChassisSpeedsProto.cpp index fc22f38bd0..be8f3eeb10 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/ChassisSpeedsProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/ChassisSpeedsProto.cpp @@ -4,29 +4,28 @@ #include "frc/kinematics/proto/ChassisSpeedsProto.h" -#include +#include "wpimath/protobuf/kinematics.npb.h" -#include "kinematics.pb.h" +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi_proto_ProtobufChassisSpeeds msg; + if (!stream.Decode(msg)) { + return {}; + } -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} - -frc::ChassisSpeeds wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::ChassisSpeeds{ - units::meters_per_second_t{m->vx()}, - units::meters_per_second_t{m->vy()}, - units::radians_per_second_t{m->omega()}, + units::meters_per_second_t{msg.vx}, + units::meters_per_second_t{msg.vy}, + units::radians_per_second_t{msg.omega}, }; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::ChassisSpeeds& value) { - auto m = static_cast(msg); - m->set_vx(value.vx.value()); - m->set_vy(value.vy.value()); - m->set_omega(value.omega.value()); + wpi_proto_ProtobufChassisSpeeds msg{ + .vx = value.vx.value(), + .vy = value.vy.value(), + .omega = value.omega.value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveKinematicsProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveKinematicsProto.cpp index 5ab51f71df..5ca8372796 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveKinematicsProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveKinematicsProto.cpp @@ -4,29 +4,24 @@ #include "frc/kinematics/proto/DifferentialDriveKinematicsProto.h" -#include +#include "wpimath/protobuf/kinematics.npb.h" -#include "kinematics.pb.h" +std::optional +wpi::Protobuf::Unpack(InputStream& stream) { + wpi_proto_ProtobufDifferentialDriveKinematics msg; + if (!stream.Decode(msg)) { + return {}; + } -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage( - arena); -} - -frc::DifferentialDriveKinematics -wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = - static_cast(&msg); return frc::DifferentialDriveKinematics{ - units::meter_t{m->track_width()}, + units::meter_t{msg.track_width}, }; } -void wpi::Protobuf::Pack( - google::protobuf::Message* msg, - const frc::DifferentialDriveKinematics& value) { - auto m = static_cast(msg); - m->set_track_width(value.trackWidth.value()); +bool wpi::Protobuf::Pack( + OutputStream& stream, const frc::DifferentialDriveKinematics& value) { + wpi_proto_ProtobufDifferentialDriveKinematics msg{ + .track_width = value.trackWidth.value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelPositionsProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelPositionsProto.cpp index 0303855297..2dbf9eeca9 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelPositionsProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelPositionsProto.cpp @@ -4,33 +4,26 @@ #include "frc/kinematics/proto/DifferentialDriveWheelPositionsProto.h" -#include +#include "wpimath/protobuf/kinematics.npb.h" -#include "kinematics.pb.h" +std::optional wpi::Protobuf< + frc::DifferentialDriveWheelPositions>::Unpack(InputStream& stream) { + wpi_proto_ProtobufDifferentialDriveWheelPositions msg; + if (!stream.Decode(msg)) { + return {}; + } -google::protobuf::Message* wpi::Protobuf< - frc::DifferentialDriveWheelPositions>::New(google::protobuf::Arena* arena) { - return wpi::CreateMessage< - wpi::proto::ProtobufDifferentialDriveWheelPositions>(arena); -} - -frc::DifferentialDriveWheelPositions -wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = - static_cast( - &msg); return frc::DifferentialDriveWheelPositions{ - units::meter_t{m->left()}, - units::meter_t{m->right()}, + units::meter_t{msg.left}, + units::meter_t{msg.right}, }; } -void wpi::Protobuf::Pack( - google::protobuf::Message* msg, - const frc::DifferentialDriveWheelPositions& value) { - auto m = - static_cast(msg); - m->set_left(value.left.value()); - m->set_right(value.right.value()); +bool wpi::Protobuf::Pack( + OutputStream& stream, const frc::DifferentialDriveWheelPositions& value) { + wpi_proto_ProtobufDifferentialDriveWheelPositions msg{ + .left = value.left.value(), + .right = value.right.value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProto.cpp index 97a5e71531..f47626676d 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProto.cpp @@ -4,31 +4,26 @@ #include "frc/kinematics/proto/DifferentialDriveWheelSpeedsProto.h" -#include +#include "wpimath/protobuf/kinematics.npb.h" -#include "kinematics.pb.h" +std::optional +wpi::Protobuf::Unpack(InputStream& stream) { + wpi_proto_ProtobufDifferentialDriveWheelSpeeds msg; + if (!stream.Decode(msg)) { + return {}; + } -google::protobuf::Message* wpi::Protobuf< - frc::DifferentialDriveWheelSpeeds>::New(google::protobuf::Arena* arena) { - return wpi::CreateMessage( - arena); -} - -frc::DifferentialDriveWheelSpeeds -wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast( - &msg); return frc::DifferentialDriveWheelSpeeds{ - units::meters_per_second_t{m->left()}, - units::meters_per_second_t{m->right()}, + units::meters_per_second_t{msg.left}, + units::meters_per_second_t{msg.right}, }; } -void wpi::Protobuf::Pack( - google::protobuf::Message* msg, - const frc::DifferentialDriveWheelSpeeds& value) { - auto m = static_cast(msg); - m->set_left(value.left.value()); - m->set_right(value.right.value()); +bool wpi::Protobuf::Pack( + OutputStream& stream, const frc::DifferentialDriveWheelSpeeds& value) { + wpi_proto_ProtobufDifferentialDriveWheelSpeeds msg{ + .left = value.left.value(), + .right = value.right.value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveKinematicsProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveKinematicsProto.cpp index 3aecee684b..412c7c92db 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveKinematicsProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveKinematicsProto.cpp @@ -4,31 +4,55 @@ #include "frc/kinematics/proto/MecanumDriveKinematicsProto.h" -#include +#include -#include "kinematics.pb.h" +#include "wpimath/protobuf/kinematics.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +std::optional +wpi::Protobuf::Unpack(InputStream& stream) { + wpi::UnpackCallback frontLeft; + wpi::UnpackCallback frontRight; + wpi::UnpackCallback rearLeft; + wpi::UnpackCallback rearRight; + wpi_proto_ProtobufMecanumDriveKinematics msg{ + .front_left = frontLeft.Callback(), + .front_right = frontRight.Callback(), + .rear_left = rearLeft.Callback(), + .rear_right = rearRight.Callback(), + }; + if (!stream.Decode(msg)) { + return {}; + } + + auto ifrontLeft = frontLeft.Items(); + auto ifrontRight = frontRight.Items(); + auto irearLeft = rearLeft.Items(); + auto irearRight = rearRight.Items(); + + if (ifrontLeft.empty() || ifrontRight.empty() || irearLeft.empty() || + irearRight.empty()) { + return {}; + } -frc::MecanumDriveKinematics wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::MecanumDriveKinematics{ - wpi::UnpackProtobuf(m->wpi_front_left()), - wpi::UnpackProtobuf(m->wpi_front_right()), - wpi::UnpackProtobuf(m->wpi_rear_left()), - wpi::UnpackProtobuf(m->wpi_rear_right()), + ifrontLeft[0], + ifrontRight[0], + irearLeft[0], + irearRight[0], }; } -void wpi::Protobuf::Pack( - google::protobuf::Message* msg, const frc::MecanumDriveKinematics& value) { - auto m = static_cast(msg); - wpi::PackProtobuf(m->mutable_front_left(), value.GetFrontLeft()); - wpi::PackProtobuf(m->mutable_front_right(), value.GetFrontRight()); - wpi::PackProtobuf(m->mutable_rear_left(), value.GetRearLeft()); - wpi::PackProtobuf(m->mutable_rear_right(), value.GetRearRight()); +bool wpi::Protobuf::Pack( + OutputStream& stream, const frc::MecanumDriveKinematics& value) { + wpi::PackCallback frontLeft{&value.GetFrontLeft()}; + wpi::PackCallback frontRight{&value.GetFrontRight()}; + wpi::PackCallback rearLeft{&value.GetRearLeft()}; + wpi::PackCallback rearRight{&value.GetRearRight()}; + wpi_proto_ProtobufMecanumDriveKinematics msg{ + .front_left = frontLeft.Callback(), + .front_right = frontRight.Callback(), + .rear_left = rearLeft.Callback(), + .rear_right = rearRight.Callback(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProto.cpp index 11233d6393..dad3dd4305 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProto.cpp @@ -4,35 +4,30 @@ #include "frc/kinematics/proto/MecanumDriveWheelPositionsProto.h" -#include +#include "wpimath/protobuf/kinematics.npb.h" -#include "kinematics.pb.h" +std::optional +wpi::Protobuf::Unpack(InputStream& stream) { + wpi_proto_ProtobufMecanumDriveWheelPositions msg; + if (!stream.Decode(msg)) { + return {}; + } -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage( - arena); -} - -frc::MecanumDriveWheelPositions -wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = - static_cast(&msg); return frc::MecanumDriveWheelPositions{ - units::meter_t{m->front_left()}, - units::meter_t{m->front_right()}, - units::meter_t{m->rear_left()}, - units::meter_t{m->rear_right()}, + units::meter_t{msg.front_left}, + units::meter_t{msg.front_right}, + units::meter_t{msg.rear_left}, + units::meter_t{msg.rear_right}, }; } -void wpi::Protobuf::Pack( - google::protobuf::Message* msg, - const frc::MecanumDriveWheelPositions& value) { - auto m = static_cast(msg); - m->set_front_left(value.frontLeft.value()); - m->set_front_right(value.frontRight.value()); - m->set_rear_left(value.rearLeft.value()); - m->set_rear_right(value.rearRight.value()); +bool wpi::Protobuf::Pack( + OutputStream& stream, const frc::MecanumDriveWheelPositions& value) { + wpi_proto_ProtobufMecanumDriveWheelPositions msg{ + .front_left = value.frontLeft.value(), + .front_right = value.frontRight.value(), + .rear_left = value.rearLeft.value(), + .rear_right = value.rearRight.value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProto.cpp index 5e9921bd47..fa4d50a1cd 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProto.cpp @@ -4,33 +4,30 @@ #include "frc/kinematics/proto/MecanumDriveWheelSpeedsProto.h" -#include +#include "wpimath/protobuf/kinematics.npb.h" -#include "kinematics.pb.h" +std::optional +wpi::Protobuf::Unpack(InputStream& stream) { + wpi_proto_ProtobufMecanumDriveWheelSpeeds msg; + if (!stream.Decode(msg)) { + return {}; + } -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} - -frc::MecanumDriveWheelSpeeds -wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = - static_cast(&msg); return frc::MecanumDriveWheelSpeeds{ - units::meters_per_second_t{m->front_left()}, - units::meters_per_second_t{m->front_right()}, - units::meters_per_second_t{m->rear_left()}, - units::meters_per_second_t{m->rear_right()}, + units::meters_per_second_t{msg.front_left}, + units::meters_per_second_t{msg.front_right}, + units::meters_per_second_t{msg.rear_left}, + units::meters_per_second_t{msg.rear_right}, }; } -void wpi::Protobuf::Pack( - google::protobuf::Message* msg, const frc::MecanumDriveWheelSpeeds& value) { - auto m = static_cast(msg); - m->set_front_left(value.frontLeft.value()); - m->set_front_right(value.frontRight.value()); - m->set_rear_left(value.rearLeft.value()); - m->set_rear_right(value.rearRight.value()); +bool wpi::Protobuf::Pack( + OutputStream& stream, const frc::MecanumDriveWheelSpeeds& value) { + wpi_proto_ProtobufMecanumDriveWheelSpeeds msg{ + .front_left = value.frontLeft.value(), + .front_right = value.frontRight.value(), + .rear_left = value.rearLeft.value(), + .rear_right = value.rearRight.value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/kinematics/proto/SwerveModulePositionProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/SwerveModulePositionProto.cpp index 7c823ad37e..262154b0be 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/SwerveModulePositionProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/SwerveModulePositionProto.cpp @@ -4,27 +4,39 @@ #include "frc/kinematics/proto/SwerveModulePositionProto.h" -#include +#include -#include "kinematics.pb.h" +#include "wpimath/protobuf/kinematics.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +std::optional +wpi::Protobuf::Unpack(InputStream& stream) { + wpi::UnpackCallback angle; + wpi_proto_ProtobufSwerveModulePosition msg{ + .distance = 0, + .angle = angle.Callback(), + }; + if (!stream.Decode(msg)) { + return {}; + } + + auto iangle = angle.Items(); + + if (iangle.empty()) { + return {}; + } -frc::SwerveModulePosition wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::SwerveModulePosition{ - units::meter_t{m->distance()}, - wpi::UnpackProtobuf(m->wpi_angle()), + units::meter_t{msg.distance}, + iangle[0], }; } -void wpi::Protobuf::Pack( - google::protobuf::Message* msg, const frc::SwerveModulePosition& value) { - auto m = static_cast(msg); - m->set_distance(value.distance.value()); - wpi::PackProtobuf(m->mutable_angle(), value.angle); +bool wpi::Protobuf::Pack( + OutputStream& stream, const frc::SwerveModulePosition& value) { + wpi::PackCallback angle{&value.angle}; + wpi_proto_ProtobufSwerveModulePosition msg{ + .distance = value.distance.value(), + .angle = angle.Callback(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/kinematics/proto/SwerveModuleStateProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/SwerveModuleStateProto.cpp index 0950ec3ecd..7f3215cca2 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/SwerveModuleStateProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/SwerveModuleStateProto.cpp @@ -4,27 +4,39 @@ #include "frc/kinematics/proto/SwerveModuleStateProto.h" -#include +#include -#include "kinematics.pb.h" +#include "wpimath/protobuf/kinematics.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +std::optional +wpi::Protobuf::Unpack(InputStream& stream) { + wpi::UnpackCallback angle; + wpi_proto_ProtobufSwerveModuleState msg{ + .speed = 0, + .angle = angle.Callback(), + }; + if (!stream.Decode(msg)) { + return {}; + } + + auto iangle = angle.Items(); + + if (iangle.empty()) { + return {}; + } -frc::SwerveModuleState wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::SwerveModuleState{ - units::meters_per_second_t{m->speed()}, - wpi::UnpackProtobuf(m->wpi_angle()), + units::meters_per_second_t{msg.speed}, + iangle[0], }; } -void wpi::Protobuf::Pack( - google::protobuf::Message* msg, const frc::SwerveModuleState& value) { - auto m = static_cast(msg); - m->set_speed(value.speed.value()); - wpi::PackProtobuf(m->mutable_angle(), value.angle); +bool wpi::Protobuf::Pack( + OutputStream& stream, const frc::SwerveModuleState& value) { + wpi::PackCallback angle{&value.angle}; + wpi_proto_ProtobufSwerveModuleState msg{ + .speed = value.speed.value(), + .angle = angle.Callback(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/spline/proto/CubicHermiteSplineProto.cpp b/wpimath/src/main/native/cpp/spline/proto/CubicHermiteSplineProto.cpp index 6189d4458c..0ce5da8c18 100644 --- a/wpimath/src/main/native/cpp/spline/proto/CubicHermiteSplineProto.cpp +++ b/wpimath/src/main/native/cpp/spline/proto/CubicHermiteSplineProto.cpp @@ -4,32 +4,50 @@ #include "frc/spline/proto/CubicHermiteSplineProto.h" -#include +#include -#include "spline.pb.h" +#include "wpimath/protobuf/spline.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +std::optional +wpi::Protobuf::Unpack(InputStream& stream) { + wpi::WpiArrayUnpackCallback xInitial; + wpi::WpiArrayUnpackCallback xFinal; + wpi::WpiArrayUnpackCallback yInitial; + wpi::WpiArrayUnpackCallback yFinal; + wpi_proto_ProtobufCubicHermiteSpline msg{ + .x_initial = xInitial.Callback(), + .x_final = xFinal.Callback(), + .y_initial = yInitial.Callback(), + .y_final = yFinal.Callback(), + }; + if (!stream.Decode(msg)) { + return {}; + } + + if (!xInitial.IsFull() || !yInitial.IsFull() || !xFinal.IsFull() || + !yFinal.IsFull()) { + return {}; + } -frc::CubicHermiteSpline wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::CubicHermiteSpline{ - wpi::UnpackProtobufArray(m->x_initial()), - wpi::UnpackProtobufArray(m->x_final()), - wpi::UnpackProtobufArray(m->y_initial()), - wpi::UnpackProtobufArray(m->y_final())}; + xInitial.Array(), + xFinal.Array(), + yInitial.Array(), + yFinal.Array(), + }; } -void wpi::Protobuf::Pack( - google::protobuf::Message* msg, const frc::CubicHermiteSpline& value) { - auto m = static_cast(msg); - wpi::PackProtobufArray(m->mutable_x_initial(), - value.GetInitialControlVector().x); - wpi::PackProtobufArray(m->mutable_x_final(), value.GetFinalControlVector().x); - wpi::PackProtobufArray(m->mutable_y_initial(), - value.GetInitialControlVector().y); - wpi::PackProtobufArray(m->mutable_y_final(), value.GetFinalControlVector().y); +bool wpi::Protobuf::Pack( + OutputStream& stream, const frc::CubicHermiteSpline& value) { + wpi::PackCallback xInitial{value.GetInitialControlVector().x}; + wpi::PackCallback xFinal{value.GetFinalControlVector().x}; + wpi::PackCallback yInitial{value.GetInitialControlVector().y}; + wpi::PackCallback yFinal{value.GetFinalControlVector().y}; + wpi_proto_ProtobufCubicHermiteSpline msg{ + .x_initial = xInitial.Callback(), + .x_final = xFinal.Callback(), + .y_initial = yInitial.Callback(), + .y_final = yFinal.Callback(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/spline/proto/QuinticHermiteSplineProto.cpp b/wpimath/src/main/native/cpp/spline/proto/QuinticHermiteSplineProto.cpp index c4d8ffc851..d3f888ae84 100644 --- a/wpimath/src/main/native/cpp/spline/proto/QuinticHermiteSplineProto.cpp +++ b/wpimath/src/main/native/cpp/spline/proto/QuinticHermiteSplineProto.cpp @@ -4,32 +4,50 @@ #include "frc/spline/proto/QuinticHermiteSplineProto.h" -#include +#include -#include "spline.pb.h" +#include "wpimath/protobuf/spline.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +std::optional +wpi::Protobuf::Unpack(InputStream& stream) { + wpi::WpiArrayUnpackCallback xInitial; + wpi::WpiArrayUnpackCallback xFinal; + wpi::WpiArrayUnpackCallback yInitial; + wpi::WpiArrayUnpackCallback yFinal; + wpi_proto_ProtobufQuinticHermiteSpline msg{ + .x_initial = xInitial.Callback(), + .x_final = xFinal.Callback(), + .y_initial = yInitial.Callback(), + .y_final = yFinal.Callback(), + }; + if (!stream.Decode(msg)) { + return {}; + } + + if (!xInitial.IsFull() || !yInitial.IsFull() || !xFinal.IsFull() || + !yFinal.IsFull()) { + return {}; + } -frc::QuinticHermiteSpline wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::QuinticHermiteSpline{ - wpi::UnpackProtobufArray(m->x_initial()), - wpi::UnpackProtobufArray(m->x_final()), - wpi::UnpackProtobufArray(m->y_initial()), - wpi::UnpackProtobufArray(m->y_final())}; + xInitial.Array(), + xFinal.Array(), + yInitial.Array(), + yFinal.Array(), + }; } -void wpi::Protobuf::Pack( - google::protobuf::Message* msg, const frc::QuinticHermiteSpline& value) { - auto m = static_cast(msg); - wpi::PackProtobufArray(m->mutable_x_initial(), - value.GetInitialControlVector().x); - wpi::PackProtobufArray(m->mutable_x_final(), value.GetFinalControlVector().x); - wpi::PackProtobufArray(m->mutable_y_initial(), - value.GetInitialControlVector().y); - wpi::PackProtobufArray(m->mutable_y_final(), value.GetFinalControlVector().y); +bool wpi::Protobuf::Pack( + OutputStream& stream, const frc::QuinticHermiteSpline& value) { + wpi::PackCallback xInitial{value.GetInitialControlVector().x}; + wpi::PackCallback xFinal{value.GetFinalControlVector().x}; + wpi::PackCallback yInitial{value.GetInitialControlVector().y}; + wpi::PackCallback yFinal{value.GetFinalControlVector().y}; + wpi_proto_ProtobufQuinticHermiteSpline msg{ + .x_initial = xInitial.Callback(), + .x_final = xFinal.Callback(), + .y_initial = yInitial.Callback(), + .y_final = yFinal.Callback(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/system/plant/proto/DCMotorProto.cpp b/wpimath/src/main/native/cpp/system/plant/proto/DCMotorProto.cpp index 81a21e98ff..ec639c5dfd 100644 --- a/wpimath/src/main/native/cpp/system/plant/proto/DCMotorProto.cpp +++ b/wpimath/src/main/native/cpp/system/plant/proto/DCMotorProto.cpp @@ -4,33 +4,34 @@ #include "frc/system/plant/proto/DCMotorProto.h" -#include +#include -#include "plant.pb.h" +#include "wpimath/protobuf/plant.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi_proto_ProtobufDCMotor msg; + if (!stream.Decode(msg)) { + return {}; + } -frc::DCMotor wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::DCMotor{ - units::volt_t{m->nominal_voltage()}, - units::newton_meter_t{m->stall_torque()}, - units::ampere_t{m->stall_current()}, - units::ampere_t{m->free_current()}, - units::radians_per_second_t{m->free_speed()}, + units::volt_t{msg.nominal_voltage}, + units::newton_meter_t{msg.stall_torque}, + units::ampere_t{msg.stall_current}, + units::ampere_t{msg.free_current}, + units::radians_per_second_t{msg.free_speed}, }; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::DCMotor& value) { - auto m = static_cast(msg); - m->set_nominal_voltage(value.nominalVoltage.value()); - m->set_stall_torque(value.stallTorque.value()); - m->set_stall_current(value.stallCurrent.value()); - m->set_free_current(value.freeCurrent.value()); - m->set_free_speed(value.freeSpeed.value()); + wpi_proto_ProtobufDCMotor msg{ + .nominal_voltage = value.nominalVoltage.value(), + .stall_torque = value.stallTorque.value(), + .stall_current = value.stallCurrent.value(), + .free_current = value.freeCurrent.value(), + .free_speed = value.freeSpeed.value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryProto.cpp b/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryProto.cpp index 3190719d59..0e1f1e1ecd 100644 --- a/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryProto.cpp +++ b/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryProto.cpp @@ -6,31 +6,28 @@ #include -#include +#include -#include "trajectory.pb.h" +#include "wpimath/protobuf/trajectory.npb.h" -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} - -frc::Trajectory wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); - std::vector states; - states.reserve(m->states().size()); - for (const auto& protoState : m->states()) { - states.push_back(wpi::UnpackProtobuf(protoState)); +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + wpi::StdVectorUnpackCallback states; + wpi_proto_ProtobufTrajectory msg{ + .states = states.Callback(), + }; + if (!stream.Decode(msg)) { + return {}; } - return frc::Trajectory{states}; + + return frc::Trajectory{states.Vec()}; } -void wpi::Protobuf::Pack(google::protobuf::Message* msg, +bool wpi::Protobuf::Pack(OutputStream& stream, const frc::Trajectory& value) { - auto m = static_cast(msg); - m->mutable_states()->Reserve(value.States().size()); - for (const auto& state : value.States()) { - wpi::PackProtobuf(m->add_states(), state); - } + wpi::PackCallback states{value.States()}; + wpi_proto_ProtobufTrajectory msg{ + .states = states.Callback(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryStateProto.cpp b/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryStateProto.cpp index 3d927de169..15af78ba12 100644 --- a/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryStateProto.cpp +++ b/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryStateProto.cpp @@ -4,33 +4,46 @@ #include "frc/trajectory/proto/TrajectoryStateProto.h" -#include +#include -#include "trajectory.pb.h" +#include -google::protobuf::Message* wpi::Protobuf::New( - google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); -} +#include "wpimath/protobuf/trajectory.npb.h" + +std::optional +wpi::Protobuf::Unpack(InputStream& stream) { + wpi::UnpackCallback pose; + wpi_proto_ProtobufTrajectoryState msg; + msg.pose = pose.Callback(); + + if (!stream.Decode(msg)) { + return {}; + } + + auto ipose = pose.Items(); + + if (ipose.empty()) { + return {}; + } -frc::Trajectory::State wpi::Protobuf::Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); return frc::Trajectory::State{ - units::second_t{m->time()}, - units::meters_per_second_t{m->velocity()}, - units::meters_per_second_squared_t{m->acceleration()}, - wpi::UnpackProtobuf(m->wpi_pose()), - units::curvature_t{m->curvature()}, + units::second_t{msg.time}, + units::meters_per_second_t{msg.velocity}, + units::meters_per_second_squared_t{msg.acceleration}, + std::move(ipose[0]), + units::curvature_t{msg.curvature}, }; } -void wpi::Protobuf::Pack( - google::protobuf::Message* msg, const frc::Trajectory::State& value) { - auto m = static_cast(msg); - m->set_time(value.t.value()); - m->set_velocity(value.velocity.value()); - m->set_acceleration(value.acceleration.value()); - wpi::PackProtobuf(m->mutable_pose(), value.pose); - m->set_curvature(value.curvature.value()); +bool wpi::Protobuf::Pack( + OutputStream& stream, const frc::Trajectory::State& value) { + wpi::PackCallback pose{&value.pose}; + wpi_proto_ProtobufTrajectoryState msg{ + .time = value.t.value(), + .velocity = value.velocity.value(), + .acceleration = value.acceleration.value(), + .pose = pose.Callback(), + .curvature = value.curvature.value(), + }; + return stream.Encode(msg); } diff --git a/wpimath/src/main/native/include/frc/controller/proto/ArmFeedforwardProto.h b/wpimath/src/main/native/include/frc/controller/proto/ArmFeedforwardProto.h index bc893aa8cb..7a91f61c75 100644 --- a/wpimath/src/main/native/include/frc/controller/proto/ArmFeedforwardProto.h +++ b/wpimath/src/main/native/include/frc/controller/proto/ArmFeedforwardProto.h @@ -8,11 +8,14 @@ #include #include "frc/controller/ArmFeedforward.h" +#include "pb.h" +#include "wpimath/protobuf/controller.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::ArmFeedforward Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, - const frc::ArmFeedforward& value); + using MessageStruct = wpi_proto_ProtobufArmFeedforward; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::ArmFeedforward& value); }; diff --git a/wpimath/src/main/native/include/frc/controller/proto/DifferentialDriveFeedforwardProto.h b/wpimath/src/main/native/include/frc/controller/proto/DifferentialDriveFeedforwardProto.h index 916e0d1432..d0d49e8fcf 100644 --- a/wpimath/src/main/native/include/frc/controller/proto/DifferentialDriveFeedforwardProto.h +++ b/wpimath/src/main/native/include/frc/controller/proto/DifferentialDriveFeedforwardProto.h @@ -8,12 +8,17 @@ #include #include "frc/controller/DifferentialDriveFeedforward.h" +#include "pb.h" +#include "wpimath/protobuf/controller.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::DifferentialDriveFeedforward Unpack( - const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, + using MessageStruct = wpi_proto_ProtobufDifferentialDriveFeedforward; + using InputStream = wpi::ProtoInputStream; + using OutputStream = + wpi::ProtoOutputStream; + static std::optional Unpack( + InputStream& stream); + static bool Pack(OutputStream& stream, const frc::DifferentialDriveFeedforward& value); }; diff --git a/wpimath/src/main/native/include/frc/controller/proto/DifferentialDriveWheelVoltagesProto.h b/wpimath/src/main/native/include/frc/controller/proto/DifferentialDriveWheelVoltagesProto.h index 486fd177d5..f3d306e43c 100644 --- a/wpimath/src/main/native/include/frc/controller/proto/DifferentialDriveWheelVoltagesProto.h +++ b/wpimath/src/main/native/include/frc/controller/proto/DifferentialDriveWheelVoltagesProto.h @@ -8,12 +8,18 @@ #include #include "frc/controller/DifferentialDriveWheelVoltages.h" +#include "pb.h" +#include "wpimath/protobuf/controller.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::DifferentialDriveWheelVoltages Unpack( - const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, + using MessageStruct = wpi_proto_ProtobufDifferentialDriveWheelVoltages; + using InputStream = + wpi::ProtoInputStream; + using OutputStream = + wpi::ProtoOutputStream; + static std::optional Unpack( + InputStream& stream); + static bool Pack(OutputStream& stream, const frc::DifferentialDriveWheelVoltages& value); }; diff --git a/wpimath/src/main/native/include/frc/controller/proto/ElevatorFeedforwardProto.h b/wpimath/src/main/native/include/frc/controller/proto/ElevatorFeedforwardProto.h index 377f62aaa3..5ae323e769 100644 --- a/wpimath/src/main/native/include/frc/controller/proto/ElevatorFeedforwardProto.h +++ b/wpimath/src/main/native/include/frc/controller/proto/ElevatorFeedforwardProto.h @@ -8,11 +8,14 @@ #include #include "frc/controller/ElevatorFeedforward.h" +#include "pb.h" +#include "wpimath/protobuf/controller.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::ElevatorFeedforward Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, - const frc::ElevatorFeedforward& value); + using MessageStruct = wpi_proto_ProtobufElevatorFeedforward; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::ElevatorFeedforward& value); }; diff --git a/wpimath/src/main/native/include/frc/controller/proto/SimpleMotorFeedforwardProto.h b/wpimath/src/main/native/include/frc/controller/proto/SimpleMotorFeedforwardProto.h index 4d763f0b19..fc5bfb1cb4 100644 --- a/wpimath/src/main/native/include/frc/controller/proto/SimpleMotorFeedforwardProto.h +++ b/wpimath/src/main/native/include/frc/controller/proto/SimpleMotorFeedforwardProto.h @@ -4,47 +4,55 @@ #pragma once -#include #include -#include "controller.pb.h" #include "frc/controller/SimpleMotorFeedforward.h" +#include "pb.h" #include "units/length.h" +#include "wpimath/protobuf/controller.npb.h" // Everything is converted into units for // frc::SimpleMotorFeedforward template -struct wpi::Protobuf> { - static google::protobuf::Message* New(google::protobuf::Arena* arena) { - return wpi::CreateMessage( - arena); - } +struct wpi::Protobuf> { // NOLINT + using MessageStruct = wpi_proto_ProtobufSimpleMotorFeedforward; + using InputStream = + wpi::ProtoInputStream>; + using OutputStream = + wpi::ProtoOutputStream>; - static frc::SimpleMotorFeedforward Unpack( - const google::protobuf::Message& msg) { - auto m = - static_cast(&msg); - return {units::volt_t{m->ks()}, - units::unit_t::kv_unit>{ - m->kv()}, - units::unit_t::ka_unit>{ - m->ka()}, - units::second_t{m->dt()}}; - } + static std::optional> Unpack( + InputStream& stream) { + wpi_proto_ProtobufSimpleMotorFeedforward msg; + if (!stream.Decode(msg)) { + return {}; + } - static void Pack(google::protobuf::Message* msg, - const frc::SimpleMotorFeedforward& value) { - auto m = static_cast(msg); - m->set_ks(value.GetKs().value()); - m->set_kv( + return frc::SimpleMotorFeedforward{ + units::volt_t{msg.ks}, units::unit_t::kv_unit>{ - value.GetKv()} - .value()); - m->set_ka( + msg.kv}, units::unit_t::ka_unit>{ - value.GetKa()} - .value()); - m->set_dt(units::second_t{value.GetDt()}.value()); + msg.ka}, + units::second_t{msg.dt}, + }; + } + + static bool Pack(OutputStream& stream, + const frc::SimpleMotorFeedforward& value) { + wpi_proto_ProtobufSimpleMotorFeedforward msg{ + .ks = value.GetKs().value(), + .kv = + units::unit_t::kv_unit>{ + value.GetKv()} + .value(), + .ka = + units::unit_t::ka_unit>{ + value.GetKa()} + .value(), + .dt = units::second_t{value.GetDt()}.value(), + }; + return stream.Encode(msg); } }; diff --git a/wpimath/src/main/native/include/frc/geometry/proto/Ellipse2dProto.h b/wpimath/src/main/native/include/frc/geometry/proto/Ellipse2dProto.h index 550e783e1c..aebcbd8053 100644 --- a/wpimath/src/main/native/include/frc/geometry/proto/Ellipse2dProto.h +++ b/wpimath/src/main/native/include/frc/geometry/proto/Ellipse2dProto.h @@ -8,10 +8,13 @@ #include #include "frc/geometry/Ellipse2d.h" +#include "wpimath/protobuf/geometry2d.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::Ellipse2d Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, const frc::Ellipse2d& value); + using MessageStruct = wpi_proto_ProtobufEllipse2d; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::Ellipse2d& value); }; diff --git a/wpimath/src/main/native/include/frc/geometry/proto/Pose2dProto.h b/wpimath/src/main/native/include/frc/geometry/proto/Pose2dProto.h index 9934b4ae83..024c8b5d68 100644 --- a/wpimath/src/main/native/include/frc/geometry/proto/Pose2dProto.h +++ b/wpimath/src/main/native/include/frc/geometry/proto/Pose2dProto.h @@ -8,10 +8,14 @@ #include #include "frc/geometry/Pose2d.h" +#include "pb.h" +#include "wpimath/protobuf/geometry2d.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::Pose2d Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, const frc::Pose2d& value); + using MessageStruct = wpi_proto_ProtobufPose2d; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::Pose2d& value); }; diff --git a/wpimath/src/main/native/include/frc/geometry/proto/Pose3dProto.h b/wpimath/src/main/native/include/frc/geometry/proto/Pose3dProto.h index 9941568d25..5b7e0ba9ee 100644 --- a/wpimath/src/main/native/include/frc/geometry/proto/Pose3dProto.h +++ b/wpimath/src/main/native/include/frc/geometry/proto/Pose3dProto.h @@ -8,10 +8,13 @@ #include #include "frc/geometry/Pose3d.h" +#include "wpimath/protobuf/geometry3d.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::Pose3d Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, const frc::Pose3d& value); + using MessageStruct = wpi_proto_ProtobufPose3d; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::Pose3d& value); }; diff --git a/wpimath/src/main/native/include/frc/geometry/proto/QuaternionProto.h b/wpimath/src/main/native/include/frc/geometry/proto/QuaternionProto.h index 77f371d67e..e0d6918417 100644 --- a/wpimath/src/main/native/include/frc/geometry/proto/QuaternionProto.h +++ b/wpimath/src/main/native/include/frc/geometry/proto/QuaternionProto.h @@ -8,11 +8,13 @@ #include #include "frc/geometry/Quaternion.h" +#include "wpimath/protobuf/geometry3d.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::Quaternion Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, - const frc::Quaternion& value); + using MessageStruct = wpi_proto_ProtobufQuaternion; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::Quaternion& value); }; diff --git a/wpimath/src/main/native/include/frc/geometry/proto/Rectangle2dProto.h b/wpimath/src/main/native/include/frc/geometry/proto/Rectangle2dProto.h index e6f20da005..9920145f98 100644 --- a/wpimath/src/main/native/include/frc/geometry/proto/Rectangle2dProto.h +++ b/wpimath/src/main/native/include/frc/geometry/proto/Rectangle2dProto.h @@ -8,11 +8,13 @@ #include #include "frc/geometry/Rectangle2d.h" +#include "wpimath/protobuf/geometry2d.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::Rectangle2d Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, - const frc::Rectangle2d& value); + using MessageStruct = wpi_proto_ProtobufRectangle2d; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::Rectangle2d& value); }; diff --git a/wpimath/src/main/native/include/frc/geometry/proto/Rotation2dProto.h b/wpimath/src/main/native/include/frc/geometry/proto/Rotation2dProto.h index 33c348e6fc..477ab240e9 100644 --- a/wpimath/src/main/native/include/frc/geometry/proto/Rotation2dProto.h +++ b/wpimath/src/main/native/include/frc/geometry/proto/Rotation2dProto.h @@ -8,11 +8,14 @@ #include #include "frc/geometry/Rotation2d.h" +#include "pb.h" +#include "wpimath/protobuf/geometry2d.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::Rotation2d Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, - const frc::Rotation2d& value); + using MessageStruct = wpi_proto_ProtobufRotation2d; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::Rotation2d& value); }; diff --git a/wpimath/src/main/native/include/frc/geometry/proto/Rotation3dProto.h b/wpimath/src/main/native/include/frc/geometry/proto/Rotation3dProto.h index f6f5662357..1c8d70b070 100644 --- a/wpimath/src/main/native/include/frc/geometry/proto/Rotation3dProto.h +++ b/wpimath/src/main/native/include/frc/geometry/proto/Rotation3dProto.h @@ -8,11 +8,13 @@ #include #include "frc/geometry/Rotation3d.h" +#include "wpimath/protobuf/geometry3d.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::Rotation3d Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, - const frc::Rotation3d& value); + using MessageStruct = wpi_proto_ProtobufRotation3d; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::Rotation3d& value); }; diff --git a/wpimath/src/main/native/include/frc/geometry/proto/Transform2dProto.h b/wpimath/src/main/native/include/frc/geometry/proto/Transform2dProto.h index 5ff19bd226..cbb3510180 100644 --- a/wpimath/src/main/native/include/frc/geometry/proto/Transform2dProto.h +++ b/wpimath/src/main/native/include/frc/geometry/proto/Transform2dProto.h @@ -8,11 +8,13 @@ #include #include "frc/geometry/Transform2d.h" +#include "wpimath/protobuf/geometry2d.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::Transform2d Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, - const frc::Transform2d& value); + using MessageStruct = wpi_proto_ProtobufTransform2d; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::Transform2d& value); }; diff --git a/wpimath/src/main/native/include/frc/geometry/proto/Transform3dProto.h b/wpimath/src/main/native/include/frc/geometry/proto/Transform3dProto.h index d27fb9a0b8..3a4643c836 100644 --- a/wpimath/src/main/native/include/frc/geometry/proto/Transform3dProto.h +++ b/wpimath/src/main/native/include/frc/geometry/proto/Transform3dProto.h @@ -8,11 +8,13 @@ #include #include "frc/geometry/Transform3d.h" +#include "wpimath/protobuf/geometry3d.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::Transform3d Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, - const frc::Transform3d& value); + using MessageStruct = wpi_proto_ProtobufTransform3d; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::Transform3d& value); }; diff --git a/wpimath/src/main/native/include/frc/geometry/proto/Translation2dProto.h b/wpimath/src/main/native/include/frc/geometry/proto/Translation2dProto.h index 6516fc8d88..acb11adabd 100644 --- a/wpimath/src/main/native/include/frc/geometry/proto/Translation2dProto.h +++ b/wpimath/src/main/native/include/frc/geometry/proto/Translation2dProto.h @@ -8,11 +8,14 @@ #include #include "frc/geometry/Translation2d.h" +#include "pb.h" +#include "wpimath/protobuf/geometry2d.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::Translation2d Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, - const frc::Translation2d& value); + using MessageStruct = wpi_proto_ProtobufTranslation2d; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::Translation2d& value); }; diff --git a/wpimath/src/main/native/include/frc/geometry/proto/Translation3dProto.h b/wpimath/src/main/native/include/frc/geometry/proto/Translation3dProto.h index 2d317fc5af..2b21943e01 100644 --- a/wpimath/src/main/native/include/frc/geometry/proto/Translation3dProto.h +++ b/wpimath/src/main/native/include/frc/geometry/proto/Translation3dProto.h @@ -8,11 +8,13 @@ #include #include "frc/geometry/Translation3d.h" +#include "wpimath/protobuf/geometry3d.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::Translation3d Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, - const frc::Translation3d& value); + using MessageStruct = wpi_proto_ProtobufTranslation3d; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::Translation3d& value); }; diff --git a/wpimath/src/main/native/include/frc/geometry/proto/Twist2dProto.h b/wpimath/src/main/native/include/frc/geometry/proto/Twist2dProto.h index 328798e14c..62e27ad230 100644 --- a/wpimath/src/main/native/include/frc/geometry/proto/Twist2dProto.h +++ b/wpimath/src/main/native/include/frc/geometry/proto/Twist2dProto.h @@ -8,10 +8,13 @@ #include #include "frc/geometry/Twist2d.h" +#include "wpimath/protobuf/geometry2d.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::Twist2d Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, const frc::Twist2d& value); + using MessageStruct = wpi_proto_ProtobufTwist2d; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::Twist2d& value); }; diff --git a/wpimath/src/main/native/include/frc/geometry/proto/Twist3dProto.h b/wpimath/src/main/native/include/frc/geometry/proto/Twist3dProto.h index 24f496935e..bb467cb6d7 100644 --- a/wpimath/src/main/native/include/frc/geometry/proto/Twist3dProto.h +++ b/wpimath/src/main/native/include/frc/geometry/proto/Twist3dProto.h @@ -8,10 +8,13 @@ #include #include "frc/geometry/Twist3d.h" +#include "wpimath/protobuf/geometry3d.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::Twist3d Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, const frc::Twist3d& value); + using MessageStruct = wpi_proto_ProtobufTwist3d; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::Twist3d& value); }; diff --git a/wpimath/src/main/native/include/frc/kinematics/Kinematics.h b/wpimath/src/main/native/include/frc/kinematics/Kinematics.h index f683dffa94..3901630e59 100644 --- a/wpimath/src/main/native/include/frc/kinematics/Kinematics.h +++ b/wpimath/src/main/native/include/frc/kinematics/Kinematics.h @@ -24,6 +24,8 @@ template std::assignable_from class WPILIB_DLLEXPORT Kinematics { public: + virtual ~Kinematics() noexcept = default; + /** * Performs forward kinematics to return the resulting chassis speed from the * wheel speeds. This method is often used for odometry -- determining the diff --git a/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h b/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h index aecc3306d5..276f9a8818 100644 --- a/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h +++ b/wpimath/src/main/native/include/frc/kinematics/SwerveDriveKinematics.h @@ -429,7 +429,7 @@ class SwerveDriveKinematics return {result}; } - const wpi::array GetModules() const { + const wpi::array& GetModules() const { return m_modules; } diff --git a/wpimath/src/main/native/include/frc/kinematics/proto/ChassisSpeedsProto.h b/wpimath/src/main/native/include/frc/kinematics/proto/ChassisSpeedsProto.h index cefc83f8db..7421bd061d 100644 --- a/wpimath/src/main/native/include/frc/kinematics/proto/ChassisSpeedsProto.h +++ b/wpimath/src/main/native/include/frc/kinematics/proto/ChassisSpeedsProto.h @@ -8,11 +8,13 @@ #include #include "frc/kinematics/ChassisSpeeds.h" +#include "wpimath/protobuf/kinematics.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::ChassisSpeeds Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, - const frc::ChassisSpeeds& value); + using MessageStruct = wpi_proto_ProtobufChassisSpeeds; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::ChassisSpeeds& value); }; diff --git a/wpimath/src/main/native/include/frc/kinematics/proto/DifferentialDriveKinematicsProto.h b/wpimath/src/main/native/include/frc/kinematics/proto/DifferentialDriveKinematicsProto.h index 9108f33c9c..02437a7214 100644 --- a/wpimath/src/main/native/include/frc/kinematics/proto/DifferentialDriveKinematicsProto.h +++ b/wpimath/src/main/native/include/frc/kinematics/proto/DifferentialDriveKinematicsProto.h @@ -8,12 +8,15 @@ #include #include "frc/kinematics/DifferentialDriveKinematics.h" +#include "wpimath/protobuf/kinematics.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::DifferentialDriveKinematics Unpack( - const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, + using MessageStruct = wpi_proto_ProtobufDifferentialDriveKinematics; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack( + InputStream& stream); + static bool Pack(OutputStream& stream, const frc::DifferentialDriveKinematics& value); }; diff --git a/wpimath/src/main/native/include/frc/kinematics/proto/DifferentialDriveWheelPositionsProto.h b/wpimath/src/main/native/include/frc/kinematics/proto/DifferentialDriveWheelPositionsProto.h index 3cf44eaa40..c4138f4784 100644 --- a/wpimath/src/main/native/include/frc/kinematics/proto/DifferentialDriveWheelPositionsProto.h +++ b/wpimath/src/main/native/include/frc/kinematics/proto/DifferentialDriveWheelPositionsProto.h @@ -8,12 +8,17 @@ #include #include "frc/kinematics/DifferentialDriveWheelPositions.h" +#include "wpimath/protobuf/kinematics.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::DifferentialDriveWheelPositions Unpack( - const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, + using MessageStruct = wpi_proto_ProtobufDifferentialDriveWheelPositions; + using InputStream = + wpi::ProtoInputStream; + using OutputStream = + wpi::ProtoOutputStream; + static std::optional Unpack( + InputStream& stream); + static bool Pack(OutputStream& stream, const frc::DifferentialDriveWheelPositions& value); }; diff --git a/wpimath/src/main/native/include/frc/kinematics/proto/DifferentialDriveWheelSpeedsProto.h b/wpimath/src/main/native/include/frc/kinematics/proto/DifferentialDriveWheelSpeedsProto.h index f310892538..f08a80b04d 100644 --- a/wpimath/src/main/native/include/frc/kinematics/proto/DifferentialDriveWheelSpeedsProto.h +++ b/wpimath/src/main/native/include/frc/kinematics/proto/DifferentialDriveWheelSpeedsProto.h @@ -8,12 +8,16 @@ #include #include "frc/kinematics/DifferentialDriveWheelSpeeds.h" +#include "wpimath/protobuf/kinematics.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::DifferentialDriveWheelSpeeds Unpack( - const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, + using MessageStruct = wpi_proto_ProtobufDifferentialDriveWheelSpeeds; + using InputStream = wpi::ProtoInputStream; + using OutputStream = + wpi::ProtoOutputStream; + static std::optional Unpack( + InputStream& stream); + static bool Pack(OutputStream& stream, const frc::DifferentialDriveWheelSpeeds& value); }; diff --git a/wpimath/src/main/native/include/frc/kinematics/proto/MecanumDriveKinematicsProto.h b/wpimath/src/main/native/include/frc/kinematics/proto/MecanumDriveKinematicsProto.h index 16e828824f..fd3beab990 100644 --- a/wpimath/src/main/native/include/frc/kinematics/proto/MecanumDriveKinematicsProto.h +++ b/wpimath/src/main/native/include/frc/kinematics/proto/MecanumDriveKinematicsProto.h @@ -8,12 +8,14 @@ #include #include "frc/kinematics/MecanumDriveKinematics.h" +#include "wpimath/protobuf/kinematics.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::MecanumDriveKinematics Unpack( - const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, + using MessageStruct = wpi_proto_ProtobufMecanumDriveKinematics; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::MecanumDriveKinematics& value); }; diff --git a/wpimath/src/main/native/include/frc/kinematics/proto/MecanumDriveWheelPositionsProto.h b/wpimath/src/main/native/include/frc/kinematics/proto/MecanumDriveWheelPositionsProto.h index a4b4bd6762..02a09a0f2e 100644 --- a/wpimath/src/main/native/include/frc/kinematics/proto/MecanumDriveWheelPositionsProto.h +++ b/wpimath/src/main/native/include/frc/kinematics/proto/MecanumDriveWheelPositionsProto.h @@ -8,12 +8,15 @@ #include #include "frc/kinematics/MecanumDriveWheelPositions.h" +#include "wpimath/protobuf/kinematics.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::MecanumDriveWheelPositions Unpack( - const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, + using MessageStruct = wpi_proto_ProtobufMecanumDriveWheelPositions; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack( + InputStream& stream); + static bool Pack(OutputStream& stream, const frc::MecanumDriveWheelPositions& value); }; diff --git a/wpimath/src/main/native/include/frc/kinematics/proto/MecanumDriveWheelSpeedsProto.h b/wpimath/src/main/native/include/frc/kinematics/proto/MecanumDriveWheelSpeedsProto.h index 4d099d3de1..6e26476fde 100644 --- a/wpimath/src/main/native/include/frc/kinematics/proto/MecanumDriveWheelSpeedsProto.h +++ b/wpimath/src/main/native/include/frc/kinematics/proto/MecanumDriveWheelSpeedsProto.h @@ -8,12 +8,15 @@ #include #include "frc/kinematics/MecanumDriveWheelSpeeds.h" +#include "wpimath/protobuf/kinematics.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::MecanumDriveWheelSpeeds Unpack( - const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, + using MessageStruct = wpi_proto_ProtobufMecanumDriveWheelSpeeds; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack( + InputStream& stream); + static bool Pack(OutputStream& stream, const frc::MecanumDriveWheelSpeeds& value); }; diff --git a/wpimath/src/main/native/include/frc/kinematics/proto/SwerveDriveKinematicsProto.h b/wpimath/src/main/native/include/frc/kinematics/proto/SwerveDriveKinematicsProto.h index d9fc19a200..170ed78837 100644 --- a/wpimath/src/main/native/include/frc/kinematics/proto/SwerveDriveKinematicsProto.h +++ b/wpimath/src/main/native/include/frc/kinematics/proto/SwerveDriveKinematicsProto.h @@ -7,36 +7,40 @@ #include #include -#include #include +#include #include "frc/kinematics/SwerveDriveKinematics.h" -#include "kinematics.pb.h" +#include "wpimath/protobuf/kinematics.npb.h" template struct wpi::Protobuf> { - static google::protobuf::Message* New(google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); - } + using MessageStruct = wpi_proto_ProtobufSwerveDriveKinematics; + using InputStream = + wpi::ProtoInputStream>; + using OutputStream = + wpi::ProtoOutputStream>; - static frc::SwerveDriveKinematics Unpack( - const google::protobuf::Message& msg) { - auto m = - static_cast(&msg); - if (m->modules_size() != NumModules) { - throw std::invalid_argument(fmt::format( - "Tried to unpack message with {} elements in modules into " - "SwerveDriveKinematics with {} modules", - m->modules_size(), NumModules)); + static std::optional> Unpack( + InputStream& stream) { + wpi::WpiArrayUnpackCallback modules; + wpi_proto_ProtobufSwerveDriveKinematics msg{ + .modules = modules.Callback(), + }; + modules.SetLimits(wpi::DecodeLimits::Fail); + if (!stream.Decode(msg)) { + return {}; } - return frc::SwerveDriveKinematics{ - wpi::UnpackProtobufArray(m->modules())}; + + return frc::SwerveDriveKinematics{modules.Array()}; } - static void Pack(google::protobuf::Message* msg, + static bool Pack(OutputStream& stream, const frc::SwerveDriveKinematics& value) { - auto m = static_cast(msg); - wpi::PackProtobufArray(m->mutable_modules(), value.GetModules()); + wpi::PackCallback modules{value.GetModules()}; + wpi_proto_ProtobufSwerveDriveKinematics msg{ + .modules = modules.Callback(), + }; + return stream.Encode(msg); } }; diff --git a/wpimath/src/main/native/include/frc/kinematics/proto/SwerveModulePositionProto.h b/wpimath/src/main/native/include/frc/kinematics/proto/SwerveModulePositionProto.h index 3e864cbd95..342717340d 100644 --- a/wpimath/src/main/native/include/frc/kinematics/proto/SwerveModulePositionProto.h +++ b/wpimath/src/main/native/include/frc/kinematics/proto/SwerveModulePositionProto.h @@ -8,11 +8,14 @@ #include #include "frc/kinematics/SwerveModulePosition.h" +#include "wpimath/protobuf/kinematics.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::SwerveModulePosition Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, + using MessageStruct = wpi_proto_ProtobufSwerveModulePosition; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::SwerveModulePosition& value); }; diff --git a/wpimath/src/main/native/include/frc/kinematics/proto/SwerveModuleStateProto.h b/wpimath/src/main/native/include/frc/kinematics/proto/SwerveModuleStateProto.h index 3e7b3ec6e4..860f7ccdae 100644 --- a/wpimath/src/main/native/include/frc/kinematics/proto/SwerveModuleStateProto.h +++ b/wpimath/src/main/native/include/frc/kinematics/proto/SwerveModuleStateProto.h @@ -8,11 +8,13 @@ #include #include "frc/kinematics/SwerveModuleState.h" +#include "wpimath/protobuf/kinematics.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::SwerveModuleState Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, - const frc::SwerveModuleState& value); + using MessageStruct = wpi_proto_ProtobufSwerveModuleState; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::SwerveModuleState& value); }; diff --git a/wpimath/src/main/native/include/frc/proto/MatrixProto.h b/wpimath/src/main/native/include/frc/proto/MatrixProto.h index 8dc9285b3c..63a7a28dc0 100644 --- a/wpimath/src/main/native/include/frc/proto/MatrixProto.h +++ b/wpimath/src/main/native/include/frc/proto/MatrixProto.h @@ -7,50 +7,65 @@ #include #include -#include #include +#include #include "frc/EigenCore.h" -#include "wpimath.pb.h" +#include "wpimath/protobuf/wpimath.npb.h" template requires(Cols != 1) struct wpi::Protobuf> { - static google::protobuf::Message* New(google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); - } + using MessageStruct = wpi_proto_ProtobufMatrix; + using InputStream = wpi::ProtoInputStream< + frc::Matrixd>; + using OutputStream = wpi::ProtoOutputStream< + frc::Matrixd>; - static frc::Matrixd Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); - if (m->num_rows() != Rows || m->num_cols() != Cols) { - throw std::invalid_argument(fmt::format( - "Tried to unpack message with {} rows and {} columns into " - "Matrix with {} rows and {} columns", - m->num_rows(), m->num_cols(), Rows, Cols)); + static std::optional> + Unpack(InputStream& stream) { + constexpr bool isSmall = Rows * Cols * sizeof(double) < 256; + using UnpackType = + std::conditional_t, + wpi::StdVectorUnpackCallback>; + UnpackType data; + data.Vec().reserve(Rows * Cols); + data.SetLimits(wpi::DecodeLimits::Fail); + wpi_proto_ProtobufMatrix msg; + msg.data = data.Callback(); + if (!stream.Decode(msg)) { + return {}; } - if (m->data_size() != Rows * Cols) { - throw std::invalid_argument( - fmt::format("Tried to unpack message with {} elements in data into " - "Matrix with {} elements", - m->data_size(), Rows * Cols)); + + if (msg.num_rows != Rows || msg.num_cols != Cols) { + return {}; } + + auto items = data.Items(); + + if (items.size() != Rows * Cols) { + return {}; + } + frc::Matrixd mat; for (int i = 0; i < Rows * Cols; i++) { - mat(i) = m->data(i); + mat(i) = items[i]; } + return mat; } - static void Pack( - google::protobuf::Message* msg, + static bool Pack( + OutputStream& stream, const frc::Matrixd& value) { - auto m = static_cast(msg); - m->set_num_rows(Rows); - m->set_num_cols(Cols); - m->clear_data(); - for (int i = 0; i < Rows * Cols; i++) { - m->add_data(value(i)); - } + std::span dataSpan{value.data(), + static_cast(Rows * Cols)}; + wpi::PackCallback data{dataSpan}; + wpi_proto_ProtobufMatrix msg{ + .num_rows = Rows, + .num_cols = Cols, + .data = data.Callback(), + }; + return stream.Encode(msg); } }; diff --git a/wpimath/src/main/native/include/frc/proto/VectorProto.h b/wpimath/src/main/native/include/frc/proto/VectorProto.h index a982e19a70..9a72c03f9e 100644 --- a/wpimath/src/main/native/include/frc/proto/VectorProto.h +++ b/wpimath/src/main/native/include/frc/proto/VectorProto.h @@ -7,41 +7,58 @@ #include #include -#include #include +#include #include "frc/EigenCore.h" -#include "wpimath.pb.h" +#include "wpimath/protobuf/wpimath.npb.h" template struct wpi::Protobuf> { - static google::protobuf::Message* New(google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); - } + using MessageStruct = wpi_proto_ProtobufVector; + using InputStream = + wpi::ProtoInputStream>; + using OutputStream = + wpi::ProtoOutputStream>; - static frc::Matrixd Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); - if (m->rows_size() != Size) { - throw std::invalid_argument( - fmt::format("Tried to unpack message with {} elements in rows into " - "Vector with {} rows", - m->rows_size(), Size)); + static std::optional> Unpack( + InputStream& stream) { + constexpr bool isSmall = Size * sizeof(double) < 256; + using UnpackType = + std::conditional_t, + wpi::StdVectorUnpackCallback>; + UnpackType rows; + rows.Vec().reserve(Size); + rows.SetLimits(wpi::DecodeLimits::Fail); + wpi_proto_ProtobufVector msg{ + .rows = rows.Callback(), + }; + if (!stream.Decode(msg)) { + return {}; } - frc::Matrixd vec; + + auto items = rows.Items(); + + if (items.size() != Size) { + return {}; + } + + frc::Matrixd mat; for (int i = 0; i < Size; i++) { - vec(i) = m->rows(i); + mat(i) = items[i]; } - return vec; + + return mat; } - static void Pack( - google::protobuf::Message* msg, + static bool Pack( + OutputStream& stream, const frc::Matrixd& value) { - auto m = static_cast(msg); - m->clear_rows(); - for (int i = 0; i < Size; i++) { - m->add_rows(value(i)); - } + std::span rowsSpan{value.data(), static_cast(Size)}; + wpi::PackCallback rows{rowsSpan}; + wpi_proto_ProtobufVector msg{ + .rows = rows.Callback(), + }; + return stream.Encode(msg); } }; diff --git a/wpimath/src/main/native/include/frc/spline/proto/CubicHermiteSplineProto.h b/wpimath/src/main/native/include/frc/spline/proto/CubicHermiteSplineProto.h index 324304b279..88dd412995 100644 --- a/wpimath/src/main/native/include/frc/spline/proto/CubicHermiteSplineProto.h +++ b/wpimath/src/main/native/include/frc/spline/proto/CubicHermiteSplineProto.h @@ -8,11 +8,13 @@ #include #include "frc/spline/CubicHermiteSpline.h" +#include "wpimath/protobuf/spline.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::CubicHermiteSpline Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, - const frc::CubicHermiteSpline& value); + using MessageStruct = wpi_proto_ProtobufCubicHermiteSpline; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::CubicHermiteSpline& value); }; diff --git a/wpimath/src/main/native/include/frc/spline/proto/QuinticHermiteSplineProto.h b/wpimath/src/main/native/include/frc/spline/proto/QuinticHermiteSplineProto.h index e84f75476a..2d59cea0be 100644 --- a/wpimath/src/main/native/include/frc/spline/proto/QuinticHermiteSplineProto.h +++ b/wpimath/src/main/native/include/frc/spline/proto/QuinticHermiteSplineProto.h @@ -8,11 +8,14 @@ #include #include "frc/spline/QuinticHermiteSpline.h" +#include "wpimath/protobuf/spline.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::QuinticHermiteSpline Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, + using MessageStruct = wpi_proto_ProtobufQuinticHermiteSpline; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::QuinticHermiteSpline& value); }; diff --git a/wpimath/src/main/native/include/frc/system/plant/proto/DCMotorProto.h b/wpimath/src/main/native/include/frc/system/plant/proto/DCMotorProto.h index acae1db6d3..8c9f2b7c66 100644 --- a/wpimath/src/main/native/include/frc/system/plant/proto/DCMotorProto.h +++ b/wpimath/src/main/native/include/frc/system/plant/proto/DCMotorProto.h @@ -8,10 +8,13 @@ #include #include "frc/system/plant/DCMotor.h" +#include "wpimath/protobuf/plant.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::DCMotor Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, const frc::DCMotor& value); + using MessageStruct = wpi_proto_ProtobufDCMotor; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::DCMotor& value); }; diff --git a/wpimath/src/main/native/include/frc/system/proto/LinearSystemProto.h b/wpimath/src/main/native/include/frc/system/proto/LinearSystemProto.h index 36eea0802e..0de5a683f6 100644 --- a/wpimath/src/main/native/include/frc/system/proto/LinearSystemProto.h +++ b/wpimath/src/main/native/include/frc/system/proto/LinearSystemProto.h @@ -5,48 +5,84 @@ #pragma once #include +#include #include -#include #include +#include #include "frc/proto/MatrixProto.h" #include "frc/system/LinearSystem.h" -#include "system.pb.h" +#include "wpimath/protobuf/system.npb.h" template struct wpi::Protobuf> { - static google::protobuf::Message* New(google::protobuf::Arena* arena) { - return wpi::CreateMessage(arena); - } + using MessageStruct = wpi_proto_ProtobufLinearSystem; + using InputStream = + wpi::ProtoInputStream>; + using OutputStream = + wpi::ProtoOutputStream>; - static frc::LinearSystem Unpack( - const google::protobuf::Message& msg) { - auto m = static_cast(&msg); - if (m->num_states() != States || m->num_inputs() != Inputs || - m->num_outputs() != Outputs) { - throw std::invalid_argument(fmt::format( - "Tried to unpack message with {} states and {} inputs and {} outputs " - "into LinearSystem with {} states and {} inputs and {} outputs", - m->num_states(), m->num_inputs(), m->num_outputs(), States, Inputs, - Outputs)); + static std::optional> Unpack( + InputStream& stream) { + wpi::UnpackCallback> a; + a.SetLimits(wpi::DecodeLimits::Fail); + wpi::UnpackCallback> b; + a.SetLimits(wpi::DecodeLimits::Fail); + wpi::UnpackCallback> c; + a.SetLimits(wpi::DecodeLimits::Fail); + wpi::UnpackCallback> d; + a.SetLimits(wpi::DecodeLimits::Fail); + + wpi_proto_ProtobufLinearSystem msg; + msg.a = a.Callback(); + msg.b = b.Callback(); + msg.c = c.Callback(); + msg.d = d.Callback(); + + if (!stream.Decode(msg)) { + return {}; } + + if (msg.num_inputs != Inputs || msg.num_outputs != Outputs || + msg.num_states != States) { + return {}; + } + + auto ai = a.Items(); + auto bi = b.Items(); + auto ci = c.Items(); + auto di = d.Items(); + + if (ai.empty() || bi.empty() || ci.empty() || di.empty()) { + return {}; + } + return frc::LinearSystem{ - wpi::UnpackProtobuf>(m->wpi_a()), - wpi::UnpackProtobuf>(m->wpi_b()), - wpi::UnpackProtobuf>(m->wpi_c()), - wpi::UnpackProtobuf>(m->wpi_d())}; + std::move(ai[0]), + std::move(bi[0]), + std::move(ci[0]), + std::move(di[0]), + }; } - static void Pack(google::protobuf::Message* msg, + static bool Pack(OutputStream& stream, const frc::LinearSystem& value) { - auto m = static_cast(msg); - m->set_num_states(States); - m->set_num_inputs(Inputs); - m->set_num_outputs(Outputs); - wpi::PackProtobuf(m->mutable_a(), value.A()); - wpi::PackProtobuf(m->mutable_b(), value.B()); - wpi::PackProtobuf(m->mutable_c(), value.C()); - wpi::PackProtobuf(m->mutable_d(), value.D()); + wpi::PackCallback a{&value.A()}; + wpi::PackCallback b{&value.B()}; + wpi::PackCallback c{&value.C()}; + wpi::PackCallback d{&value.D()}; + + wpi_proto_ProtobufLinearSystem msg{ + .num_states = States, + .num_inputs = Inputs, + .num_outputs = Outputs, + .a = a.Callback(), + .b = b.Callback(), + .c = c.Callback(), + .d = d.Callback(), + }; + + return stream.Encode(msg); } }; diff --git a/wpimath/src/main/native/include/frc/trajectory/proto/TrajectoryProto.h b/wpimath/src/main/native/include/frc/trajectory/proto/TrajectoryProto.h index 4b485b2a92..b6a1e5b958 100644 --- a/wpimath/src/main/native/include/frc/trajectory/proto/TrajectoryProto.h +++ b/wpimath/src/main/native/include/frc/trajectory/proto/TrajectoryProto.h @@ -8,11 +8,13 @@ #include #include "frc/trajectory/Trajectory.h" +#include "wpimath/protobuf/trajectory.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::Trajectory Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, - const frc::Trajectory& value); + using MessageStruct = wpi_proto_ProtobufTrajectory; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::Trajectory& value); }; diff --git a/wpimath/src/main/native/include/frc/trajectory/proto/TrajectoryStateProto.h b/wpimath/src/main/native/include/frc/trajectory/proto/TrajectoryStateProto.h index 150837b8d3..7399c8709c 100644 --- a/wpimath/src/main/native/include/frc/trajectory/proto/TrajectoryStateProto.h +++ b/wpimath/src/main/native/include/frc/trajectory/proto/TrajectoryStateProto.h @@ -8,11 +8,13 @@ #include #include "frc/trajectory/Trajectory.h" +#include "wpimath/protobuf/trajectory.npb.h" template <> struct WPILIB_DLLEXPORT wpi::Protobuf { - static google::protobuf::Message* New(google::protobuf::Arena* arena); - static frc::Trajectory::State Unpack(const google::protobuf::Message& msg); - static void Pack(google::protobuf::Message* msg, - const frc::Trajectory::State& value); + using MessageStruct = wpi_proto_ProtobufTrajectoryState; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const frc::Trajectory::State& value); }; diff --git a/wpimath/src/test/native/cpp/ProtoTestBase.h b/wpimath/src/test/native/cpp/ProtoTestBase.h index 5a5affd812..c2fbef75b9 100644 --- a/wpimath/src/test/native/cpp/ProtoTestBase.h +++ b/wpimath/src/test/native/cpp/ProtoTestBase.h @@ -4,8 +4,8 @@ #pragma once -#include #include +#include #include template @@ -14,41 +14,14 @@ class ProtoTest : public testing::Test {}; TYPED_TEST_SUITE_P(ProtoTest); TYPED_TEST_P(ProtoTest, RoundTrip) { - using Type = typename TypeParam::Type; - google::protobuf::Arena arena; - google::protobuf::Message* proto = wpi::Protobuf::New(&arena); - wpi::PackProtobuf(proto, TypeParam::kTestData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Type unpacked_data = wpi::UnpackProtobuf(*proto); - TypeParam::CheckEq(TypeParam::kTestData, unpacked_data); + ASSERT_TRUE(message.Pack(buf, TypeParam::kTestData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + TypeParam::CheckEq(TypeParam::kTestData, *unpacked_data); } -TYPED_TEST_P(ProtoTest, DoublePack) { - using Type = typename TypeParam::Type; - google::protobuf::Arena arena; - google::protobuf::Message* proto = wpi::Protobuf::New(&arena); - wpi::PackProtobuf(proto, TypeParam::kTestData); - wpi::PackProtobuf(proto, TypeParam::kTestData); - - Type unpacked_data = wpi::UnpackProtobuf(*proto); - TypeParam::CheckEq(TypeParam::kTestData, unpacked_data); -} - -TYPED_TEST_P(ProtoTest, DoubleUnpack) { - using Type = typename TypeParam::Type; - google::protobuf::Arena arena; - google::protobuf::Message* proto = wpi::Protobuf::New(&arena); - wpi::PackProtobuf(proto, TypeParam::kTestData); - - { - Type unpacked_data = wpi::UnpackProtobuf(*proto); - TypeParam::CheckEq(TypeParam::kTestData, unpacked_data); - } - - { - Type unpacked_data = wpi::UnpackProtobuf(*proto); - TypeParam::CheckEq(TypeParam::kTestData, unpacked_data); - } -} - -REGISTER_TYPED_TEST_SUITE_P(ProtoTest, RoundTrip, DoublePack, DoubleUnpack); +REGISTER_TYPED_TEST_SUITE_P(ProtoTest, RoundTrip); diff --git a/wpimath/src/test/native/cpp/controller/proto/ArmFeedforwardProtoTest.cpp b/wpimath/src/test/native/cpp/controller/proto/ArmFeedforwardProtoTest.cpp index 6ad9579a74..ef4f612d8c 100644 --- a/wpimath/src/test/native/cpp/controller/proto/ArmFeedforwardProtoTest.cpp +++ b/wpimath/src/test/native/cpp/controller/proto/ArmFeedforwardProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/controller/ArmFeedforward.h" @@ -11,8 +11,6 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - static constexpr auto Ks = 1.91_V; static constexpr auto Kg = 2.29_V; static constexpr auto Kv = 35.04_V * 1_s / 1_rad; @@ -21,13 +19,15 @@ const ArmFeedforward kExpectedData{Ks, Kg, Kv, Ka}; } // namespace TEST(ArmFeedforwardProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - ArmFeedforward unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.GetKs().value(), unpacked_data.GetKs().value()); - EXPECT_EQ(kExpectedData.GetKg().value(), unpacked_data.GetKg().value()); - EXPECT_EQ(kExpectedData.GetKv().value(), unpacked_data.GetKv().value()); - EXPECT_EQ(kExpectedData.GetKa().value(), unpacked_data.GetKa().value()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.GetKs().value(), unpacked_data->GetKs().value()); + EXPECT_EQ(kExpectedData.GetKg().value(), unpacked_data->GetKg().value()); + EXPECT_EQ(kExpectedData.GetKv().value(), unpacked_data->GetKv().value()); + EXPECT_EQ(kExpectedData.GetKa().value(), unpacked_data->GetKa().value()); } diff --git a/wpimath/src/test/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProtoTest.cpp b/wpimath/src/test/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProtoTest.cpp index 466aa50f39..bc7a099a42 100644 --- a/wpimath/src/test/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProtoTest.cpp +++ b/wpimath/src/test/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/controller/DifferentialDriveWheelVoltages.h" @@ -18,11 +18,12 @@ const DifferentialDriveWheelVoltages kExpectedData = } // namespace TEST(DifferentialDriveWheelVoltagesProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - DifferentialDriveWheelVoltages unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.left.value(), unpacked_data.left.value()); - EXPECT_EQ(kExpectedData.right.value(), unpacked_data.right.value()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + EXPECT_EQ(kExpectedData.left.value(), unpacked_data->left.value()); + EXPECT_EQ(kExpectedData.right.value(), unpacked_data->right.value()); } diff --git a/wpimath/src/test/native/cpp/controller/proto/ElevatorFeedforwardProtoTest.cpp b/wpimath/src/test/native/cpp/controller/proto/ElevatorFeedforwardProtoTest.cpp index 62d8bdb4c8..be0cc42518 100644 --- a/wpimath/src/test/native/cpp/controller/proto/ElevatorFeedforwardProtoTest.cpp +++ b/wpimath/src/test/native/cpp/controller/proto/ElevatorFeedforwardProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/controller/ElevatorFeedforward.h" @@ -11,8 +11,6 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - static constexpr auto Ks = 1.91_V; static constexpr auto Kg = 2.29_V; static constexpr auto Kv = 35.04_V * 1_s / 1_m; @@ -22,13 +20,15 @@ constexpr ElevatorFeedforward kExpectedData{Ks, Kg, Kv, Ka}; } // namespace TEST(ElevatorFeedforwardProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - ElevatorFeedforward unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.GetKs().value(), unpacked_data.GetKs().value()); - EXPECT_EQ(kExpectedData.GetKg().value(), unpacked_data.GetKg().value()); - EXPECT_EQ(kExpectedData.GetKv().value(), unpacked_data.GetKv().value()); - EXPECT_EQ(kExpectedData.GetKa().value(), unpacked_data.GetKa().value()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.GetKs().value(), unpacked_data->GetKs().value()); + EXPECT_EQ(kExpectedData.GetKg().value(), unpacked_data->GetKg().value()); + EXPECT_EQ(kExpectedData.GetKv().value(), unpacked_data->GetKv().value()); + EXPECT_EQ(kExpectedData.GetKa().value(), unpacked_data->GetKa().value()); } diff --git a/wpimath/src/test/native/cpp/geometry/proto/Ellipse2dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Ellipse2dProtoTest.cpp index 810d368e63..09294f3689 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Ellipse2dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Ellipse2dProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/geometry/Ellipse2d.h" @@ -11,19 +11,19 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const Ellipse2d kExpectedData{ Pose2d{Translation2d{0.191_m, 2.2_m}, Rotation2d{22.9_rad}}, 1.2_m, 2.3_m}; } // namespace TEST(Ellipse2dProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Ellipse2d unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.Center(), unpacked_data.Center()); - EXPECT_EQ(kExpectedData.XSemiAxis(), unpacked_data.XSemiAxis()); - EXPECT_EQ(kExpectedData.YSemiAxis(), unpacked_data.YSemiAxis()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.Center(), unpacked_data->Center()); + EXPECT_EQ(kExpectedData.XSemiAxis(), unpacked_data->XSemiAxis()); + EXPECT_EQ(kExpectedData.YSemiAxis(), unpacked_data->YSemiAxis()); } diff --git a/wpimath/src/test/native/cpp/geometry/proto/Pose2dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Pose2dProtoTest.cpp index 64067dde4b..3a746f8180 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Pose2dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Pose2dProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/geometry/Pose2d.h" @@ -11,18 +11,18 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const Pose2d kExpectedData = Pose2d{Translation2d{0.191_m, 2.2_m}, Rotation2d{22.9_rad}}; } // namespace TEST(Pose2dProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Pose2d unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.Translation(), unpacked_data.Translation()); - EXPECT_EQ(kExpectedData.Rotation(), unpacked_data.Rotation()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.Translation(), unpacked_data->Translation()); + EXPECT_EQ(kExpectedData.Rotation(), unpacked_data->Rotation()); } diff --git a/wpimath/src/test/native/cpp/geometry/proto/Pose3dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Pose3dProtoTest.cpp index f685f9b8e1..70106995ee 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Pose3dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Pose3dProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/geometry/Pose3d.h" @@ -11,19 +11,19 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const Pose3d kExpectedData = Pose3d{Translation3d{1.1_m, 2.2_m, 1.1_m}, Rotation3d{Quaternion{1.91, 0.3504, 3.3, 1.74}}}; } // namespace TEST(Pose3dProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Pose3d unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.Translation(), unpacked_data.Translation()); - EXPECT_EQ(kExpectedData.Rotation(), unpacked_data.Rotation()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.Translation(), unpacked_data->Translation()); + EXPECT_EQ(kExpectedData.Rotation(), unpacked_data->Rotation()); } diff --git a/wpimath/src/test/native/cpp/geometry/proto/QuaternionProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/QuaternionProtoTest.cpp index 13c206e6aa..a063125bf8 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/QuaternionProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/QuaternionProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/geometry/Quaternion.h" @@ -11,19 +11,19 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const Quaternion kExpectedData = Quaternion{1.1, 0.191, 35.04, 19.1}; } // namespace TEST(QuaternionProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Quaternion unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.W(), unpacked_data.W()); - EXPECT_EQ(kExpectedData.X(), unpacked_data.X()); - EXPECT_EQ(kExpectedData.Y(), unpacked_data.Y()); - EXPECT_EQ(kExpectedData.Z(), unpacked_data.Z()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.W(), unpacked_data->W()); + EXPECT_EQ(kExpectedData.X(), unpacked_data->X()); + EXPECT_EQ(kExpectedData.Y(), unpacked_data->Y()); + EXPECT_EQ(kExpectedData.Z(), unpacked_data->Z()); } diff --git a/wpimath/src/test/native/cpp/geometry/proto/Rectangle2dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Rectangle2dProtoTest.cpp index 04f2d774f2..f434762a73 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Rectangle2dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Rectangle2dProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/geometry/Rectangle2d.h" @@ -11,19 +11,19 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const Rectangle2d kExpectedData{ Pose2d{Translation2d{0.191_m, 2.2_m}, Rotation2d{22.9_rad}}, 1.2_m, 2.3_m}; } // namespace TEST(Rectangle2dProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Rectangle2d unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.Center(), unpacked_data.Center()); - EXPECT_EQ(kExpectedData.XWidth(), unpacked_data.XWidth()); - EXPECT_EQ(kExpectedData.YWidth(), unpacked_data.YWidth()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.Center(), unpacked_data->Center()); + EXPECT_EQ(kExpectedData.XWidth(), unpacked_data->XWidth()); + EXPECT_EQ(kExpectedData.YWidth(), unpacked_data->YWidth()); } diff --git a/wpimath/src/test/native/cpp/geometry/proto/Rotation2dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Rotation2dProtoTest.cpp index 4a10988ab7..7b6aacaf91 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Rotation2dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Rotation2dProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/geometry/Rotation2d.h" @@ -11,16 +11,15 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const Rotation2d kExpectedData = Rotation2d{1.91_rad}; } // namespace TEST(Rotation2dProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Rotation2d unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.Radians().value(), unpacked_data.Radians().value()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + EXPECT_EQ(kExpectedData.Radians().value(), unpacked_data->Radians().value()); } diff --git a/wpimath/src/test/native/cpp/geometry/proto/Rotation3dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Rotation3dProtoTest.cpp index 7850894b0a..83bfd89499 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Rotation3dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Rotation3dProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/geometry/Rotation3d.h" @@ -11,17 +11,17 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const Rotation3d kExpectedData = Rotation3d{Quaternion{2.29, 0.191, 0.191, 17.4}}; } // namespace TEST(Rotation3dProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Rotation3d unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.GetQuaternion(), unpacked_data.GetQuaternion()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.GetQuaternion(), unpacked_data->GetQuaternion()); } diff --git a/wpimath/src/test/native/cpp/geometry/proto/Transform2dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Transform2dProtoTest.cpp index 6225426f32..a11586f995 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Transform2dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Transform2dProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/geometry/Transform2d.h" @@ -11,18 +11,18 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const Transform2d kExpectedData = Transform2d{Translation2d{0.191_m, 2.2_m}, Rotation2d{4.4_rad}}; } // namespace TEST(Transform2dProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Transform2d unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.Translation(), unpacked_data.Translation()); - EXPECT_EQ(kExpectedData.Rotation(), unpacked_data.Rotation()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.Translation(), unpacked_data->Translation()); + EXPECT_EQ(kExpectedData.Rotation(), unpacked_data->Rotation()); } diff --git a/wpimath/src/test/native/cpp/geometry/proto/Transform3dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Transform3dProtoTest.cpp index c5731eea0d..ac05d6c12b 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Transform3dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Transform3dProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/geometry/Transform3d.h" @@ -11,19 +11,19 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const Transform3d kExpectedData = Transform3d{Translation3d{0.3504_m, 22.9_m, 3.504_m}, Rotation3d{Quaternion{0.3504, 35.04, 2.29, 0.3504}}}; } // namespace TEST(Transform3dProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Transform3d unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.Translation(), unpacked_data.Translation()); - EXPECT_EQ(kExpectedData.Rotation(), unpacked_data.Rotation()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.Translation(), unpacked_data->Translation()); + EXPECT_EQ(kExpectedData.Rotation(), unpacked_data->Rotation()); } diff --git a/wpimath/src/test/native/cpp/geometry/proto/Translation2dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Translation2dProtoTest.cpp index 37ec61b3b1..ed6c1ecdef 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Translation2dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Translation2dProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/geometry/Translation2d.h" @@ -11,17 +11,16 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const Translation2d kExpectedData = Translation2d{3.504_m, 22.9_m}; } // namespace TEST(Translation2dProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Translation2d unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.X().value(), unpacked_data.X().value()); - EXPECT_EQ(kExpectedData.Y().value(), unpacked_data.Y().value()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + EXPECT_EQ(kExpectedData.X().value(), unpacked_data->X().value()); + EXPECT_EQ(kExpectedData.Y().value(), unpacked_data->Y().value()); } diff --git a/wpimath/src/test/native/cpp/geometry/proto/Translation3dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Translation3dProtoTest.cpp index 732b1a62af..ba01a74de9 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Translation3dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Translation3dProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/geometry/Translation3d.h" @@ -11,18 +11,18 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const Translation3d kExpectedData = Translation3d{35.04_m, 22.9_m, 3.504_m}; } // namespace TEST(Translation3dProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Translation3d unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.X(), unpacked_data.X()); - EXPECT_EQ(kExpectedData.Y(), unpacked_data.Y()); - EXPECT_EQ(kExpectedData.Z(), unpacked_data.Z()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.X(), unpacked_data->X()); + EXPECT_EQ(kExpectedData.Y(), unpacked_data->Y()); + EXPECT_EQ(kExpectedData.Z(), unpacked_data->Z()); } diff --git a/wpimath/src/test/native/cpp/geometry/proto/Twist2dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Twist2dProtoTest.cpp index 305d3297d8..91d7b06791 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Twist2dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Twist2dProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/geometry/Twist2d.h" @@ -11,18 +11,18 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const Twist2d kExpectedData = Twist2d{2.29_m, 35.04_m, 35.04_rad}; } // namespace TEST(Twist2dProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Twist2d unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.dx.value(), unpacked_data.dx.value()); - EXPECT_EQ(kExpectedData.dy.value(), unpacked_data.dy.value()); - EXPECT_EQ(kExpectedData.dtheta.value(), unpacked_data.dtheta.value()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.dx.value(), unpacked_data->dx.value()); + EXPECT_EQ(kExpectedData.dy.value(), unpacked_data->dy.value()); + EXPECT_EQ(kExpectedData.dtheta.value(), unpacked_data->dtheta.value()); } diff --git a/wpimath/src/test/native/cpp/geometry/proto/Twist3dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Twist3dProtoTest.cpp index 9c454840a0..d2ee74cce9 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Twist3dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Twist3dProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/geometry/Twist3d.h" @@ -11,22 +11,22 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const Twist3d kExpectedData = Twist3d{1.1_m, 2.29_m, 35.04_m, 0.174_rad, 19.1_rad, 4.4_rad}; } // namespace TEST(Twist3dProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Twist3d unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.dx.value(), unpacked_data.dx.value()); - EXPECT_EQ(kExpectedData.dy.value(), unpacked_data.dy.value()); - EXPECT_EQ(kExpectedData.dz.value(), unpacked_data.dz.value()); - EXPECT_EQ(kExpectedData.rx.value(), unpacked_data.rx.value()); - EXPECT_EQ(kExpectedData.ry.value(), unpacked_data.ry.value()); - EXPECT_EQ(kExpectedData.rz.value(), unpacked_data.rz.value()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.dx.value(), unpacked_data->dx.value()); + EXPECT_EQ(kExpectedData.dy.value(), unpacked_data->dy.value()); + EXPECT_EQ(kExpectedData.dz.value(), unpacked_data->dz.value()); + EXPECT_EQ(kExpectedData.rx.value(), unpacked_data->rx.value()); + EXPECT_EQ(kExpectedData.ry.value(), unpacked_data->ry.value()); + EXPECT_EQ(kExpectedData.rz.value(), unpacked_data->rz.value()); } diff --git a/wpimath/src/test/native/cpp/kinematics/proto/ChassisSpeedsProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/ChassisSpeedsProtoTest.cpp index 9d91a5b2ff..008c86b610 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/ChassisSpeedsProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/ChassisSpeedsProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/kinematics/ChassisSpeeds.h" @@ -11,19 +11,19 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const ChassisSpeeds kExpectedData = ChassisSpeeds{2.29_mps, 2.2_mps, 0.3504_rad_per_s}; } // namespace TEST(ChassisSpeedsProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - ChassisSpeeds unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.vx.value(), unpacked_data.vx.value()); - EXPECT_EQ(kExpectedData.vy.value(), unpacked_data.vy.value()); - EXPECT_EQ(kExpectedData.omega.value(), unpacked_data.omega.value()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.vx.value(), unpacked_data->vx.value()); + EXPECT_EQ(kExpectedData.vy.value(), unpacked_data->vy.value()); + EXPECT_EQ(kExpectedData.omega.value(), unpacked_data->omega.value()); } diff --git a/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveKinematicsProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveKinematicsProtoTest.cpp index 47ed61fea6..5c9b7507c7 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveKinematicsProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveKinematicsProtoTest.cpp @@ -4,6 +4,7 @@ #include #include +#include #include "frc/kinematics/DifferentialDriveKinematics.h" @@ -11,17 +12,18 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const DifferentialDriveKinematics kExpectedData = DifferentialDriveKinematics{1.74_m}; } // namespace TEST(DifferentialDriveKinematicsProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - DifferentialDriveKinematics unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.trackWidth.value(), unpacked_data.trackWidth.value()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.trackWidth.value(), + unpacked_data->trackWidth.value()); } diff --git a/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProtoTest.cpp index 35ac5aebce..b09317117a 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/kinematics/DifferentialDriveWheelSpeeds.h" @@ -11,18 +11,18 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const DifferentialDriveWheelSpeeds kExpectedData = DifferentialDriveWheelSpeeds{1.74_mps, 35.04_mps}; } // namespace TEST(DifferentialDriveWheelSpeedsProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - DifferentialDriveWheelSpeeds unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.left.value(), unpacked_data.left.value()); - EXPECT_EQ(kExpectedData.right.value(), unpacked_data.right.value()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.left.value(), unpacked_data->left.value()); + EXPECT_EQ(kExpectedData.right.value(), unpacked_data->right.value()); } diff --git a/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveKinematicsProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveKinematicsProtoTest.cpp index fd1b4d1526..c217cfe4d3 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveKinematicsProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveKinematicsProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/kinematics/MecanumDriveKinematics.h" @@ -11,21 +11,21 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const MecanumDriveKinematics kExpectedData = MecanumDriveKinematics{ Translation2d{19.1_m, 2.2_m}, Translation2d{35.04_m, 1.91_m}, Translation2d{1.74_m, 3.504_m}, Translation2d{3.504_m, 1.91_m}}; } // namespace TEST(MecanumDriveKinematicsProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - MecanumDriveKinematics unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.GetFrontLeft(), unpacked_data.GetFrontLeft()); - EXPECT_EQ(kExpectedData.GetFrontRight(), unpacked_data.GetFrontRight()); - EXPECT_EQ(kExpectedData.GetRearLeft(), unpacked_data.GetRearLeft()); - EXPECT_EQ(kExpectedData.GetRearRight(), unpacked_data.GetRearRight()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.GetFrontLeft(), unpacked_data->GetFrontLeft()); + EXPECT_EQ(kExpectedData.GetFrontRight(), unpacked_data->GetFrontRight()); + EXPECT_EQ(kExpectedData.GetRearLeft(), unpacked_data->GetRearLeft()); + EXPECT_EQ(kExpectedData.GetRearRight(), unpacked_data->GetRearRight()); } diff --git a/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProtoTest.cpp index fae1f0b33e..6cac10f2db 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/kinematics/MecanumDriveWheelPositions.h" @@ -11,20 +11,21 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const MecanumDriveWheelPositions kExpectedData = MecanumDriveWheelPositions{17.4_m, 2.29_m, 22.9_m, 1.74_m}; } // namespace TEST(MecanumDriveWheelPositionsProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - MecanumDriveWheelPositions unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.frontLeft.value(), unpacked_data.frontLeft.value()); - EXPECT_EQ(kExpectedData.frontRight.value(), unpacked_data.frontRight.value()); - EXPECT_EQ(kExpectedData.rearLeft.value(), unpacked_data.rearLeft.value()); - EXPECT_EQ(kExpectedData.rearRight.value(), unpacked_data.rearRight.value()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.frontLeft.value(), unpacked_data->frontLeft.value()); + EXPECT_EQ(kExpectedData.frontRight.value(), + unpacked_data->frontRight.value()); + EXPECT_EQ(kExpectedData.rearLeft.value(), unpacked_data->rearLeft.value()); + EXPECT_EQ(kExpectedData.rearRight.value(), unpacked_data->rearRight.value()); } diff --git a/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProtoTest.cpp index 26a98b4cb6..2744b24d4d 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/kinematics/MecanumDriveWheelSpeeds.h" @@ -11,20 +11,21 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const MecanumDriveWheelSpeeds kExpectedData = MecanumDriveWheelSpeeds{2.29_mps, 17.4_mps, 4.4_mps, 0.229_mps}; } // namespace TEST(MecanumDriveWheelSpeedsProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - MecanumDriveWheelSpeeds unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.frontLeft.value(), unpacked_data.frontLeft.value()); - EXPECT_EQ(kExpectedData.frontRight.value(), unpacked_data.frontRight.value()); - EXPECT_EQ(kExpectedData.rearLeft.value(), unpacked_data.rearLeft.value()); - EXPECT_EQ(kExpectedData.rearRight.value(), unpacked_data.rearRight.value()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.frontLeft.value(), unpacked_data->frontLeft.value()); + EXPECT_EQ(kExpectedData.frontRight.value(), + unpacked_data->frontRight.value()); + EXPECT_EQ(kExpectedData.rearLeft.value(), unpacked_data->rearLeft.value()); + EXPECT_EQ(kExpectedData.rearRight.value(), unpacked_data->rearRight.value()); } diff --git a/wpimath/src/test/native/cpp/kinematics/proto/SwerveModulePositionProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/SwerveModulePositionProtoTest.cpp index 4a3013e6f8..6cf9c06a69 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/SwerveModulePositionProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/SwerveModulePositionProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/kinematics/SwerveModulePosition.h" @@ -11,18 +11,18 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const SwerveModulePosition kExpectedData = SwerveModulePosition{3.504_m, Rotation2d{17.4_rad}}; } // namespace TEST(SwerveModulePositionProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - SwerveModulePosition unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.distance.value(), unpacked_data.distance.value()); - EXPECT_EQ(kExpectedData.angle, unpacked_data.angle); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.distance.value(), unpacked_data->distance.value()); + EXPECT_EQ(kExpectedData.angle, unpacked_data->angle); } diff --git a/wpimath/src/test/native/cpp/kinematics/proto/SwerveModuleStateProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/SwerveModuleStateProtoTest.cpp index c86152d93a..9fc3407335 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/SwerveModuleStateProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/SwerveModuleStateProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/kinematics/SwerveModuleState.h" @@ -11,18 +11,18 @@ using namespace frc; namespace { -using ProtoType = wpi::Protobuf; - const SwerveModuleState kExpectedData = SwerveModuleState{22.9_mps, Rotation2d{3.3_rad}}; } // namespace TEST(SwerveModuleStateProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - SwerveModuleState unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.speed.value(), unpacked_data.speed.value()); - EXPECT_EQ(kExpectedData.angle, unpacked_data.angle); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.speed.value(), unpacked_data->speed.value()); + EXPECT_EQ(kExpectedData.angle, unpacked_data->angle); } diff --git a/wpimath/src/test/native/cpp/system/plant/proto/DCMotorProtoTest.cpp b/wpimath/src/test/native/cpp/system/plant/proto/DCMotorProtoTest.cpp index 2c4a6747df..cb395f91fe 100644 --- a/wpimath/src/test/native/cpp/system/plant/proto/DCMotorProtoTest.cpp +++ b/wpimath/src/test/native/cpp/system/plant/proto/DCMotorProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/system/plant/DCMotor.h" @@ -15,21 +15,23 @@ inline constexpr DCMotor kExpectedData = DCMotor{1.91_V, 19.1_Nm, 1.74_A, 2.29_A, 2.2_rad_per_s, 2}; TEST(DCMotorProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; + + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); - DCMotor unpacked_data = ProtoType::Unpack(*proto); EXPECT_EQ(kExpectedData.nominalVoltage.value(), - unpacked_data.nominalVoltage.value()); + unpacked_data->nominalVoltage.value()); EXPECT_EQ(kExpectedData.stallTorque.value(), - unpacked_data.stallTorque.value()); + unpacked_data->stallTorque.value()); EXPECT_EQ(kExpectedData.stallCurrent.value(), - unpacked_data.stallCurrent.value()); + unpacked_data->stallCurrent.value()); EXPECT_EQ(kExpectedData.freeCurrent.value(), - unpacked_data.freeCurrent.value()); - EXPECT_EQ(kExpectedData.freeSpeed.value(), unpacked_data.freeSpeed.value()); - EXPECT_EQ(kExpectedData.R.value(), unpacked_data.R.value()); - EXPECT_EQ(kExpectedData.Kv.value(), unpacked_data.Kv.value()); - EXPECT_EQ(kExpectedData.Kt.value(), unpacked_data.Kt.value()); + unpacked_data->freeCurrent.value()); + EXPECT_EQ(kExpectedData.freeSpeed.value(), unpacked_data->freeSpeed.value()); + EXPECT_EQ(kExpectedData.R.value(), unpacked_data->R.value()); + EXPECT_EQ(kExpectedData.Kv.value(), unpacked_data->Kv.value()); + EXPECT_EQ(kExpectedData.Kt.value(), unpacked_data->Kt.value()); } diff --git a/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryProtoTest.cpp b/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryProtoTest.cpp index eb60c9dd01..2a5c46cfbc 100644 --- a/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryProtoTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/trajectory/Trajectory.h" @@ -26,10 +26,11 @@ const Trajectory kExpectedData = Trajectory{std::vector{ } // namespace TEST(TrajectoryProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Trajectory unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.States(), unpacked_data.States()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + EXPECT_EQ(kExpectedData.States(), unpacked_data->States()); } diff --git a/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryStateProtoTest.cpp b/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryStateProtoTest.cpp index 4f3e42c097..4b2529c9ea 100644 --- a/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryStateProtoTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryStateProtoTest.cpp @@ -2,8 +2,8 @@ // Open Source Software; you can modify and/or share it under the terms of // the WPILib BSD license file in the root directory of this project. -#include #include +#include #include "frc/trajectory/Trajectory.h" @@ -20,15 +20,17 @@ const Trajectory::State kExpectedData = Trajectory::State{ } // namespace TEST(TrajectoryStateProtoTest, Roundtrip) { - google::protobuf::Arena arena; - google::protobuf::Message* proto = ProtoType::New(&arena); - ProtoType::Pack(proto, kExpectedData); + wpi::ProtobufMessage message; + wpi::SmallVector buf; - Trajectory::State unpacked_data = ProtoType::Unpack(*proto); - EXPECT_EQ(kExpectedData.t.value(), unpacked_data.t.value()); - EXPECT_EQ(kExpectedData.velocity.value(), unpacked_data.velocity.value()); + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + EXPECT_EQ(kExpectedData.t.value(), unpacked_data->t.value()); + EXPECT_EQ(kExpectedData.velocity.value(), unpacked_data->velocity.value()); EXPECT_EQ(kExpectedData.acceleration.value(), - unpacked_data.acceleration.value()); - EXPECT_EQ(kExpectedData.pose, unpacked_data.pose); - EXPECT_EQ(kExpectedData.curvature.value(), unpacked_data.curvature.value()); + unpacked_data->acceleration.value()); + EXPECT_EQ(kExpectedData.pose, unpacked_data->pose); + EXPECT_EQ(kExpectedData.curvature.value(), unpacked_data->curvature.value()); } diff --git a/wpiutil/.styleguide b/wpiutil/.styleguide index 7f1dff125f..5b2fd08555 100644 --- a/wpiutil/.styleguide +++ b/wpiutil/.styleguide @@ -28,6 +28,7 @@ generatedFileExclude { src/test/native/cpp/llvm/ src/test/native/cpp/span/ src/test/native/cpp/json/ + src/generated/test/native/cpp } licenseUpdateExclude { diff --git a/wpiutil/BUILD.bazel b/wpiutil/BUILD.bazel index d23d218ce4..e92f58c99d 100644 --- a/wpiutil/BUILD.bazel +++ b/wpiutil/BUILD.bazel @@ -124,6 +124,23 @@ filegroup( visibility = ["//wpiutil:__subpackages__"], ) +cc_library( + name = "nanopb-headers", + hdrs = glob([ + "src/main/native/thirdparty/nanopb/include/**/*.h", + "src/main/native/thirdparty/nanopb/include/**/*.inc", + ]), + includes = ["src/main/native/thirdparty/nanopb/include"], + strip_include_prefix = "src/main/native/thirdparty/nanopb/include", + visibility = ["//wpiutil:__subpackages__"], +) + +filegroup( + name = "nanopb-srcs", + srcs = glob(["src/main/native/thirdparty/nanopb/src/**"]), + visibility = ["//wpiutil:__subpackages__"], +) + cc_library( name = "sigslot-headers", hdrs = glob([ @@ -165,6 +182,7 @@ cc_library( ":mpack-srcs", ":native-srcs", ":protobuf-srcs", + ":nanopb-srcs", ], hdrs = glob(["src/main/native/include/**/*"]), includes = ["src/main/native/include"], @@ -180,6 +198,7 @@ cc_library( ":memory-headers", ":mpack-headers", ":protobuf-headers", + ":nanopb-headers", ":sigslot-headers", ] + select({ "@rules_bzlmodrio_toolchains//constraints/is_roborio:roborio": ["@bzlmodrio-ni//libraries/cpp/ni:shared"], @@ -206,13 +225,25 @@ cc_library( visibility = ["//visibility:public"], ) +cc_library( + name = "nanopb-test-headers", + hdrs = glob(["src/generated/test/native/cpp/*.h"]), + includes = ["src/generated/test/native/cpp"], + strip_include_prefix = "src/generated/test/native/cpp", + visibility = ["//wpiutil:__subpackages__"], +) + cc_test( name = "wpiutil-cpp-test", size = "small", - srcs = glob(["src/test/native/cpp/**"]), + srcs = glob([ + "src/test/native/cpp/**", + "src/generated/test/native/cpp/*", + ]), linkstatic = True, tags = ["no-tsan"], # TODO(pj.reiniger) Find problem deps = [ + ":nanopb-test-headers", ":wpiutil.static", ":wpiutil-testlib", "//thirdparty/googletest:googletest.static", diff --git a/wpiutil/CMakeLists.txt b/wpiutil/CMakeLists.txt index 139b6bc7b4..0c41be53db 100644 --- a/wpiutil/CMakeLists.txt +++ b/wpiutil/CMakeLists.txt @@ -119,6 +119,7 @@ file( src/main/native/thirdparty/json/cpp/*.cpp src/main/native/thirdparty/llvm/cpp/*.cpp src/main/native/thirdparty/mpack/src/*.cpp + src/main/native/thirdparty/nanopb/src/*.cpp ) list(REMOVE_ITEM wpiutil_native_src ${wpiutil_jni_src}) if(NOT WITH_PROTOBUF) @@ -200,6 +201,7 @@ install( src/main/native/thirdparty/llvm/include/ src/main/native/thirdparty/memory/include/ src/main/native/thirdparty/mpack/include/ + src/main/native/thirdparty/nanopb/include/ src/main/native/thirdparty/sigslot/include/ DESTINATION "${include_dest}/wpiutil" ) @@ -213,6 +215,7 @@ target_include_directories( $ $ $ + $ $ $ ) @@ -241,6 +244,9 @@ if(WITH_TESTS) target_include_directories(wpiutil_testlib INTERFACE src/test/native/include) wpilib_add_test(wpiutil src/test/native/cpp) + target_include_directories(wpiutil_test PRIVATE src/generated/test/native/cpp) + file(GLOB_RECURSE wpiutil_nanopb_test_src src/generated/test/native/cpp/*.cpp) + target_sources(wpiutil_test PRIVATE ${wpiutil_nanopb_test_src}) target_link_libraries(wpiutil_test wpiutil googletest wpiutil_testlib) if(MSVC) target_compile_options(wpiutil_test PRIVATE /utf-8) diff --git a/wpiutil/build.gradle b/wpiutil/build.gradle index 4958fe634b..92052919ad 100644 --- a/wpiutil/build.gradle +++ b/wpiutil/build.gradle @@ -1,6 +1,7 @@ apply from: "${rootDir}/shared/resources.gradle" ext { + skipproto = true noWpiutil = true skipJniSymbols = [ 'Java_edu_wpi_first_util_CombinedRuntimeLoader_setDllDirectory' @@ -53,6 +54,15 @@ ext { srcDirs 'src/main/native/thirdparty/mpack/include' } } + nanopbCpp(CppSourceSet) { + source { + srcDirs 'src/main/native/thirdparty/nanopb/src' + include '*.cpp' + } + exportedHeaders { + srcDirs 'src/main/native/thirdparty/nanopb/include' + } + } sigslotCpp(CppSourceSet) { source { srcDirs 'src/main/native/thirdparty/sigslot/src' @@ -100,7 +110,7 @@ ext { include '**/*.cpp' } exportedHeaders { - srcDirs 'src/main/native/include', 'src/main/native/cpp', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/fmtlib/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/mpack/include' + srcDirs 'src/main/native/include', 'src/main/native/cpp', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/fmtlib/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/mpack/include', 'src/main/native/thirdparty/nanopb/include' include '**/*.h' } } @@ -114,7 +124,7 @@ ext { include '**/*.cpp' } exportedHeaders { - srcDirs 'src/main/native/include', 'src/main/native/cpp', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/fmtlib/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/json/include', 'src/main/native/thirdparty/mpack/include' + srcDirs 'src/main/native/include', 'src/main/native/cpp', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/fmtlib/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/json/include', 'src/main/native/thirdparty/mpack/include', 'src/main/native/thirdparty/nanopb/include' include '**/*.h' } } @@ -127,7 +137,7 @@ ext { include '**/*.cpp' } exportedHeaders { - srcDirs 'src/main/native/include', 'src/main/native/cpp', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/fmtlib/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/json/include', 'src/main/native/thirdparty/mpack/include' + srcDirs 'src/main/native/include', 'src/main/native/cpp', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/fmtlib/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/json/include', 'src/main/native/thirdparty/mpack/include', 'src/main/native/thirdparty/nanopb/include' include '**/*.h' } } @@ -140,7 +150,7 @@ ext { include '**/*.cpp' } exportedHeaders { - srcDirs 'src/main/native/include', 'src/main/native/cpp', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/fmtlib/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/json/include', 'src/main/native/thirdparty/mpack/include' + srcDirs 'src/main/native/include', 'src/main/native/cpp', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/fmtlib/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/json/include', 'src/main/native/thirdparty/mpack/include', 'src/main/native/thirdparty/nanopb/include' include '**/*.h' } } @@ -174,6 +184,7 @@ cppHeadersZip { 'src/main/native/thirdparty/json/include', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/mpack/include', + 'src/main/native/thirdparty/nanopb/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/memory/include', 'src/main/native/thirdparty/protobuf/include' @@ -203,6 +214,9 @@ cppSourcesZip { from('src/main/native/thirdparty/mpack/src') { into '/' } + from('src/main/native/thirdparty/nanopb/src') { + into '/' + } from('src/main/native/thirdparty/protobuf/src') { into '/' } @@ -216,7 +230,27 @@ model { all { it.sources.each { it.exportedHeaders { - srcDirs 'src/main/native/include', 'src/main/native/thirdparty/argparse/include/', 'src/main/native/thirdparty/expected/include', 'src/main/native/thirdparty/fmtlib/include', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/json/include', 'src/main/native/thirdparty/memory/include', 'src/main/native/thirdparty/mpack/include', 'src/main/native/thirdparty/protobuf/include' + srcDirs 'src/main/native/include', 'src/main/native/thirdparty/argparse/include/', 'src/main/native/thirdparty/expected/include', 'src/main/native/thirdparty/fmtlib/include', 'src/main/native/thirdparty/llvm/include', 'src/main/native/thirdparty/sigslot/include', 'src/main/native/thirdparty/json/include', 'src/main/native/thirdparty/memory/include', 'src/main/native/thirdparty/mpack/include', 'src/main/native/thirdparty/protobuf/include', 'src/main/native/thirdparty/nanopb/include' + } + } + } + } + testSuites { + withType(GoogleTestTestSuiteSpec) { + sources { + protobufGenCpp(CppSourceSet) { + source { + srcDirs 'src/generated/test/native/cpp' + include '**/*.cpp' + } + exportedHeaders { + srcDirs 'src/generated/test/native/cpp' + } + } + } + it.sources.each { + it.exportedHeaders { + srcDirs 'src/test/native/include', 'src/generated/test/native/cpp' } } } diff --git a/wpiutil/generate_nanopb.py b/wpiutil/generate_nanopb.py new file mode 100755 index 0000000000..f514b5d2b6 --- /dev/null +++ b/wpiutil/generate_nanopb.py @@ -0,0 +1,88 @@ +#!/usr/bin/env python3 + +# Copyright (c) FIRST and other WPILib contributors. +# Open Source Software; you can modify and/or share it under the terms of +# the WPILib BSD license file in the root directory of this project. + +import argparse +import os +import shutil +import subprocess +import sys +from pathlib import Path + + +def generate_nanopb(nanopb: Path, output_directory: Path, proto_dir: Path): + shutil.rmtree(output_directory.absolute(), ignore_errors=True) + os.makedirs(output_directory.absolute()) + + proto_files = proto_dir.glob("*.proto") + for path in proto_files: + absolute_filename = path.absolute() + subprocess.run( + [ + sys.executable, + nanopb, + f"-I{absolute_filename.parent}", + f"-D{output_directory.absolute()}", + "-S.cpp", + "-e.npb", + absolute_filename, + ], + check=True, + ) + java_files = (output_directory).glob("*") + for java_file in java_files: + with (java_file).open(encoding="utf-8") as f: + content = f.read() + + java_file.write_text( + "// Copyright (c) FIRST and other WPILib contributors.\n// Open Source Software; you can modify and/or share it under the terms of\n// the WPILib BSD license file in the root directory of this project.\n" + + content, + encoding="utf-8", + newline="\n", + ) + + +def main(): + script_path = Path(__file__).resolve() + dirname = script_path.parent + + root_path = dirname.parent + nanopb_path = os.path.join( + root_path, + "wpiutil", + "src", + "main", + "native", + "thirdparty", + "nanopb", + "generator", + "nanopb_generator.py", + ) + + parser = argparse.ArgumentParser() + parser.add_argument( + "--nanopb", + help="Nanopb generator command", + default=nanopb_path, + ) + parser.add_argument( + "--output_directory", + help="Optional. If set, will output the generated files to this directory, otherwise it will use a path relative to the script", + default=dirname / "src/generated/test/native/cpp", + type=Path, + ) + parser.add_argument( + "--proto_directory", + help="Optional. If set, will use this directory to glob for protobuf files", + default=dirname / "src/test/proto", + type=Path, + ) + args = parser.parse_args() + + generate_nanopb(args.nanopb, args.output_directory, args.proto_directory) + + +if __name__ == "__main__": + main() diff --git a/wpiutil/src/generated/test/native/cpp/wpiutil.npb.cpp b/wpiutil/src/generated/test/native/cpp/wpiutil.npb.cpp new file mode 100644 index 0000000000..d2f52da5da --- /dev/null +++ b/wpiutil/src/generated/test/native/cpp/wpiutil.npb.cpp @@ -0,0 +1,584 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb constant definitions */ +/* Generated by nanopb-0.4.9 */ + +#include "wpiutil.npb.h" +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +#include +#include +static const uint8_t file_descriptor[] { +0x0a,0x0d,0x77,0x70,0x69,0x75,0x74,0x69,0x6c,0x2e, +0x70,0x72,0x6f,0x74,0x6f,0x12,0x09,0x77,0x70,0x69, +0x2e,0x70,0x72,0x6f,0x74,0x6f,0x22,0x22,0x0a,0x0e, +0x54,0x65,0x73,0x74,0x50,0x72,0x6f,0x74,0x6f,0x49, +0x6e,0x6e,0x65,0x72,0x12,0x10,0x0a,0x03,0x6d,0x73, +0x67,0x18,0x01,0x20,0x01,0x28,0x09,0x52,0x03,0x6d, +0x73,0x67,0x22,0xa6,0x04,0x0a,0x09,0x54,0x65,0x73, +0x74,0x50,0x72,0x6f,0x74,0x6f,0x12,0x1d,0x0a,0x0a, +0x64,0x6f,0x75,0x62,0x6c,0x65,0x5f,0x6d,0x73,0x67, +0x18,0x01,0x20,0x01,0x28,0x01,0x52,0x09,0x64,0x6f, +0x75,0x62,0x6c,0x65,0x4d,0x73,0x67,0x12,0x1b,0x0a, +0x09,0x66,0x6c,0x6f,0x61,0x74,0x5f,0x6d,0x73,0x67, +0x18,0x02,0x20,0x01,0x28,0x02,0x52,0x08,0x66,0x6c, +0x6f,0x61,0x74,0x4d,0x73,0x67,0x12,0x1b,0x0a,0x09, +0x69,0x6e,0x74,0x33,0x32,0x5f,0x6d,0x73,0x67,0x18, +0x03,0x20,0x01,0x28,0x05,0x52,0x08,0x69,0x6e,0x74, +0x33,0x32,0x4d,0x73,0x67,0x12,0x1b,0x0a,0x09,0x69, +0x6e,0x74,0x36,0x34,0x5f,0x6d,0x73,0x67,0x18,0x04, +0x20,0x01,0x28,0x03,0x52,0x08,0x69,0x6e,0x74,0x36, +0x34,0x4d,0x73,0x67,0x12,0x1d,0x0a,0x0a,0x75,0x69, +0x6e,0x74,0x33,0x32,0x5f,0x6d,0x73,0x67,0x18,0x05, +0x20,0x01,0x28,0x0d,0x52,0x09,0x75,0x69,0x6e,0x74, +0x33,0x32,0x4d,0x73,0x67,0x12,0x1d,0x0a,0x0a,0x75, +0x69,0x6e,0x74,0x36,0x34,0x5f,0x6d,0x73,0x67,0x18, +0x06,0x20,0x01,0x28,0x04,0x52,0x09,0x75,0x69,0x6e, +0x74,0x36,0x34,0x4d,0x73,0x67,0x12,0x1d,0x0a,0x0a, +0x73,0x69,0x6e,0x74,0x33,0x32,0x5f,0x6d,0x73,0x67, +0x18,0x07,0x20,0x01,0x28,0x11,0x52,0x09,0x73,0x69, +0x6e,0x74,0x33,0x32,0x4d,0x73,0x67,0x12,0x1d,0x0a, +0x0a,0x73,0x69,0x6e,0x74,0x36,0x34,0x5f,0x6d,0x73, +0x67,0x18,0x08,0x20,0x01,0x28,0x12,0x52,0x09,0x73, +0x69,0x6e,0x74,0x36,0x34,0x4d,0x73,0x67,0x12,0x1f, +0x0a,0x0b,0x66,0x69,0x78,0x65,0x64,0x33,0x32,0x5f, +0x6d,0x73,0x67,0x18,0x09,0x20,0x01,0x28,0x07,0x52, +0x0a,0x66,0x69,0x78,0x65,0x64,0x33,0x32,0x4d,0x73, +0x67,0x12,0x1f,0x0a,0x0b,0x66,0x69,0x78,0x65,0x64, +0x36,0x34,0x5f,0x6d,0x73,0x67,0x18,0x0a,0x20,0x01, +0x28,0x06,0x52,0x0a,0x66,0x69,0x78,0x65,0x64,0x36, +0x34,0x4d,0x73,0x67,0x12,0x21,0x0a,0x0c,0x73,0x66, +0x69,0x78,0x65,0x64,0x33,0x32,0x5f,0x6d,0x73,0x67, +0x18,0x0b,0x20,0x01,0x28,0x0f,0x52,0x0b,0x73,0x66, +0x69,0x78,0x65,0x64,0x33,0x32,0x4d,0x73,0x67,0x12, +0x21,0x0a,0x0c,0x73,0x66,0x69,0x78,0x65,0x64,0x36, +0x34,0x5f,0x6d,0x73,0x67,0x18,0x0c,0x20,0x01,0x28, +0x10,0x52,0x0b,0x73,0x66,0x69,0x78,0x65,0x64,0x36, +0x34,0x4d,0x73,0x67,0x12,0x19,0x0a,0x08,0x62,0x6f, +0x6f,0x6c,0x5f,0x6d,0x73,0x67,0x18,0x0d,0x20,0x01, +0x28,0x08,0x52,0x07,0x62,0x6f,0x6f,0x6c,0x4d,0x73, +0x67,0x12,0x1d,0x0a,0x0a,0x73,0x74,0x72,0x69,0x6e, +0x67,0x5f,0x6d,0x73,0x67,0x18,0x0e,0x20,0x01,0x28, +0x09,0x52,0x09,0x73,0x74,0x72,0x69,0x6e,0x67,0x4d, +0x73,0x67,0x12,0x1b,0x0a,0x09,0x62,0x79,0x74,0x65, +0x73,0x5f,0x6d,0x73,0x67,0x18,0x0f,0x20,0x01,0x28, +0x0c,0x52,0x08,0x62,0x79,0x74,0x65,0x73,0x4d,0x73, +0x67,0x12,0x48,0x0a,0x12,0x54,0x65,0x73,0x74,0x50, +0x72,0x6f,0x74,0x6f,0x49,0x6e,0x6e,0x65,0x72,0x5f, +0x6d,0x73,0x67,0x18,0x10,0x20,0x01,0x28,0x0b,0x32, +0x19,0x2e,0x77,0x70,0x69,0x2e,0x70,0x72,0x6f,0x74, +0x6f,0x2e,0x54,0x65,0x73,0x74,0x50,0x72,0x6f,0x74, +0x6f,0x49,0x6e,0x6e,0x65,0x72,0x52,0x11,0x54,0x65, +0x73,0x74,0x50,0x72,0x6f,0x74,0x6f,0x49,0x6e,0x6e, +0x65,0x72,0x4d,0x73,0x67,0x22,0xf6,0x06,0x0a,0x11, +0x4f,0x70,0x74,0x69,0x6f,0x6e,0x61,0x6c,0x54,0x65, +0x73,0x74,0x50,0x72,0x6f,0x74,0x6f,0x12,0x22,0x0a, +0x0a,0x64,0x6f,0x75,0x62,0x6c,0x65,0x5f,0x6d,0x73, +0x67,0x18,0x01,0x20,0x01,0x28,0x01,0x48,0x00,0x52, +0x09,0x64,0x6f,0x75,0x62,0x6c,0x65,0x4d,0x73,0x67, +0x88,0x01,0x01,0x12,0x20,0x0a,0x09,0x66,0x6c,0x6f, +0x61,0x74,0x5f,0x6d,0x73,0x67,0x18,0x02,0x20,0x01, +0x28,0x02,0x48,0x01,0x52,0x08,0x66,0x6c,0x6f,0x61, +0x74,0x4d,0x73,0x67,0x88,0x01,0x01,0x12,0x20,0x0a, +0x09,0x69,0x6e,0x74,0x33,0x32,0x5f,0x6d,0x73,0x67, +0x18,0x03,0x20,0x01,0x28,0x05,0x48,0x02,0x52,0x08, +0x69,0x6e,0x74,0x33,0x32,0x4d,0x73,0x67,0x88,0x01, +0x01,0x12,0x20,0x0a,0x09,0x69,0x6e,0x74,0x36,0x34, +0x5f,0x6d,0x73,0x67,0x18,0x04,0x20,0x01,0x28,0x03, +0x48,0x03,0x52,0x08,0x69,0x6e,0x74,0x36,0x34,0x4d, +0x73,0x67,0x88,0x01,0x01,0x12,0x22,0x0a,0x0a,0x75, +0x69,0x6e,0x74,0x33,0x32,0x5f,0x6d,0x73,0x67,0x18, +0x05,0x20,0x01,0x28,0x0d,0x48,0x04,0x52,0x09,0x75, +0x69,0x6e,0x74,0x33,0x32,0x4d,0x73,0x67,0x88,0x01, +0x01,0x12,0x22,0x0a,0x0a,0x75,0x69,0x6e,0x74,0x36, +0x34,0x5f,0x6d,0x73,0x67,0x18,0x06,0x20,0x01,0x28, +0x04,0x48,0x05,0x52,0x09,0x75,0x69,0x6e,0x74,0x36, +0x34,0x4d,0x73,0x67,0x88,0x01,0x01,0x12,0x22,0x0a, +0x0a,0x73,0x69,0x6e,0x74,0x33,0x32,0x5f,0x6d,0x73, +0x67,0x18,0x07,0x20,0x01,0x28,0x11,0x48,0x06,0x52, +0x09,0x73,0x69,0x6e,0x74,0x33,0x32,0x4d,0x73,0x67, +0x88,0x01,0x01,0x12,0x22,0x0a,0x0a,0x73,0x69,0x6e, +0x74,0x36,0x34,0x5f,0x6d,0x73,0x67,0x18,0x08,0x20, +0x01,0x28,0x12,0x48,0x07,0x52,0x09,0x73,0x69,0x6e, +0x74,0x36,0x34,0x4d,0x73,0x67,0x88,0x01,0x01,0x12, +0x24,0x0a,0x0b,0x66,0x69,0x78,0x65,0x64,0x33,0x32, +0x5f,0x6d,0x73,0x67,0x18,0x09,0x20,0x01,0x28,0x07, +0x48,0x08,0x52,0x0a,0x66,0x69,0x78,0x65,0x64,0x33, +0x32,0x4d,0x73,0x67,0x88,0x01,0x01,0x12,0x24,0x0a, +0x0b,0x66,0x69,0x78,0x65,0x64,0x36,0x34,0x5f,0x6d, +0x73,0x67,0x18,0x0a,0x20,0x01,0x28,0x06,0x48,0x09, +0x52,0x0a,0x66,0x69,0x78,0x65,0x64,0x36,0x34,0x4d, +0x73,0x67,0x88,0x01,0x01,0x12,0x26,0x0a,0x0c,0x73, +0x66,0x69,0x78,0x65,0x64,0x33,0x32,0x5f,0x6d,0x73, +0x67,0x18,0x0b,0x20,0x01,0x28,0x0f,0x48,0x0a,0x52, +0x0b,0x73,0x66,0x69,0x78,0x65,0x64,0x33,0x32,0x4d, +0x73,0x67,0x88,0x01,0x01,0x12,0x26,0x0a,0x0c,0x73, +0x66,0x69,0x78,0x65,0x64,0x36,0x34,0x5f,0x6d,0x73, +0x67,0x18,0x0c,0x20,0x01,0x28,0x10,0x48,0x0b,0x52, +0x0b,0x73,0x66,0x69,0x78,0x65,0x64,0x36,0x34,0x4d, +0x73,0x67,0x88,0x01,0x01,0x12,0x1e,0x0a,0x08,0x62, +0x6f,0x6f,0x6c,0x5f,0x6d,0x73,0x67,0x18,0x0d,0x20, +0x01,0x28,0x08,0x48,0x0c,0x52,0x07,0x62,0x6f,0x6f, +0x6c,0x4d,0x73,0x67,0x88,0x01,0x01,0x12,0x22,0x0a, +0x0a,0x73,0x74,0x72,0x69,0x6e,0x67,0x5f,0x6d,0x73, +0x67,0x18,0x0e,0x20,0x01,0x28,0x09,0x48,0x0d,0x52, +0x09,0x73,0x74,0x72,0x69,0x6e,0x67,0x4d,0x73,0x67, +0x88,0x01,0x01,0x12,0x20,0x0a,0x09,0x62,0x79,0x74, +0x65,0x73,0x5f,0x6d,0x73,0x67,0x18,0x0f,0x20,0x01, +0x28,0x0c,0x48,0x0e,0x52,0x08,0x62,0x79,0x74,0x65, +0x73,0x4d,0x73,0x67,0x88,0x01,0x01,0x12,0x4d,0x0a, +0x12,0x54,0x65,0x73,0x74,0x50,0x72,0x6f,0x74,0x6f, +0x49,0x6e,0x6e,0x65,0x72,0x5f,0x6d,0x73,0x67,0x18, +0x10,0x20,0x01,0x28,0x0b,0x32,0x19,0x2e,0x77,0x70, +0x69,0x2e,0x70,0x72,0x6f,0x74,0x6f,0x2e,0x54,0x65, +0x73,0x74,0x50,0x72,0x6f,0x74,0x6f,0x49,0x6e,0x6e, +0x65,0x72,0x48,0x0f,0x52,0x11,0x54,0x65,0x73,0x74, +0x50,0x72,0x6f,0x74,0x6f,0x49,0x6e,0x6e,0x65,0x72, +0x4d,0x73,0x67,0x88,0x01,0x01,0x42,0x0d,0x0a,0x0b, +0x5f,0x64,0x6f,0x75,0x62,0x6c,0x65,0x5f,0x6d,0x73, +0x67,0x42,0x0c,0x0a,0x0a,0x5f,0x66,0x6c,0x6f,0x61, +0x74,0x5f,0x6d,0x73,0x67,0x42,0x0c,0x0a,0x0a,0x5f, +0x69,0x6e,0x74,0x33,0x32,0x5f,0x6d,0x73,0x67,0x42, +0x0c,0x0a,0x0a,0x5f,0x69,0x6e,0x74,0x36,0x34,0x5f, +0x6d,0x73,0x67,0x42,0x0d,0x0a,0x0b,0x5f,0x75,0x69, +0x6e,0x74,0x33,0x32,0x5f,0x6d,0x73,0x67,0x42,0x0d, +0x0a,0x0b,0x5f,0x75,0x69,0x6e,0x74,0x36,0x34,0x5f, +0x6d,0x73,0x67,0x42,0x0d,0x0a,0x0b,0x5f,0x73,0x69, +0x6e,0x74,0x33,0x32,0x5f,0x6d,0x73,0x67,0x42,0x0d, +0x0a,0x0b,0x5f,0x73,0x69,0x6e,0x74,0x36,0x34,0x5f, +0x6d,0x73,0x67,0x42,0x0e,0x0a,0x0c,0x5f,0x66,0x69, +0x78,0x65,0x64,0x33,0x32,0x5f,0x6d,0x73,0x67,0x42, +0x0e,0x0a,0x0c,0x5f,0x66,0x69,0x78,0x65,0x64,0x36, +0x34,0x5f,0x6d,0x73,0x67,0x42,0x0f,0x0a,0x0d,0x5f, +0x73,0x66,0x69,0x78,0x65,0x64,0x33,0x32,0x5f,0x6d, +0x73,0x67,0x42,0x0f,0x0a,0x0d,0x5f,0x73,0x66,0x69, +0x78,0x65,0x64,0x36,0x34,0x5f,0x6d,0x73,0x67,0x42, +0x0b,0x0a,0x09,0x5f,0x62,0x6f,0x6f,0x6c,0x5f,0x6d, +0x73,0x67,0x42,0x0d,0x0a,0x0b,0x5f,0x73,0x74,0x72, +0x69,0x6e,0x67,0x5f,0x6d,0x73,0x67,0x42,0x0c,0x0a, +0x0a,0x5f,0x62,0x79,0x74,0x65,0x73,0x5f,0x6d,0x73, +0x67,0x42,0x15,0x0a,0x13,0x5f,0x54,0x65,0x73,0x74, +0x50,0x72,0x6f,0x74,0x6f,0x49,0x6e,0x6e,0x65,0x72, +0x5f,0x6d,0x73,0x67,0x22,0xae,0x04,0x0a,0x11,0x52, +0x65,0x70,0x65,0x61,0x74,0x65,0x64,0x54,0x65,0x73, +0x74,0x50,0x72,0x6f,0x74,0x6f,0x12,0x1d,0x0a,0x0a, +0x64,0x6f,0x75,0x62,0x6c,0x65,0x5f,0x6d,0x73,0x67, +0x18,0x01,0x20,0x03,0x28,0x01,0x52,0x09,0x64,0x6f, +0x75,0x62,0x6c,0x65,0x4d,0x73,0x67,0x12,0x1b,0x0a, +0x09,0x66,0x6c,0x6f,0x61,0x74,0x5f,0x6d,0x73,0x67, +0x18,0x02,0x20,0x03,0x28,0x02,0x52,0x08,0x66,0x6c, +0x6f,0x61,0x74,0x4d,0x73,0x67,0x12,0x1b,0x0a,0x09, +0x69,0x6e,0x74,0x33,0x32,0x5f,0x6d,0x73,0x67,0x18, +0x03,0x20,0x03,0x28,0x05,0x52,0x08,0x69,0x6e,0x74, +0x33,0x32,0x4d,0x73,0x67,0x12,0x1b,0x0a,0x09,0x69, +0x6e,0x74,0x36,0x34,0x5f,0x6d,0x73,0x67,0x18,0x04, +0x20,0x03,0x28,0x03,0x52,0x08,0x69,0x6e,0x74,0x36, +0x34,0x4d,0x73,0x67,0x12,0x1d,0x0a,0x0a,0x75,0x69, +0x6e,0x74,0x33,0x32,0x5f,0x6d,0x73,0x67,0x18,0x05, +0x20,0x03,0x28,0x0d,0x52,0x09,0x75,0x69,0x6e,0x74, +0x33,0x32,0x4d,0x73,0x67,0x12,0x1d,0x0a,0x0a,0x75, +0x69,0x6e,0x74,0x36,0x34,0x5f,0x6d,0x73,0x67,0x18, +0x06,0x20,0x03,0x28,0x04,0x52,0x09,0x75,0x69,0x6e, +0x74,0x36,0x34,0x4d,0x73,0x67,0x12,0x1d,0x0a,0x0a, +0x73,0x69,0x6e,0x74,0x33,0x32,0x5f,0x6d,0x73,0x67, +0x18,0x07,0x20,0x03,0x28,0x11,0x52,0x09,0x73,0x69, +0x6e,0x74,0x33,0x32,0x4d,0x73,0x67,0x12,0x1d,0x0a, +0x0a,0x73,0x69,0x6e,0x74,0x36,0x34,0x5f,0x6d,0x73, +0x67,0x18,0x08,0x20,0x03,0x28,0x12,0x52,0x09,0x73, +0x69,0x6e,0x74,0x36,0x34,0x4d,0x73,0x67,0x12,0x1f, +0x0a,0x0b,0x66,0x69,0x78,0x65,0x64,0x33,0x32,0x5f, +0x6d,0x73,0x67,0x18,0x09,0x20,0x03,0x28,0x07,0x52, +0x0a,0x66,0x69,0x78,0x65,0x64,0x33,0x32,0x4d,0x73, +0x67,0x12,0x1f,0x0a,0x0b,0x66,0x69,0x78,0x65,0x64, +0x36,0x34,0x5f,0x6d,0x73,0x67,0x18,0x0a,0x20,0x03, +0x28,0x06,0x52,0x0a,0x66,0x69,0x78,0x65,0x64,0x36, +0x34,0x4d,0x73,0x67,0x12,0x21,0x0a,0x0c,0x73,0x66, +0x69,0x78,0x65,0x64,0x33,0x32,0x5f,0x6d,0x73,0x67, +0x18,0x0b,0x20,0x03,0x28,0x0f,0x52,0x0b,0x73,0x66, +0x69,0x78,0x65,0x64,0x33,0x32,0x4d,0x73,0x67,0x12, +0x21,0x0a,0x0c,0x73,0x66,0x69,0x78,0x65,0x64,0x36, +0x34,0x5f,0x6d,0x73,0x67,0x18,0x0c,0x20,0x03,0x28, +0x10,0x52,0x0b,0x73,0x66,0x69,0x78,0x65,0x64,0x36, +0x34,0x4d,0x73,0x67,0x12,0x19,0x0a,0x08,0x62,0x6f, +0x6f,0x6c,0x5f,0x6d,0x73,0x67,0x18,0x0d,0x20,0x03, +0x28,0x08,0x52,0x07,0x62,0x6f,0x6f,0x6c,0x4d,0x73, +0x67,0x12,0x1d,0x0a,0x0a,0x73,0x74,0x72,0x69,0x6e, +0x67,0x5f,0x6d,0x73,0x67,0x18,0x0e,0x20,0x03,0x28, +0x09,0x52,0x09,0x73,0x74,0x72,0x69,0x6e,0x67,0x4d, +0x73,0x67,0x12,0x1b,0x0a,0x09,0x62,0x79,0x74,0x65, +0x73,0x5f,0x6d,0x73,0x67,0x18,0x0f,0x20,0x03,0x28, +0x0c,0x52,0x08,0x62,0x79,0x74,0x65,0x73,0x4d,0x73, +0x67,0x12,0x48,0x0a,0x12,0x54,0x65,0x73,0x74,0x50, +0x72,0x6f,0x74,0x6f,0x49,0x6e,0x6e,0x65,0x72,0x5f, +0x6d,0x73,0x67,0x18,0x10,0x20,0x03,0x28,0x0b,0x32, +0x19,0x2e,0x77,0x70,0x69,0x2e,0x70,0x72,0x6f,0x74, +0x6f,0x2e,0x54,0x65,0x73,0x74,0x50,0x72,0x6f,0x74, +0x6f,0x49,0x6e,0x6e,0x65,0x72,0x52,0x11,0x54,0x65, +0x73,0x74,0x50,0x72,0x6f,0x74,0x6f,0x49,0x6e,0x6e, +0x65,0x72,0x4d,0x73,0x67,0x4a,0xc3,0x19,0x0a,0x06, +0x12,0x04,0x00,0x00,0x3f,0x01,0x0a,0x08,0x0a,0x01, +0x0c,0x12,0x03,0x00,0x00,0x12,0x0a,0x08,0x0a,0x01, +0x02,0x12,0x03,0x02,0x00,0x12,0x0a,0x0a,0x0a,0x02, +0x04,0x00,0x12,0x04,0x04,0x00,0x06,0x01,0x0a,0x0a, +0x0a,0x03,0x04,0x00,0x01,0x12,0x03,0x04,0x08,0x16, +0x0a,0x0b,0x0a,0x04,0x04,0x00,0x02,0x00,0x12,0x03, +0x05,0x02,0x11,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02, +0x00,0x05,0x12,0x03,0x05,0x02,0x08,0x0a,0x0c,0x0a, +0x05,0x04,0x00,0x02,0x00,0x01,0x12,0x03,0x05,0x09, +0x0c,0x0a,0x0c,0x0a,0x05,0x04,0x00,0x02,0x00,0x03, +0x12,0x03,0x05,0x0f,0x10,0x0a,0x0a,0x0a,0x02,0x04, +0x01,0x12,0x04,0x08,0x00,0x19,0x01,0x0a,0x0a,0x0a, +0x03,0x04,0x01,0x01,0x12,0x03,0x08,0x08,0x11,0x0a, +0x0b,0x0a,0x04,0x04,0x01,0x02,0x00,0x12,0x03,0x09, +0x02,0x18,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x00, +0x05,0x12,0x03,0x09,0x02,0x08,0x0a,0x0c,0x0a,0x05, +0x04,0x01,0x02,0x00,0x01,0x12,0x03,0x09,0x09,0x13, +0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x00,0x03,0x12, +0x03,0x09,0x16,0x17,0x0a,0x0b,0x0a,0x04,0x04,0x01, +0x02,0x01,0x12,0x03,0x0a,0x02,0x16,0x0a,0x0c,0x0a, +0x05,0x04,0x01,0x02,0x01,0x05,0x12,0x03,0x0a,0x02, +0x07,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x01,0x01, +0x12,0x03,0x0a,0x08,0x11,0x0a,0x0c,0x0a,0x05,0x04, +0x01,0x02,0x01,0x03,0x12,0x03,0x0a,0x14,0x15,0x0a, +0x0b,0x0a,0x04,0x04,0x01,0x02,0x02,0x12,0x03,0x0b, +0x02,0x16,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x02, +0x05,0x12,0x03,0x0b,0x02,0x07,0x0a,0x0c,0x0a,0x05, +0x04,0x01,0x02,0x02,0x01,0x12,0x03,0x0b,0x08,0x11, +0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x02,0x03,0x12, +0x03,0x0b,0x14,0x15,0x0a,0x0b,0x0a,0x04,0x04,0x01, +0x02,0x03,0x12,0x03,0x0c,0x02,0x16,0x0a,0x0c,0x0a, +0x05,0x04,0x01,0x02,0x03,0x05,0x12,0x03,0x0c,0x02, +0x07,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x03,0x01, +0x12,0x03,0x0c,0x08,0x11,0x0a,0x0c,0x0a,0x05,0x04, +0x01,0x02,0x03,0x03,0x12,0x03,0x0c,0x14,0x15,0x0a, +0x0b,0x0a,0x04,0x04,0x01,0x02,0x04,0x12,0x03,0x0d, +0x02,0x18,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x04, +0x05,0x12,0x03,0x0d,0x02,0x08,0x0a,0x0c,0x0a,0x05, +0x04,0x01,0x02,0x04,0x01,0x12,0x03,0x0d,0x09,0x13, +0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x04,0x03,0x12, +0x03,0x0d,0x16,0x17,0x0a,0x0b,0x0a,0x04,0x04,0x01, +0x02,0x05,0x12,0x03,0x0e,0x02,0x18,0x0a,0x0c,0x0a, +0x05,0x04,0x01,0x02,0x05,0x05,0x12,0x03,0x0e,0x02, +0x08,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x05,0x01, +0x12,0x03,0x0e,0x09,0x13,0x0a,0x0c,0x0a,0x05,0x04, +0x01,0x02,0x05,0x03,0x12,0x03,0x0e,0x16,0x17,0x0a, +0x0b,0x0a,0x04,0x04,0x01,0x02,0x06,0x12,0x03,0x0f, +0x02,0x18,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x06, +0x05,0x12,0x03,0x0f,0x02,0x08,0x0a,0x0c,0x0a,0x05, +0x04,0x01,0x02,0x06,0x01,0x12,0x03,0x0f,0x09,0x13, +0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x06,0x03,0x12, +0x03,0x0f,0x16,0x17,0x0a,0x0b,0x0a,0x04,0x04,0x01, +0x02,0x07,0x12,0x03,0x10,0x02,0x18,0x0a,0x0c,0x0a, +0x05,0x04,0x01,0x02,0x07,0x05,0x12,0x03,0x10,0x02, +0x08,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x07,0x01, +0x12,0x03,0x10,0x09,0x13,0x0a,0x0c,0x0a,0x05,0x04, +0x01,0x02,0x07,0x03,0x12,0x03,0x10,0x16,0x17,0x0a, +0x0b,0x0a,0x04,0x04,0x01,0x02,0x08,0x12,0x03,0x11, +0x02,0x1a,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x08, +0x05,0x12,0x03,0x11,0x02,0x09,0x0a,0x0c,0x0a,0x05, +0x04,0x01,0x02,0x08,0x01,0x12,0x03,0x11,0x0a,0x15, +0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x08,0x03,0x12, +0x03,0x11,0x18,0x19,0x0a,0x0b,0x0a,0x04,0x04,0x01, +0x02,0x09,0x12,0x03,0x12,0x02,0x1b,0x0a,0x0c,0x0a, +0x05,0x04,0x01,0x02,0x09,0x05,0x12,0x03,0x12,0x02, +0x09,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x09,0x01, +0x12,0x03,0x12,0x0a,0x15,0x0a,0x0c,0x0a,0x05,0x04, +0x01,0x02,0x09,0x03,0x12,0x03,0x12,0x18,0x1a,0x0a, +0x0b,0x0a,0x04,0x04,0x01,0x02,0x0a,0x12,0x03,0x13, +0x02,0x1d,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x0a, +0x05,0x12,0x03,0x13,0x02,0x0a,0x0a,0x0c,0x0a,0x05, +0x04,0x01,0x02,0x0a,0x01,0x12,0x03,0x13,0x0b,0x17, +0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x0a,0x03,0x12, +0x03,0x13,0x1a,0x1c,0x0a,0x0b,0x0a,0x04,0x04,0x01, +0x02,0x0b,0x12,0x03,0x14,0x02,0x1d,0x0a,0x0c,0x0a, +0x05,0x04,0x01,0x02,0x0b,0x05,0x12,0x03,0x14,0x02, +0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x0b,0x01, +0x12,0x03,0x14,0x0b,0x17,0x0a,0x0c,0x0a,0x05,0x04, +0x01,0x02,0x0b,0x03,0x12,0x03,0x14,0x1a,0x1c,0x0a, +0x0b,0x0a,0x04,0x04,0x01,0x02,0x0c,0x12,0x03,0x15, +0x02,0x15,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x0c, +0x05,0x12,0x03,0x15,0x02,0x06,0x0a,0x0c,0x0a,0x05, +0x04,0x01,0x02,0x0c,0x01,0x12,0x03,0x15,0x07,0x0f, +0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x0c,0x03,0x12, +0x03,0x15,0x12,0x14,0x0a,0x0b,0x0a,0x04,0x04,0x01, +0x02,0x0d,0x12,0x03,0x16,0x02,0x19,0x0a,0x0c,0x0a, +0x05,0x04,0x01,0x02,0x0d,0x05,0x12,0x03,0x16,0x02, +0x08,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x0d,0x01, +0x12,0x03,0x16,0x09,0x13,0x0a,0x0c,0x0a,0x05,0x04, +0x01,0x02,0x0d,0x03,0x12,0x03,0x16,0x16,0x18,0x0a, +0x0b,0x0a,0x04,0x04,0x01,0x02,0x0e,0x12,0x03,0x17, +0x02,0x17,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x0e, +0x05,0x12,0x03,0x17,0x02,0x07,0x0a,0x0c,0x0a,0x05, +0x04,0x01,0x02,0x0e,0x01,0x12,0x03,0x17,0x08,0x11, +0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x0e,0x03,0x12, +0x03,0x17,0x14,0x16,0x0a,0x0b,0x0a,0x04,0x04,0x01, +0x02,0x0f,0x12,0x03,0x18,0x02,0x29,0x0a,0x0c,0x0a, +0x05,0x04,0x01,0x02,0x0f,0x06,0x12,0x03,0x18,0x02, +0x10,0x0a,0x0c,0x0a,0x05,0x04,0x01,0x02,0x0f,0x01, +0x12,0x03,0x18,0x11,0x23,0x0a,0x0c,0x0a,0x05,0x04, +0x01,0x02,0x0f,0x03,0x12,0x03,0x18,0x26,0x28,0x0a, +0x0a,0x0a,0x02,0x04,0x02,0x12,0x04,0x1b,0x00,0x2c, +0x01,0x0a,0x0a,0x0a,0x03,0x04,0x02,0x01,0x12,0x03, +0x1b,0x08,0x19,0x0a,0x0b,0x0a,0x04,0x04,0x02,0x02, +0x00,0x12,0x03,0x1c,0x02,0x21,0x0a,0x0c,0x0a,0x05, +0x04,0x02,0x02,0x00,0x04,0x12,0x03,0x1c,0x02,0x0a, +0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x00,0x05,0x12, +0x03,0x1c,0x0b,0x11,0x0a,0x0c,0x0a,0x05,0x04,0x02, +0x02,0x00,0x01,0x12,0x03,0x1c,0x12,0x1c,0x0a,0x0c, +0x0a,0x05,0x04,0x02,0x02,0x00,0x03,0x12,0x03,0x1c, +0x1f,0x20,0x0a,0x0b,0x0a,0x04,0x04,0x02,0x02,0x01, +0x12,0x03,0x1d,0x02,0x1f,0x0a,0x0c,0x0a,0x05,0x04, +0x02,0x02,0x01,0x04,0x12,0x03,0x1d,0x02,0x0a,0x0a, +0x0c,0x0a,0x05,0x04,0x02,0x02,0x01,0x05,0x12,0x03, +0x1d,0x0b,0x10,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02, +0x01,0x01,0x12,0x03,0x1d,0x11,0x1a,0x0a,0x0c,0x0a, +0x05,0x04,0x02,0x02,0x01,0x03,0x12,0x03,0x1d,0x1d, +0x1e,0x0a,0x0b,0x0a,0x04,0x04,0x02,0x02,0x02,0x12, +0x03,0x1e,0x02,0x1f,0x0a,0x0c,0x0a,0x05,0x04,0x02, +0x02,0x02,0x04,0x12,0x03,0x1e,0x02,0x0a,0x0a,0x0c, +0x0a,0x05,0x04,0x02,0x02,0x02,0x05,0x12,0x03,0x1e, +0x0b,0x10,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x02, +0x01,0x12,0x03,0x1e,0x11,0x1a,0x0a,0x0c,0x0a,0x05, +0x04,0x02,0x02,0x02,0x03,0x12,0x03,0x1e,0x1d,0x1e, +0x0a,0x0b,0x0a,0x04,0x04,0x02,0x02,0x03,0x12,0x03, +0x1f,0x02,0x1f,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02, +0x03,0x04,0x12,0x03,0x1f,0x02,0x0a,0x0a,0x0c,0x0a, +0x05,0x04,0x02,0x02,0x03,0x05,0x12,0x03,0x1f,0x0b, +0x10,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x03,0x01, +0x12,0x03,0x1f,0x11,0x1a,0x0a,0x0c,0x0a,0x05,0x04, +0x02,0x02,0x03,0x03,0x12,0x03,0x1f,0x1d,0x1e,0x0a, +0x0b,0x0a,0x04,0x04,0x02,0x02,0x04,0x12,0x03,0x20, +0x02,0x21,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x04, +0x04,0x12,0x03,0x20,0x02,0x0a,0x0a,0x0c,0x0a,0x05, +0x04,0x02,0x02,0x04,0x05,0x12,0x03,0x20,0x0b,0x11, +0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x04,0x01,0x12, +0x03,0x20,0x12,0x1c,0x0a,0x0c,0x0a,0x05,0x04,0x02, +0x02,0x04,0x03,0x12,0x03,0x20,0x1f,0x20,0x0a,0x0b, +0x0a,0x04,0x04,0x02,0x02,0x05,0x12,0x03,0x21,0x02, +0x21,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x05,0x04, +0x12,0x03,0x21,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04, +0x02,0x02,0x05,0x05,0x12,0x03,0x21,0x0b,0x11,0x0a, +0x0c,0x0a,0x05,0x04,0x02,0x02,0x05,0x01,0x12,0x03, +0x21,0x12,0x1c,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02, +0x05,0x03,0x12,0x03,0x21,0x1f,0x20,0x0a,0x0b,0x0a, +0x04,0x04,0x02,0x02,0x06,0x12,0x03,0x22,0x02,0x21, +0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x06,0x04,0x12, +0x03,0x22,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x02, +0x02,0x06,0x05,0x12,0x03,0x22,0x0b,0x11,0x0a,0x0c, +0x0a,0x05,0x04,0x02,0x02,0x06,0x01,0x12,0x03,0x22, +0x12,0x1c,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x06, +0x03,0x12,0x03,0x22,0x1f,0x20,0x0a,0x0b,0x0a,0x04, +0x04,0x02,0x02,0x07,0x12,0x03,0x23,0x02,0x21,0x0a, +0x0c,0x0a,0x05,0x04,0x02,0x02,0x07,0x04,0x12,0x03, +0x23,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02, +0x07,0x05,0x12,0x03,0x23,0x0b,0x11,0x0a,0x0c,0x0a, +0x05,0x04,0x02,0x02,0x07,0x01,0x12,0x03,0x23,0x12, +0x1c,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x07,0x03, +0x12,0x03,0x23,0x1f,0x20,0x0a,0x0b,0x0a,0x04,0x04, +0x02,0x02,0x08,0x12,0x03,0x24,0x02,0x23,0x0a,0x0c, +0x0a,0x05,0x04,0x02,0x02,0x08,0x04,0x12,0x03,0x24, +0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x08, +0x05,0x12,0x03,0x24,0x0b,0x12,0x0a,0x0c,0x0a,0x05, +0x04,0x02,0x02,0x08,0x01,0x12,0x03,0x24,0x13,0x1e, +0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x08,0x03,0x12, +0x03,0x24,0x21,0x22,0x0a,0x0b,0x0a,0x04,0x04,0x02, +0x02,0x09,0x12,0x03,0x25,0x02,0x24,0x0a,0x0c,0x0a, +0x05,0x04,0x02,0x02,0x09,0x04,0x12,0x03,0x25,0x02, +0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x09,0x05, +0x12,0x03,0x25,0x0b,0x12,0x0a,0x0c,0x0a,0x05,0x04, +0x02,0x02,0x09,0x01,0x12,0x03,0x25,0x13,0x1e,0x0a, +0x0c,0x0a,0x05,0x04,0x02,0x02,0x09,0x03,0x12,0x03, +0x25,0x21,0x23,0x0a,0x0b,0x0a,0x04,0x04,0x02,0x02, +0x0a,0x12,0x03,0x26,0x02,0x26,0x0a,0x0c,0x0a,0x05, +0x04,0x02,0x02,0x0a,0x04,0x12,0x03,0x26,0x02,0x0a, +0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x0a,0x05,0x12, +0x03,0x26,0x0b,0x13,0x0a,0x0c,0x0a,0x05,0x04,0x02, +0x02,0x0a,0x01,0x12,0x03,0x26,0x14,0x20,0x0a,0x0c, +0x0a,0x05,0x04,0x02,0x02,0x0a,0x03,0x12,0x03,0x26, +0x23,0x25,0x0a,0x0b,0x0a,0x04,0x04,0x02,0x02,0x0b, +0x12,0x03,0x27,0x02,0x26,0x0a,0x0c,0x0a,0x05,0x04, +0x02,0x02,0x0b,0x04,0x12,0x03,0x27,0x02,0x0a,0x0a, +0x0c,0x0a,0x05,0x04,0x02,0x02,0x0b,0x05,0x12,0x03, +0x27,0x0b,0x13,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02, +0x0b,0x01,0x12,0x03,0x27,0x14,0x20,0x0a,0x0c,0x0a, +0x05,0x04,0x02,0x02,0x0b,0x03,0x12,0x03,0x27,0x23, +0x25,0x0a,0x0b,0x0a,0x04,0x04,0x02,0x02,0x0c,0x12, +0x03,0x28,0x02,0x1e,0x0a,0x0c,0x0a,0x05,0x04,0x02, +0x02,0x0c,0x04,0x12,0x03,0x28,0x02,0x0a,0x0a,0x0c, +0x0a,0x05,0x04,0x02,0x02,0x0c,0x05,0x12,0x03,0x28, +0x0b,0x0f,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x0c, +0x01,0x12,0x03,0x28,0x10,0x18,0x0a,0x0c,0x0a,0x05, +0x04,0x02,0x02,0x0c,0x03,0x12,0x03,0x28,0x1b,0x1d, +0x0a,0x0b,0x0a,0x04,0x04,0x02,0x02,0x0d,0x12,0x03, +0x29,0x02,0x22,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02, +0x0d,0x04,0x12,0x03,0x29,0x02,0x0a,0x0a,0x0c,0x0a, +0x05,0x04,0x02,0x02,0x0d,0x05,0x12,0x03,0x29,0x0b, +0x11,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x0d,0x01, +0x12,0x03,0x29,0x12,0x1c,0x0a,0x0c,0x0a,0x05,0x04, +0x02,0x02,0x0d,0x03,0x12,0x03,0x29,0x1f,0x21,0x0a, +0x0b,0x0a,0x04,0x04,0x02,0x02,0x0e,0x12,0x03,0x2a, +0x02,0x20,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x0e, +0x04,0x12,0x03,0x2a,0x02,0x0a,0x0a,0x0c,0x0a,0x05, +0x04,0x02,0x02,0x0e,0x05,0x12,0x03,0x2a,0x0b,0x10, +0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x0e,0x01,0x12, +0x03,0x2a,0x11,0x1a,0x0a,0x0c,0x0a,0x05,0x04,0x02, +0x02,0x0e,0x03,0x12,0x03,0x2a,0x1d,0x1f,0x0a,0x0b, +0x0a,0x04,0x04,0x02,0x02,0x0f,0x12,0x03,0x2b,0x02, +0x32,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02,0x0f,0x04, +0x12,0x03,0x2b,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04, +0x02,0x02,0x0f,0x06,0x12,0x03,0x2b,0x0b,0x19,0x0a, +0x0c,0x0a,0x05,0x04,0x02,0x02,0x0f,0x01,0x12,0x03, +0x2b,0x1a,0x2c,0x0a,0x0c,0x0a,0x05,0x04,0x02,0x02, +0x0f,0x03,0x12,0x03,0x2b,0x2f,0x31,0x0a,0x0a,0x0a, +0x02,0x04,0x03,0x12,0x04,0x2e,0x00,0x3f,0x01,0x0a, +0x0a,0x0a,0x03,0x04,0x03,0x01,0x12,0x03,0x2e,0x08, +0x19,0x0a,0x0b,0x0a,0x04,0x04,0x03,0x02,0x00,0x12, +0x03,0x2f,0x02,0x21,0x0a,0x0c,0x0a,0x05,0x04,0x03, +0x02,0x00,0x04,0x12,0x03,0x2f,0x02,0x0a,0x0a,0x0c, +0x0a,0x05,0x04,0x03,0x02,0x00,0x05,0x12,0x03,0x2f, +0x0b,0x11,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x00, +0x01,0x12,0x03,0x2f,0x12,0x1c,0x0a,0x0c,0x0a,0x05, +0x04,0x03,0x02,0x00,0x03,0x12,0x03,0x2f,0x1f,0x20, +0x0a,0x0b,0x0a,0x04,0x04,0x03,0x02,0x01,0x12,0x03, +0x30,0x02,0x1f,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02, +0x01,0x04,0x12,0x03,0x30,0x02,0x0a,0x0a,0x0c,0x0a, +0x05,0x04,0x03,0x02,0x01,0x05,0x12,0x03,0x30,0x0b, +0x10,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x01,0x01, +0x12,0x03,0x30,0x11,0x1a,0x0a,0x0c,0x0a,0x05,0x04, +0x03,0x02,0x01,0x03,0x12,0x03,0x30,0x1d,0x1e,0x0a, +0x0b,0x0a,0x04,0x04,0x03,0x02,0x02,0x12,0x03,0x31, +0x02,0x1f,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x02, +0x04,0x12,0x03,0x31,0x02,0x0a,0x0a,0x0c,0x0a,0x05, +0x04,0x03,0x02,0x02,0x05,0x12,0x03,0x31,0x0b,0x10, +0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x02,0x01,0x12, +0x03,0x31,0x11,0x1a,0x0a,0x0c,0x0a,0x05,0x04,0x03, +0x02,0x02,0x03,0x12,0x03,0x31,0x1d,0x1e,0x0a,0x0b, +0x0a,0x04,0x04,0x03,0x02,0x03,0x12,0x03,0x32,0x02, +0x1f,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x03,0x04, +0x12,0x03,0x32,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04, +0x03,0x02,0x03,0x05,0x12,0x03,0x32,0x0b,0x10,0x0a, +0x0c,0x0a,0x05,0x04,0x03,0x02,0x03,0x01,0x12,0x03, +0x32,0x11,0x1a,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02, +0x03,0x03,0x12,0x03,0x32,0x1d,0x1e,0x0a,0x0b,0x0a, +0x04,0x04,0x03,0x02,0x04,0x12,0x03,0x33,0x02,0x21, +0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x04,0x04,0x12, +0x03,0x33,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x03, +0x02,0x04,0x05,0x12,0x03,0x33,0x0b,0x11,0x0a,0x0c, +0x0a,0x05,0x04,0x03,0x02,0x04,0x01,0x12,0x03,0x33, +0x12,0x1c,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x04, +0x03,0x12,0x03,0x33,0x1f,0x20,0x0a,0x0b,0x0a,0x04, +0x04,0x03,0x02,0x05,0x12,0x03,0x34,0x02,0x21,0x0a, +0x0c,0x0a,0x05,0x04,0x03,0x02,0x05,0x04,0x12,0x03, +0x34,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02, +0x05,0x05,0x12,0x03,0x34,0x0b,0x11,0x0a,0x0c,0x0a, +0x05,0x04,0x03,0x02,0x05,0x01,0x12,0x03,0x34,0x12, +0x1c,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x05,0x03, +0x12,0x03,0x34,0x1f,0x20,0x0a,0x0b,0x0a,0x04,0x04, +0x03,0x02,0x06,0x12,0x03,0x35,0x02,0x21,0x0a,0x0c, +0x0a,0x05,0x04,0x03,0x02,0x06,0x04,0x12,0x03,0x35, +0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x06, +0x05,0x12,0x03,0x35,0x0b,0x11,0x0a,0x0c,0x0a,0x05, +0x04,0x03,0x02,0x06,0x01,0x12,0x03,0x35,0x12,0x1c, +0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x06,0x03,0x12, +0x03,0x35,0x1f,0x20,0x0a,0x0b,0x0a,0x04,0x04,0x03, +0x02,0x07,0x12,0x03,0x36,0x02,0x21,0x0a,0x0c,0x0a, +0x05,0x04,0x03,0x02,0x07,0x04,0x12,0x03,0x36,0x02, +0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x07,0x05, +0x12,0x03,0x36,0x0b,0x11,0x0a,0x0c,0x0a,0x05,0x04, +0x03,0x02,0x07,0x01,0x12,0x03,0x36,0x12,0x1c,0x0a, +0x0c,0x0a,0x05,0x04,0x03,0x02,0x07,0x03,0x12,0x03, +0x36,0x1f,0x20,0x0a,0x0b,0x0a,0x04,0x04,0x03,0x02, +0x08,0x12,0x03,0x37,0x02,0x23,0x0a,0x0c,0x0a,0x05, +0x04,0x03,0x02,0x08,0x04,0x12,0x03,0x37,0x02,0x0a, +0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x08,0x05,0x12, +0x03,0x37,0x0b,0x12,0x0a,0x0c,0x0a,0x05,0x04,0x03, +0x02,0x08,0x01,0x12,0x03,0x37,0x13,0x1e,0x0a,0x0c, +0x0a,0x05,0x04,0x03,0x02,0x08,0x03,0x12,0x03,0x37, +0x21,0x22,0x0a,0x0b,0x0a,0x04,0x04,0x03,0x02,0x09, +0x12,0x03,0x38,0x02,0x24,0x0a,0x0c,0x0a,0x05,0x04, +0x03,0x02,0x09,0x04,0x12,0x03,0x38,0x02,0x0a,0x0a, +0x0c,0x0a,0x05,0x04,0x03,0x02,0x09,0x05,0x12,0x03, +0x38,0x0b,0x12,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02, +0x09,0x01,0x12,0x03,0x38,0x13,0x1e,0x0a,0x0c,0x0a, +0x05,0x04,0x03,0x02,0x09,0x03,0x12,0x03,0x38,0x21, +0x23,0x0a,0x0b,0x0a,0x04,0x04,0x03,0x02,0x0a,0x12, +0x03,0x39,0x02,0x26,0x0a,0x0c,0x0a,0x05,0x04,0x03, +0x02,0x0a,0x04,0x12,0x03,0x39,0x02,0x0a,0x0a,0x0c, +0x0a,0x05,0x04,0x03,0x02,0x0a,0x05,0x12,0x03,0x39, +0x0b,0x13,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x0a, +0x01,0x12,0x03,0x39,0x14,0x20,0x0a,0x0c,0x0a,0x05, +0x04,0x03,0x02,0x0a,0x03,0x12,0x03,0x39,0x23,0x25, +0x0a,0x0b,0x0a,0x04,0x04,0x03,0x02,0x0b,0x12,0x03, +0x3a,0x02,0x26,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02, +0x0b,0x04,0x12,0x03,0x3a,0x02,0x0a,0x0a,0x0c,0x0a, +0x05,0x04,0x03,0x02,0x0b,0x05,0x12,0x03,0x3a,0x0b, +0x13,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x0b,0x01, +0x12,0x03,0x3a,0x14,0x20,0x0a,0x0c,0x0a,0x05,0x04, +0x03,0x02,0x0b,0x03,0x12,0x03,0x3a,0x23,0x25,0x0a, +0x0b,0x0a,0x04,0x04,0x03,0x02,0x0c,0x12,0x03,0x3b, +0x02,0x1e,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x0c, +0x04,0x12,0x03,0x3b,0x02,0x0a,0x0a,0x0c,0x0a,0x05, +0x04,0x03,0x02,0x0c,0x05,0x12,0x03,0x3b,0x0b,0x0f, +0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x0c,0x01,0x12, +0x03,0x3b,0x10,0x18,0x0a,0x0c,0x0a,0x05,0x04,0x03, +0x02,0x0c,0x03,0x12,0x03,0x3b,0x1b,0x1d,0x0a,0x0b, +0x0a,0x04,0x04,0x03,0x02,0x0d,0x12,0x03,0x3c,0x02, +0x22,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x0d,0x04, +0x12,0x03,0x3c,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04, +0x03,0x02,0x0d,0x05,0x12,0x03,0x3c,0x0b,0x11,0x0a, +0x0c,0x0a,0x05,0x04,0x03,0x02,0x0d,0x01,0x12,0x03, +0x3c,0x12,0x1c,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02, +0x0d,0x03,0x12,0x03,0x3c,0x1f,0x21,0x0a,0x0b,0x0a, +0x04,0x04,0x03,0x02,0x0e,0x12,0x03,0x3d,0x02,0x20, +0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x0e,0x04,0x12, +0x03,0x3d,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x03, +0x02,0x0e,0x05,0x12,0x03,0x3d,0x0b,0x10,0x0a,0x0c, +0x0a,0x05,0x04,0x03,0x02,0x0e,0x01,0x12,0x03,0x3d, +0x11,0x1a,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x0e, +0x03,0x12,0x03,0x3d,0x1d,0x1f,0x0a,0x0b,0x0a,0x04, +0x04,0x03,0x02,0x0f,0x12,0x03,0x3e,0x02,0x32,0x0a, +0x0c,0x0a,0x05,0x04,0x03,0x02,0x0f,0x04,0x12,0x03, +0x3e,0x02,0x0a,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02, +0x0f,0x06,0x12,0x03,0x3e,0x0b,0x19,0x0a,0x0c,0x0a, +0x05,0x04,0x03,0x02,0x0f,0x01,0x12,0x03,0x3e,0x1a, +0x2c,0x0a,0x0c,0x0a,0x05,0x04,0x03,0x02,0x0f,0x03, +0x12,0x03,0x3e,0x2f,0x31,0x62,0x06,0x70,0x72,0x6f, +0x74,0x6f,0x33, +}; +static const char file_name[] = "wpiutil.proto"; +static const char wpi_proto_TestProtoInner_name[] = "wpi.proto.TestProtoInner"; +std::string_view wpi_proto_TestProtoInner::msg_name(void) noexcept { return wpi_proto_TestProtoInner_name; } +pb_filedesc_t wpi_proto_TestProtoInner::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_TestProtoInner, wpi_proto_TestProtoInner, AUTO) + + +static const char wpi_proto_TestProto_name[] = "wpi.proto.TestProto"; +std::string_view wpi_proto_TestProto::msg_name(void) noexcept { return wpi_proto_TestProto_name; } +pb_filedesc_t wpi_proto_TestProto::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_TestProto, wpi_proto_TestProto, AUTO) + + +static const char wpi_proto_OptionalTestProto_name[] = "wpi.proto.OptionalTestProto"; +std::string_view wpi_proto_OptionalTestProto::msg_name(void) noexcept { return wpi_proto_OptionalTestProto_name; } +pb_filedesc_t wpi_proto_OptionalTestProto::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_OptionalTestProto, wpi_proto_OptionalTestProto, AUTO) + + +static const char wpi_proto_RepeatedTestProto_name[] = "wpi.proto.RepeatedTestProto"; +std::string_view wpi_proto_RepeatedTestProto::msg_name(void) noexcept { return wpi_proto_RepeatedTestProto_name; } +pb_filedesc_t wpi_proto_RepeatedTestProto::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; } +PB_BIND(wpi_proto_RepeatedTestProto, wpi_proto_RepeatedTestProto, 2) + + + +#ifndef PB_CONVERT_DOUBLE_FLOAT +/* On some platforms (such as AVR), double is really float. + * To be able to encode/decode double on these platforms, you need. + * to define PB_CONVERT_DOUBLE_FLOAT in pb.h or compiler command line. + */ +PB_STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES) +#endif + diff --git a/wpiutil/src/generated/test/native/cpp/wpiutil.npb.h b/wpiutil/src/generated/test/native/cpp/wpiutil.npb.h new file mode 100644 index 0000000000..d13518b32a --- /dev/null +++ b/wpiutil/src/generated/test/native/cpp/wpiutil.npb.h @@ -0,0 +1,246 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. +/* Automatically generated nanopb header */ +/* Generated by nanopb-0.4.9 */ + +#ifndef PB_WPI_PROTO_WPIUTIL_NPB_H_INCLUDED +#define PB_WPI_PROTO_WPIUTIL_NPB_H_INCLUDED +#include +#include +#include + +#if PB_PROTO_HEADER_VERSION != 40 +#error Regenerate this file with the current version of nanopb generator. +#endif + +/* Struct definitions */ +typedef struct _wpi_proto_TestProtoInner { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + pb_callback_t msg; +} wpi_proto_TestProtoInner; + +typedef struct _wpi_proto_TestProto { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + double double_msg; + float float_msg; + int32_t int32_msg; + int64_t int64_msg; + uint32_t uint32_msg; + uint64_t uint64_msg; + int32_t sint32_msg; + int64_t sint64_msg; + uint32_t fixed32_msg; + uint64_t fixed64_msg; + int32_t sfixed32_msg; + int64_t sfixed64_msg; + bool bool_msg; + pb_callback_t string_msg; + pb_callback_t bytes_msg; + pb_callback_t TestProtoInner_msg; +} wpi_proto_TestProto; + +typedef struct _wpi_proto_OptionalTestProto { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + bool has_double_msg; + double double_msg; + bool has_float_msg; + float float_msg; + bool has_int32_msg; + int32_t int32_msg; + bool has_int64_msg; + int64_t int64_msg; + bool has_uint32_msg; + uint32_t uint32_msg; + bool has_uint64_msg; + uint64_t uint64_msg; + bool has_sint32_msg; + int32_t sint32_msg; + bool has_sint64_msg; + int64_t sint64_msg; + bool has_fixed32_msg; + uint32_t fixed32_msg; + bool has_fixed64_msg; + uint64_t fixed64_msg; + bool has_sfixed32_msg; + int32_t sfixed32_msg; + bool has_sfixed64_msg; + int64_t sfixed64_msg; + bool has_bool_msg; + bool bool_msg; + pb_callback_t string_msg; + pb_callback_t bytes_msg; + pb_callback_t TestProtoInner_msg; +} wpi_proto_OptionalTestProto; + +typedef struct _wpi_proto_RepeatedTestProto { + static const pb_msgdesc_t* msg_descriptor(void) noexcept; + static std::string_view msg_name(void) noexcept; + static pb_filedesc_t file_descriptor(void) noexcept; + + pb_callback_t double_msg; + pb_callback_t float_msg; + pb_callback_t int32_msg; + pb_callback_t int64_msg; + pb_callback_t uint32_msg; + pb_callback_t uint64_msg; + pb_callback_t sint32_msg; + pb_callback_t sint64_msg; + pb_callback_t fixed32_msg; + pb_callback_t fixed64_msg; + pb_callback_t sfixed32_msg; + pb_callback_t sfixed64_msg; + pb_callback_t bool_msg; + pb_callback_t string_msg; + pb_callback_t bytes_msg; + pb_callback_t TestProtoInner_msg; +} wpi_proto_RepeatedTestProto; + + +/* Initializer values for message structs */ +#define wpi_proto_TestProtoInner_init_default {{{NULL}, NULL}} +#define wpi_proto_TestProto_init_default {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_OptionalTestProto_init_default {false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_RepeatedTestProto_init_default {{{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_TestProtoInner_init_zero {{{NULL}, NULL}} +#define wpi_proto_TestProto_init_zero {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_OptionalTestProto_init_zero {false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, false, 0, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}} +#define wpi_proto_RepeatedTestProto_init_zero {{{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}, {{NULL}, NULL}} + +/* Field tags (for use in manual encoding/decoding) */ +#define wpi_proto_TestProtoInner_msg_tag 1 +#define wpi_proto_TestProto_double_msg_tag 1 +#define wpi_proto_TestProto_float_msg_tag 2 +#define wpi_proto_TestProto_int32_msg_tag 3 +#define wpi_proto_TestProto_int64_msg_tag 4 +#define wpi_proto_TestProto_uint32_msg_tag 5 +#define wpi_proto_TestProto_uint64_msg_tag 6 +#define wpi_proto_TestProto_sint32_msg_tag 7 +#define wpi_proto_TestProto_sint64_msg_tag 8 +#define wpi_proto_TestProto_fixed32_msg_tag 9 +#define wpi_proto_TestProto_fixed64_msg_tag 10 +#define wpi_proto_TestProto_sfixed32_msg_tag 11 +#define wpi_proto_TestProto_sfixed64_msg_tag 12 +#define wpi_proto_TestProto_bool_msg_tag 13 +#define wpi_proto_TestProto_string_msg_tag 14 +#define wpi_proto_TestProto_bytes_msg_tag 15 +#define wpi_proto_TestProto_TestProtoInner_msg_tag 16 +#define wpi_proto_OptionalTestProto_double_msg_tag 1 +#define wpi_proto_OptionalTestProto_float_msg_tag 2 +#define wpi_proto_OptionalTestProto_int32_msg_tag 3 +#define wpi_proto_OptionalTestProto_int64_msg_tag 4 +#define wpi_proto_OptionalTestProto_uint32_msg_tag 5 +#define wpi_proto_OptionalTestProto_uint64_msg_tag 6 +#define wpi_proto_OptionalTestProto_sint32_msg_tag 7 +#define wpi_proto_OptionalTestProto_sint64_msg_tag 8 +#define wpi_proto_OptionalTestProto_fixed32_msg_tag 9 +#define wpi_proto_OptionalTestProto_fixed64_msg_tag 10 +#define wpi_proto_OptionalTestProto_sfixed32_msg_tag 11 +#define wpi_proto_OptionalTestProto_sfixed64_msg_tag 12 +#define wpi_proto_OptionalTestProto_bool_msg_tag 13 +#define wpi_proto_OptionalTestProto_string_msg_tag 14 +#define wpi_proto_OptionalTestProto_bytes_msg_tag 15 +#define wpi_proto_OptionalTestProto_TestProtoInner_msg_tag 16 +#define wpi_proto_RepeatedTestProto_double_msg_tag 1 +#define wpi_proto_RepeatedTestProto_float_msg_tag 2 +#define wpi_proto_RepeatedTestProto_int32_msg_tag 3 +#define wpi_proto_RepeatedTestProto_int64_msg_tag 4 +#define wpi_proto_RepeatedTestProto_uint32_msg_tag 5 +#define wpi_proto_RepeatedTestProto_uint64_msg_tag 6 +#define wpi_proto_RepeatedTestProto_sint32_msg_tag 7 +#define wpi_proto_RepeatedTestProto_sint64_msg_tag 8 +#define wpi_proto_RepeatedTestProto_fixed32_msg_tag 9 +#define wpi_proto_RepeatedTestProto_fixed64_msg_tag 10 +#define wpi_proto_RepeatedTestProto_sfixed32_msg_tag 11 +#define wpi_proto_RepeatedTestProto_sfixed64_msg_tag 12 +#define wpi_proto_RepeatedTestProto_bool_msg_tag 13 +#define wpi_proto_RepeatedTestProto_string_msg_tag 14 +#define wpi_proto_RepeatedTestProto_bytes_msg_tag 15 +#define wpi_proto_RepeatedTestProto_TestProtoInner_msg_tag 16 + +/* Struct field encoding specification for nanopb */ +#define wpi_proto_TestProtoInner_FIELDLIST(X, a) \ +X(a, CALLBACK, SINGULAR, STRING, msg, 1) +#define wpi_proto_TestProtoInner_CALLBACK pb_default_field_callback +#define wpi_proto_TestProtoInner_DEFAULT NULL + +#define wpi_proto_TestProto_FIELDLIST(X, a) \ +X(a, STATIC, SINGULAR, DOUBLE, double_msg, 1) \ +X(a, STATIC, SINGULAR, FLOAT, float_msg, 2) \ +X(a, STATIC, SINGULAR, INT32, int32_msg, 3) \ +X(a, STATIC, SINGULAR, INT64, int64_msg, 4) \ +X(a, STATIC, SINGULAR, UINT32, uint32_msg, 5) \ +X(a, STATIC, SINGULAR, UINT64, uint64_msg, 6) \ +X(a, STATIC, SINGULAR, SINT32, sint32_msg, 7) \ +X(a, STATIC, SINGULAR, SINT64, sint64_msg, 8) \ +X(a, STATIC, SINGULAR, FIXED32, fixed32_msg, 9) \ +X(a, STATIC, SINGULAR, FIXED64, fixed64_msg, 10) \ +X(a, STATIC, SINGULAR, SFIXED32, sfixed32_msg, 11) \ +X(a, STATIC, SINGULAR, SFIXED64, sfixed64_msg, 12) \ +X(a, STATIC, SINGULAR, BOOL, bool_msg, 13) \ +X(a, CALLBACK, SINGULAR, STRING, string_msg, 14) \ +X(a, CALLBACK, SINGULAR, BYTES, bytes_msg, 15) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, TestProtoInner_msg, 16) +#define wpi_proto_TestProto_CALLBACK pb_default_field_callback +#define wpi_proto_TestProto_DEFAULT NULL +#define wpi_proto_TestProto_TestProtoInner_msg_MSGTYPE wpi_proto_TestProtoInner + +#define wpi_proto_OptionalTestProto_FIELDLIST(X, a) \ +X(a, STATIC, OPTIONAL, DOUBLE, double_msg, 1) \ +X(a, STATIC, OPTIONAL, FLOAT, float_msg, 2) \ +X(a, STATIC, OPTIONAL, INT32, int32_msg, 3) \ +X(a, STATIC, OPTIONAL, INT64, int64_msg, 4) \ +X(a, STATIC, OPTIONAL, UINT32, uint32_msg, 5) \ +X(a, STATIC, OPTIONAL, UINT64, uint64_msg, 6) \ +X(a, STATIC, OPTIONAL, SINT32, sint32_msg, 7) \ +X(a, STATIC, OPTIONAL, SINT64, sint64_msg, 8) \ +X(a, STATIC, OPTIONAL, FIXED32, fixed32_msg, 9) \ +X(a, STATIC, OPTIONAL, FIXED64, fixed64_msg, 10) \ +X(a, STATIC, OPTIONAL, SFIXED32, sfixed32_msg, 11) \ +X(a, STATIC, OPTIONAL, SFIXED64, sfixed64_msg, 12) \ +X(a, STATIC, OPTIONAL, BOOL, bool_msg, 13) \ +X(a, CALLBACK, OPTIONAL, STRING, string_msg, 14) \ +X(a, CALLBACK, OPTIONAL, BYTES, bytes_msg, 15) \ +X(a, CALLBACK, OPTIONAL, MESSAGE, TestProtoInner_msg, 16) +#define wpi_proto_OptionalTestProto_CALLBACK pb_default_field_callback +#define wpi_proto_OptionalTestProto_DEFAULT NULL +#define wpi_proto_OptionalTestProto_TestProtoInner_msg_MSGTYPE wpi_proto_TestProtoInner + +#define wpi_proto_RepeatedTestProto_FIELDLIST(X, a) \ +X(a, CALLBACK, REPEATED, DOUBLE, double_msg, 1) \ +X(a, CALLBACK, REPEATED, FLOAT, float_msg, 2) \ +X(a, CALLBACK, REPEATED, INT32, int32_msg, 3) \ +X(a, CALLBACK, REPEATED, INT64, int64_msg, 4) \ +X(a, CALLBACK, REPEATED, UINT32, uint32_msg, 5) \ +X(a, CALLBACK, REPEATED, UINT64, uint64_msg, 6) \ +X(a, CALLBACK, REPEATED, SINT32, sint32_msg, 7) \ +X(a, CALLBACK, REPEATED, SINT64, sint64_msg, 8) \ +X(a, CALLBACK, REPEATED, FIXED32, fixed32_msg, 9) \ +X(a, CALLBACK, REPEATED, FIXED64, fixed64_msg, 10) \ +X(a, CALLBACK, REPEATED, SFIXED32, sfixed32_msg, 11) \ +X(a, CALLBACK, REPEATED, SFIXED64, sfixed64_msg, 12) \ +X(a, CALLBACK, REPEATED, BOOL, bool_msg, 13) \ +X(a, CALLBACK, REPEATED, STRING, string_msg, 14) \ +X(a, CALLBACK, REPEATED, BYTES, bytes_msg, 15) \ +X(a, CALLBACK, REPEATED, MESSAGE, TestProtoInner_msg, 16) +#define wpi_proto_RepeatedTestProto_CALLBACK pb_default_field_callback +#define wpi_proto_RepeatedTestProto_DEFAULT NULL +#define wpi_proto_RepeatedTestProto_TestProtoInner_msg_MSGTYPE wpi_proto_TestProtoInner + +/* Maximum encoded size of messages (where known) */ +/* wpi_proto_TestProtoInner_size depends on runtime parameters */ +/* wpi_proto_TestProto_size depends on runtime parameters */ +/* wpi_proto_OptionalTestProto_size depends on runtime parameters */ +/* wpi_proto_RepeatedTestProto_size depends on runtime parameters */ + + +#endif diff --git a/wpiutil/src/main/native/cpp/protobuf/Protobuf.cpp b/wpiutil/src/main/native/cpp/protobuf/Protobuf.cpp index 4fc10b26a6..a99cb7c164 100644 --- a/wpiutil/src/main/native/cpp/protobuf/Protobuf.cpp +++ b/wpiutil/src/main/native/cpp/protobuf/Protobuf.cpp @@ -8,191 +8,43 @@ #include #include -#include -#include -#include -#include -#include "wpi/ProtoHelper.h" #include "wpi/SmallVector.h" using namespace wpi; -using google::protobuf::Arena; -using google::protobuf::FileDescriptor; -using google::protobuf::FileDescriptorProto; - -namespace { -class VectorOutputStream final - : public google::protobuf::io::ZeroCopyOutputStream { - public: - // Create a StringOutputStream which appends bytes to the given string. - // The string remains property of the caller, but it is mutated in arbitrary - // ways and MUST NOT be accessed in any way until you're done with the - // stream. Either be sure there's no further usage, or (safest) destroy the - // stream before using the contents. - // - // Hint: If you call target->reserve(n) before creating the stream, - // the first call to Next() will return at least n bytes of buffer - // space. - explicit VectorOutputStream(std::vector& target) : target_{target} {} - VectorOutputStream(const VectorOutputStream&) = delete; - ~VectorOutputStream() override = default; - - VectorOutputStream& operator=(const VectorOutputStream&) = delete; - - // implements ZeroCopyOutputStream --------------------------------- - bool Next(void** data, int* size) override; - void BackUp(int count) override { target_.resize(target_.size() - count); } - int64_t ByteCount() const override { return target_.size(); } - - private: - static constexpr size_t kMinimumSize = 16; - - std::vector& target_; -}; - -class SmallVectorOutputStream final - : public google::protobuf::io::ZeroCopyOutputStream { - public: - // Create a StringOutputStream which appends bytes to the given string. - // The string remains property of the caller, but it is mutated in arbitrary - // ways and MUST NOT be accessed in any way until you're done with the - // stream. Either be sure there's no further usage, or (safest) destroy the - // stream before using the contents. - // - // Hint: If you call target->reserve(n) before creating the stream, - // the first call to Next() will return at least n bytes of buffer - // space. - explicit SmallVectorOutputStream(wpi::SmallVectorImpl& target) - : target_{target} { - target.resize(0); - } - SmallVectorOutputStream(const SmallVectorOutputStream&) = delete; - ~SmallVectorOutputStream() override = default; - - SmallVectorOutputStream& operator=(const SmallVectorOutputStream&) = delete; - - // implements ZeroCopyOutputStream --------------------------------- - bool Next(void** data, int* size) override; - void BackUp(int count) override { target_.resize(target_.size() - count); } - int64_t ByteCount() const override { return target_.size(); } - - private: - static constexpr size_t kMinimumSize = 16; - - wpi::SmallVectorImpl& target_; -}; -} // namespace - -bool VectorOutputStream::Next(void** data, int* size) { - size_t old_size = target_.size(); - - // Grow the string. - size_t new_size; - if (old_size < target_.capacity()) { - // Resize to match its capacity, since we can get away - // without a memory allocation this way. - new_size = target_.capacity(); - } else { - // Size has reached capacity, try to double it. - new_size = old_size * 2; - } - // Avoid integer overflow in returned '*size'. - new_size = (std::min)(new_size, old_size + (std::numeric_limits::max)()); - // Increase the size, also make sure that it is at least kMinimumSize. - target_.resize((std::max)(new_size, kMinimumSize)); - - *data = target_.data() + old_size; - *size = target_.size() - old_size; - return true; -} - -bool SmallVectorOutputStream::Next(void** data, int* size) { - size_t old_size = target_.size(); - - // Grow the string. - size_t new_size; - if (old_size < target_.capacity()) { - // Resize to match its capacity, since we can get away - // without a memory allocation this way. - new_size = target_.capacity(); - } else { - // Size has reached capacity, try to double it. - new_size = old_size * 2; - } - // Avoid integer overflow in returned '*size'. - new_size = (std::min)(new_size, old_size + (std::numeric_limits::max)()); - // Increase the size, also make sure that it is at least kMinimumSize. - target_.resize_for_overwrite((std::max)(new_size, kMinimumSize)); - - *data = target_.data() + old_size; - *size = target_.size() - old_size; - return true; -} - -void detail::DeleteProtobuf(google::protobuf::Message* msg) { - if (msg && !msg->GetArena()) { - delete msg; - } -} - -bool detail::ParseProtobuf(google::protobuf::Message* msg, - std::span data) { - return msg->ParseFromArray(data.data(), data.size()); -} - -bool detail::SerializeProtobuf(wpi::SmallVectorImpl& out, - const google::protobuf::Message& msg) { - SmallVectorOutputStream stream{out}; - return msg.SerializeToZeroCopyStream(&stream); -} - -bool detail::SerializeProtobuf(std::vector& out, - const google::protobuf::Message& msg) { - VectorOutputStream stream{out}; - return msg.SerializeToZeroCopyStream(&stream); -} - -std::string detail::GetTypeString(const google::protobuf::Message& msg) { - return fmt::format("proto:{}", msg.GetDescriptor()->full_name()); -} - -static void ForEachProtobufDescriptorImpl( - const FileDescriptor* desc, - function_ref exists, - function_ref schema)> - fn, - Arena* arena, FileDescriptorProto** descproto) { - std::string name = fmt::format("proto:{}", desc->name()); - if (exists(name)) { - return; - } - for (int i = 0, ndep = desc->dependency_count(); i < ndep; ++i) { - ForEachProtobufDescriptorImpl(desc->dependency(i), exists, fn, arena, - descproto); - } - if (!*descproto) { - *descproto = wpi::CreateMessage(arena); - } - (*descproto)->Clear(); - desc->CopyTo(*descproto); - SmallVector buf; - detail::SerializeProtobuf(buf, **descproto); - fn(name, buf); +std::string detail::GetTypeString(const pb_msgdesc_t* msg) { + return fmt::format("proto:{}", msg->proto_name); } void detail::ForEachProtobufDescriptor( - const google::protobuf::Message& msg, + const pb_msgdesc_t* msg, function_ref exists, function_ref descriptor)> fn) { - FileDescriptorProto* descproto = nullptr; - ForEachProtobufDescriptorImpl(msg.GetDescriptor()->file(), exists, fn, - msg.GetArena(), &descproto); - if (descproto && !msg.GetArena()) { - delete descproto; + std::string name = fmt::format("proto:{}", msg->file_descriptor.file_name); + if (exists(name)) { + return; } + const pb_msgdesc_t* const* nested = msg->submsg_info; + while (*nested) { + ForEachProtobufDescriptor(*nested, exists, fn); + nested++; + } + fn(name, msg->file_descriptor.file_descriptor); +} + +bool detail::WriteFromSmallVector(pb_ostream_t* stream, const pb_byte_t* buf, + size_t count) { + SmallVectorType* vec = reinterpret_cast(stream->state); + vec->append(buf, buf + count); + return true; +} + +bool detail::WriteFromStdVector(pb_ostream_t* stream, const pb_byte_t* buf, + size_t count) { + StdVectorType* vec = reinterpret_cast(stream->state); + vec->insert(vec->end(), buf, buf + count); + return true; } diff --git a/wpiutil/src/main/native/include/wpi/protobuf/Protobuf.h b/wpiutil/src/main/native/include/wpi/protobuf/Protobuf.h index fb8b7943c4..34ad3b3aca 100644 --- a/wpiutil/src/main/native/include/wpi/protobuf/Protobuf.h +++ b/wpiutil/src/main/native/include/wpi/protobuf/Protobuf.h @@ -14,18 +14,12 @@ #include #include +#include "pb.h" +#include "pb_decode.h" +#include "pb_encode.h" #include "wpi/array.h" #include "wpi/function_ref.h" -namespace google::protobuf { -class Arena; -class Message; -template -class RepeatedPtrField; -template -class RepeatedField; -} // namespace google::protobuf - namespace wpi { template @@ -41,43 +35,235 @@ class SmallVectorImpl; template struct Protobuf {}; +namespace detail { +using SmallVectorType = wpi::SmallVectorImpl; +using StdVectorType = std::vector; +bool WriteFromSmallVector(pb_ostream_t* stream, const pb_byte_t* buf, + size_t count); + +bool WriteFromStdVector(pb_ostream_t* stream, const pb_byte_t* buf, + size_t count); +} // namespace detail + +/** + * Class for wrapping a nanopb istream. + */ +template +class ProtoInputStream { + public: + /** + * Constructs a nanopb istream from an existing istream object. + * Generally used internally for decoding submessages + * + * @param[in] stream the nanopb istream + */ + explicit ProtoInputStream(pb_istream_t* stream) + : m_streamMsg{stream}, + m_msgDesc{ + Protobuf>::MessageStruct::msg_descriptor()} { + } + + /** + * Constructs a nanopb istream from a buffer. + * + * @param[in] stream the stream buffer + */ + explicit ProtoInputStream(std::span stream) + : m_streamLocal{pb_istream_from_buffer( + reinterpret_cast(stream.data()), stream.size())}, + m_msgDesc{ + Protobuf>::MessageStruct::msg_descriptor()} { + } + + /** + * Gets the backing nanopb stream object. + * + * @return nanopb stream + */ + pb_istream_t* Stream() noexcept { + return m_streamMsg ? m_streamMsg : &m_streamLocal; + } + + /** + * Gets the nanopb message descriptor + * + * @return the nanopb message descriptor + */ + const pb_msgdesc_t* MsgDesc() const noexcept { return m_msgDesc; } + + /** + * Decodes a protobuf. Flags are the same flags passed to pb_decode_ex. + * + * @param[in] msg The message to decode into + * @param[in] flags Flags to pass + * @return true if decoding was successful, false otherwise + */ + bool Decode(typename Protobuf>::MessageStruct& msg, + unsigned int flags = 0) { + return pb_decode_ex(Stream(), m_msgDesc, &msg, flags); + } + + private: + pb_istream_t m_streamLocal; + pb_istream_t* m_streamMsg{nullptr}; + const pb_msgdesc_t* m_msgDesc; +}; + +/** + * Class for wrapping a nanopb ostream + */ +template +class ProtoOutputStream { + public: + /** + * Constructs a nanopb ostream from an existing ostream object + * Generally used internally for encoding messages. + * + * This constructor will cause `Encode` to call pb_encode_submessage + * instead of `pb_encode_ex` + * + * @param[in] stream the nanopb ostream + */ + explicit ProtoOutputStream(pb_ostream_t* stream) + : m_streamMsg{stream}, + m_msgDesc{ + Protobuf>::MessageStruct::msg_descriptor()} { + } + + /** + * Constructs a nanopb ostream from a buffer. + * + * This constructor will cause `Encode` to call pb_encode_ex` + * + * @param[in] out the stream buffer + */ + explicit ProtoOutputStream(detail::SmallVectorType& out) + : m_msgDesc{ + Protobuf>::MessageStruct::msg_descriptor()} { + m_streamLocal.callback = detail::WriteFromSmallVector; + m_streamLocal.state = &out; + m_streamLocal.max_size = SIZE_MAX; + m_streamLocal.bytes_written = 0; + m_streamLocal.errmsg = nullptr; + } + + /** + * Constructs a nanopb ostream from a buffer. + * + * This constructor will cause `Encode` to call pb_encode_ex` + * + * @param[in] out the stream buffer + */ + explicit ProtoOutputStream(detail::StdVectorType& out) + : m_msgDesc{ + Protobuf>::MessageStruct::msg_descriptor()} { + m_streamLocal.callback = detail::WriteFromStdVector; + m_streamLocal.state = &out; + m_streamLocal.max_size = SIZE_MAX; + m_streamLocal.bytes_written = 0; + m_streamLocal.errmsg = nullptr; + } + + /** + * Constructs a empty nanopb stream. You must fill out the stream + * returned from `Stream` before calling Encode. + * + * This constructor exists to cause `Encode` to call pb_encode_ex`, + * but allow manipulating the stream manually. + */ + ProtoOutputStream() + : m_msgDesc{Protobuf< + std::remove_cvref_t>::MessageStruct::msg_descriptor()} {} + + /** + * Gets the backing nanopb stream object. + * + * @return nanopb stream + */ + pb_ostream_t* Stream() noexcept { + return m_streamMsg ? m_streamMsg : &m_streamLocal; + } + + /** + * Gets if this stream points to a submessage, and will call + * pb_encode_submessage instead of pb_encode + * + * @return true if submessage, false otherwise + */ + bool IsSubmessage() const noexcept { return m_streamMsg; } + + /** + * Gets the nanopb message descriptor + * + * @return the nanopb message descriptor + */ + const pb_msgdesc_t* MsgDesc() const noexcept { return m_msgDesc; } + + /** + * Decodes a protobuf. Flags are the same flags passed to pb_decode_ex. + * + * @param[in] msg The message to encode from + * @return true if encoding was successful, false otherwise + */ + bool Encode( + const typename Protobuf>::MessageStruct& msg) { + if (m_streamMsg) { + return pb_encode_submessage(m_streamMsg, m_msgDesc, &msg); + } + return pb_encode(&m_streamLocal, m_msgDesc, &msg); + } + + private: + pb_ostream_t m_streamLocal; + pb_ostream_t* m_streamMsg{nullptr}; + const pb_msgdesc_t* m_msgDesc; +}; + /** * Specifies that a type is capable of protobuf serialization and * deserialization. * * This is designed for serializing complex flexible data structures using * code generated from a .proto file. Serialization consists of writing - * values into a mutable protobuf Message and deserialization consists of - * reading values from an immutable protobuf Message. + * values into a nanopb Stream and deserialization consists of + * reading values from nanopb Stream. * * Implementations must define a template specialization for wpi::Protobuf with * T being the type that is being serialized/deserialized, with the following * static members (as enforced by this concept): - * - google::protobuf::Message* New(google::protobuf::Arena*): create a protobuf - * message - * - T Unpack(const google::protobuf::Message&): function for deserialization - * - void Pack(google::protobuf::Message*, T&& value): function for - * serialization + * - using MessageStruct = nanopb_message_struct_here: typedef to the wpilib + * modified nanopb message struct + * - std::optional Unpack(wpi::ProtoInputStream&): function + * for deserialization + * - bool Pack(wpi::ProtoOutputStream&, T&& value): function + * for serialization * - * To avoid pulling in the protobuf headers, these functions use - * google::protobuf::Message instead of a more specific type; implementations - * will need to static_cast to the correct type as created by New(). - * - * Additionally: In a static block, call StructRegistry.registerClass() to - * register the class + * As a suggestion, 2 extra type usings can be added to simplify the stream + * definitions, however these are not required. + * - using InputStream = wpi::ProtoInputStream; + * - using OutputStream = wpi::ProtoOutputStream; */ template concept ProtobufSerializable = requires( - google::protobuf::Arena* arena, const google::protobuf::Message& inmsg, - google::protobuf::Message* outmsg, const T& value) { + wpi::ProtoOutputStream>& ostream, + wpi::ProtoInputStream>& istream, const T& value) { typename Protobuf>; { - Protobuf>::New(arena) - } -> std::same_as; + Protobuf>::Unpack(istream) + } -> std::same_as>>; { - Protobuf>::Unpack(inmsg) - } -> std::same_as>; - Protobuf>::Pack(outmsg, value); + Protobuf>::Pack(ostream, value) + } -> std::same_as; + typename Protobuf>::MessageStruct; + { + Protobuf>::MessageStruct::msg_descriptor() + } -> std::same_as; + { + Protobuf>::MessageStruct::msg_name() + } -> std::same_as; + { + Protobuf>::MessageStruct::file_descriptor() + } -> std::same_as; }; /** @@ -85,146 +271,22 @@ concept ProtobufSerializable = requires( * * In addition to meeting ProtobufSerializable, implementations must define a * wpi::Protobuf static member - * `void UnpackInto(T*, const google::protobuf::Message&)` to update the - * pointed-to T with the contents of the message. + * - bool UnpackInto(T*, wpi::ProtoInputStream&)` to update the + * pointed-to T with the contents of the message. */ template concept MutableProtobufSerializable = ProtobufSerializable && - requires(T* out, const google::protobuf::Message& msg) { - Protobuf>::UnpackInto(out, msg); + requires(T* out, wpi::ProtoInputStream& istream) { + { + Protobuf>::UnpackInto(out, istream) + } -> std::same_as; }; -/** - * Unpack a serialized protobuf message. - * - * @tparam T object type - * @param msg protobuf message - * @return Deserialized object - */ -template -inline T UnpackProtobuf(const google::protobuf::Message& msg) { - return Protobuf::Unpack(msg); -} - -/** - * Unpack a serialized protobuf array message. - * - * @tparam Proto element type of the protobuf array - * @tparam T object type - * @tparam N number of objects - * @param msg protobuf array message - * @return Deserialized array - */ -template Proto, - ProtobufSerializable T, size_t N> -wpi::array UnpackProtobufArray( - const google::protobuf::RepeatedPtrField& msg) { - if (N != std::dynamic_extent && msg.size() != N) { - // TODO - } - wpi::array arr(wpi::empty_array); - for (size_t i = 0; i < N; i++) { - arr[i] = wpi::UnpackProtobuf(msg.Get(i)); - } - return arr; -} - -/** - * Unpack a serialized protobuf array message. - * - * @tparam T element type of the protobuf array - * @tparam N number of objects - * @param msg protobuf array message - * @return Deserialized array - */ -template -wpi::array UnpackProtobufArray( - const google::protobuf::RepeatedField& msg) { - if (N != std::dynamic_extent && msg.size() != N) { - // TODO - } - wpi::array arr(wpi::empty_array); - for (size_t i = 0; i < N; i++) { - arr[i] = msg.Get(i); - } - return arr; -} - -/** - * Pack a serialized protobuf message. - * - * @param msg protobuf message (mutable, output) - * @param value object - */ -template -inline void PackProtobuf(google::protobuf::Message* msg, const T& value) { - Protobuf>::Pack(msg, value); -} - -/** - * Pack a serialized protobuf array message. - * - * @tparam Proto element type of the protobuf array - * @tparam T object type - * @tparam N number of objects - * @param msg protobuf message (mutable, output) - * @param arr array of objects - */ -template Proto, - ProtobufSerializable T, size_t N> -void PackProtobufArray(google::protobuf::RepeatedPtrField* msg, - const wpi::array& arr) { - msg->Clear(); - msg->Reserve(N); - for (const auto& obj : arr) { - PackProtobuf(msg->Add(), obj); - } -} - -/** - * Pack a serialized protobuf array message. - * - * @tparam T object type - * @tparam N number of objects - * @param msg protobuf message (mutable, output) - * @param arr array of objects - */ -template -void PackProtobufArray(google::protobuf::RepeatedField* msg, - const wpi::array& arr) { - msg->Clear(); - msg->Reserve(N); - msg->Add(arr.begin(), arr.end()); -} - -/** - * Unpack a serialized struct into an existing object, overwriting its contents. - * - * @param out object (output) - * @param msg protobuf message - */ -template -inline void UnpackProtobufInto(T* out, const google::protobuf::Message& msg) { - if constexpr (MutableProtobufSerializable) { - Protobuf::UnpackInto(out, msg); - } else { - *out = UnpackProtobuf(msg); - } -} - -// these detail functions avoid the need to include protobuf headers namespace detail { -void DeleteProtobuf(google::protobuf::Message* msg); -bool ParseProtobuf(google::protobuf::Message* msg, - std::span data); -bool SerializeProtobuf(wpi::SmallVectorImpl& out, - const google::protobuf::Message& msg); -bool SerializeProtobuf(std::vector& out, - const google::protobuf::Message& msg); -std::string GetTypeString(const google::protobuf::Message& msg); +std::string GetTypeString(const pb_msgdesc_t* msg); void ForEachProtobufDescriptor( - const google::protobuf::Message& msg, + const pb_msgdesc_t* msg, function_ref wants, function_ref descriptor)> @@ -232,48 +294,23 @@ void ForEachProtobufDescriptor( } // namespace detail /** - * Owning wrapper (ala std::unique_ptr) for google::protobuf::Message* that does - * not require the protobuf headers be included. Note this object is not thread - * safe; users of this object are required to provide any necessary thread - * safety. + * Ease of use wrapper to make nanopb streams more opaque to the user. + * This class is stateless and thread safe. * * @tparam T serialized object type */ template class ProtobufMessage { public: - explicit ProtobufMessage(google::protobuf::Arena* arena = nullptr) - : m_msg{Protobuf::New(arena)} {} - ~ProtobufMessage() { detail::DeleteProtobuf(m_msg); } - ProtobufMessage(const ProtobufMessage&) = delete; - ProtobufMessage& operator=(const ProtobufMessage&) = delete; - ProtobufMessage(ProtobufMessage&& rhs) : m_msg{rhs.m_msg} { - rhs.m_msg = nullptr; - } - ProtobufMessage& operator=(ProtobufMessage&& rhs) { - std::swap(m_msg, rhs.m_msg); - return *this; - } - - /** - * Gets the stored message object. - * - * @return google::protobuf::Message* - */ - google::protobuf::Message* GetMessage() { return m_msg; } - const google::protobuf::Message* GetMessage() const { return m_msg; } - /** * Unpacks from a byte array. * * @param data byte array * @return Optional; empty if parsing failed */ - std::optional Unpack(std::span data) { - if (!detail::ParseProtobuf(m_msg, data)) { - return std::nullopt; - } - return Protobuf::Unpack(*m_msg); + std::optional> Unpack(std::span data) { + ProtoInputStream> stream{data}; + return Protobuf>::Unpack(stream); } /** @@ -284,11 +321,17 @@ class ProtobufMessage { * @return true if successful */ bool UnpackInto(T* out, std::span data) { - if (!detail::ParseProtobuf(m_msg, data)) { - return false; + if constexpr (MutableProtobufSerializable) { + ProtoInputStream> stream{data}; + return Protobuf>::UnpackInto(out, stream); + } else { + auto unpacked = Unpack(data); + if (!unpacked) { + return false; + } + *out = std::move(unpacked.value()); + return true; } - UnpackProtobufInto(out, *m_msg); - return true; } /** @@ -299,8 +342,8 @@ class ProtobufMessage { * @return true if successful */ bool Pack(wpi::SmallVectorImpl& out, const T& value) { - Protobuf::Pack(m_msg, value); - return detail::SerializeProtobuf(out, *m_msg); + ProtoOutputStream> stream{out}; + return Protobuf>::Pack(stream, value); } /** @@ -311,8 +354,8 @@ class ProtobufMessage { * @return true if successful */ bool Pack(std::vector& out, const T& value) { - Protobuf::Pack(m_msg, value); - return detail::SerializeProtobuf(out, *m_msg); + ProtoOutputStream> stream{out}; + return Protobuf>::Pack(stream, value); } /** @@ -320,7 +363,10 @@ class ProtobufMessage { * * @return type string */ - std::string GetTypeString() const { return detail::GetTypeString(*m_msg); } + std::string GetTypeString() const { + return detail::GetTypeString( + Protobuf>::MessageStruct::msg_descriptor()); + } /** * Loops over all protobuf descriptors including nested/referenced @@ -335,11 +381,10 @@ class ProtobufMessage { function_ref descriptor)> fn) { - detail::ForEachProtobufDescriptor(*m_msg, exists, fn); + detail::ForEachProtobufDescriptor( + Protobuf>::MessageStruct::msg_descriptor(), + exists, fn); } - - private: - google::protobuf::Message* m_msg = nullptr; }; } // namespace wpi diff --git a/wpiutil/src/main/native/include/wpi/protobuf/ProtobufCallbacks.h b/wpiutil/src/main/native/include/wpi/protobuf/ProtobufCallbacks.h new file mode 100644 index 0000000000..277329ebaa --- /dev/null +++ b/wpiutil/src/main/native/include/wpi/protobuf/ProtobufCallbacks.h @@ -0,0 +1,670 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include +#include +#include + +#include + +#include "pb.h" +#include "wpi/SmallVector.h" +#include "wpi/array.h" +#include "wpi/protobuf/Protobuf.h" + +namespace wpi { + +/** + * The behavior to use when more elements are in the message then expected when + * decoding. + */ +enum class DecodeLimits { + // Ignore any extra elements + Ignore, + // Add any extra elements to the backing vector + Add, + // Cause decoding to fail if extra elements exist + Fail, +}; + +template +concept StringLike = std::is_convertible_v; + +template +concept ConstVectorLike = std::is_convertible_v>; + +template +concept MutableVectorLike = std::is_convertible_v>; + +template +concept PackBytes = StringLike || ConstVectorLike; + +template +concept UnpackBytes = requires(T& t) { + { t.resize(size_t()) }; // NOLINT + { t.size() } -> std::same_as; + { t.data() } -> std::convertible_to; +} && (PackBytes || MutableVectorLike); + +template +concept ProtoEnumeration = std::is_enum_v; + +template +concept ProtoPackable = + ProtoEnumeration || std::integral || std::floating_point; + +template +concept ProtoCallbackPackable = + ProtobufSerializable || PackBytes || ProtoPackable; + +template +concept ProtoCallbackUnpackable = + ProtobufSerializable || UnpackBytes || ProtoPackable; + +namespace detail { + +template +concept Validatable = ProtoCallbackPackable || ProtoCallbackUnpackable; + +template +constexpr bool ValidateType(pb_type_t type) { + switch (type) { + case PB_LTYPE_BOOL: + return std::integral; + case PB_LTYPE_VARINT: + return std::signed_integral || ProtoEnumeration; + case PB_LTYPE_UVARINT: + return std::unsigned_integral; + case PB_LTYPE_SVARINT: + return std::signed_integral; + case PB_LTYPE_FIXED32: + return std::integral || std::floating_point; + case PB_LTYPE_FIXED64: + return std::integral || std::floating_point; + case PB_LTYPE_BYTES: + case PB_LTYPE_STRING: + return PackBytes || UnpackBytes; + case PB_LTYPE_SUBMESSAGE: + return ProtobufSerializable; + default: + return false; + } +} + +} // namespace detail + +/** + * A callback method that will directly unpack elements into + * the specified vector like data structure. The size passed + * is the expected number of elements. + * + * By default, any elements in the packed buffer past N will + * still be added to the vector. + * + * @tparam T object type + * @tparam U vector type to pack into + * @tparam N number of elements + */ +template +class DirectUnpackCallback { + public: + /** + * Constructs a callback from a vector like type. + * + * @param storage the vector to store into + */ + explicit DirectUnpackCallback(U& storage) : m_storage{storage} { + m_callback.funcs.decode = CallbackFunc; + m_callback.arg = this; + } + DirectUnpackCallback(const DirectUnpackCallback&) = delete; + DirectUnpackCallback(DirectUnpackCallback&&) = delete; + DirectUnpackCallback& operator=(const DirectUnpackCallback&) = delete; + DirectUnpackCallback& operator=(DirectUnpackCallback&&) = delete; + + /** + * Set the limits on what happens if more elements exist in the buffer then + * expected. + * + * @param limit the limit to set + */ + void SetLimits(DecodeLimits limit) noexcept { m_limits = limit; } + + /** + * Gets the nanopb callback pointing to this object. + * + * @return nanopb callback + */ + pb_callback_t Callback() const { return m_callback; } + + private: + bool SizeCheck(bool* retVal) const { + if (m_storage.size() >= N) { + switch (m_limits) { + case DecodeLimits::Ignore: + *retVal = true; + return false; + + case DecodeLimits::Add: + break; + + default: + *retVal = false; + return false; + } + } + return true; + } + + bool Decode(pb_istream_t* stream, pb_type_t fieldType) { + if constexpr (ProtoPackable) { + switch (fieldType) { + case PB_LTYPE_BOOL: + if constexpr (std::integral) { + bool val = false; + if (!pb_decode_bool(stream, &val)) { + return false; + } + m_storage.emplace_back(static_cast(val)); + return true; + } else { + return false; + } + case PB_LTYPE_VARINT: + if constexpr (std::signed_integral || ProtoEnumeration) { + int64_t val = 0; + if (!pb_decode_varint(stream, reinterpret_cast(&val))) { + return false; + } + m_storage.emplace_back(static_cast(val)); + return true; + } else { + return false; + } + case PB_LTYPE_UVARINT: + if constexpr (std::unsigned_integral) { + uint64_t val = 0; + if (!pb_decode_varint(stream, &val)) { + return false; + } + m_storage.emplace_back(static_cast(val)); + return true; + } else { + return false; + } + case PB_LTYPE_SVARINT: + if constexpr (std::signed_integral) { + int64_t val = 0; + if (!pb_decode_svarint(stream, &val)) { + return false; + } + m_storage.emplace_back(static_cast(val)); + return true; + } else { + return false; + } + case PB_LTYPE_FIXED32: + if constexpr (std::signed_integral) { + int32_t val = 0; + if (!pb_decode_fixed32(stream, &val)) { + return false; + } + m_storage.emplace_back(static_cast(val)); + return true; + } else if constexpr (std::unsigned_integral) { + uint32_t val = 0; + if (!pb_decode_fixed32(stream, &val)) { + return false; + } + m_storage.emplace_back(static_cast(val)); + return true; + } + if constexpr (std::floating_point) { + float val = 0; + if (!pb_decode_fixed32(stream, &val)) { + return false; + } + m_storage.emplace_back(static_cast(val)); + return true; + } else { + return false; + } + case PB_LTYPE_FIXED64: + if constexpr (std::signed_integral) { + int64_t val = 0; + if (!pb_decode_fixed64(stream, &val)) { + return false; + } + m_storage.emplace_back(static_cast(val)); + return true; + } else if constexpr (std::unsigned_integral) { + uint64_t val = 0; + if (!pb_decode_fixed64(stream, &val)) { + return false; + } + m_storage.emplace_back(static_cast(val)); + return true; + } + if constexpr (std::floating_point) { + double val = 0; + if (!pb_decode_fixed64(stream, &val)) { + return false; + } + m_storage.emplace_back(static_cast(val)); + return true; + } else { + return false; + } + default: + return false; + } + } else if constexpr (UnpackBytes) { + T& space = m_storage.emplace_back(T{}); + space.resize(stream->bytes_left); + return pb_read(stream, reinterpret_cast(space.data()), + space.size()); + } else if constexpr (ProtobufSerializable) { + ProtoInputStream istream{stream}; + auto decoded = wpi::Protobuf::Unpack(istream); + if (decoded.has_value()) { + m_storage.emplace_back(std::move(decoded.value())); + return true; + } + return false; + } + } + + bool CallbackFunc(pb_istream_t* stream, const pb_field_t* field) { + pb_type_t fieldType = PB_LTYPE(field->type); + + if (!detail::ValidateType(fieldType)) { + return false; + } + + // Validate our types + if constexpr (ProtoPackable) { + // Handle decode loop + while (stream->bytes_left > 0) { + bool sizeRetVal = 0; + if (!SizeCheck(&sizeRetVal)) { + return sizeRetVal; + } + + if (!Decode(stream, fieldType)) { + return false; + } + } + return true; + } else { + // At this point, do the size check + bool sizeRetVal = 0; + if (!SizeCheck(&sizeRetVal)) { + return sizeRetVal; + } + + // At this point, we're good to decode + return Decode(stream, fieldType); + } + } + + static bool CallbackFunc(pb_istream_t* stream, const pb_field_t* field, + void** arg) { + return reinterpret_cast(*arg)->CallbackFunc(stream, + field); + } + + U& m_storage; + pb_callback_t m_callback; + DecodeLimits m_limits{DecodeLimits::Add}; +}; + +/** + * A DirectUnpackCallback backed by a SmallVector. + * + * By default, any elements in the packed buffer past N will + * be ignored, but decoding will still succeed + * + * @tparam T object type + * @tparam N small vector small size/number of expected elements + */ +template +class UnpackCallback + : public DirectUnpackCallback, N> { + public: + /** + * Constructs an UnpackCallback. + */ + UnpackCallback() + : DirectUnpackCallback, N>{m_storedBuffer} { + this->SetLimits(DecodeLimits::Ignore); + } + + /** + * Gets a span pointing to the storage buffer. + * + * @return storage buffer span + */ + std::span Items() noexcept { return m_storedBuffer; } + + /** + * Gets a const span pointing to the storage buffer. + * + * @return storage buffer span + */ + std::span Items() const noexcept { return m_storedBuffer; } + + /** + * Gets a reference to the backing small vector. + * + * @return small vector reference + */ + wpi::SmallVector& Vec() noexcept { return m_storedBuffer; } + + private: + wpi::SmallVector m_storedBuffer; +}; + +/** + * A DirectUnpackCallback backed by a std::vector. + * + * By default, any elements in the packed buffer past N will + * be ignored, but decoding will still succeed + * + * @tparam T object type + * @tparam N number of expected elements + */ +template +class StdVectorUnpackCallback + : public DirectUnpackCallback, N> { + public: + /** + * Constructs a StdVectorUnpackCallback. + */ + StdVectorUnpackCallback() + : DirectUnpackCallback, N>{m_storedBuffer} { + this->SetLimits(DecodeLimits::Ignore); + } + + /** + * Gets a span pointing to the storage buffer. + * + * @return storage buffer span + */ + std::span Items() noexcept { return m_storedBuffer; } + + /** + * Gets a const span pointing to the storage buffer. + * + * @return storage buffer span + */ + std::span Items() const noexcept { return m_storedBuffer; } + + /** + * Gets a reference to the backing vector. + * + * @return vector reference + */ + std::vector& Vec() noexcept { return m_storedBuffer; } + + private: + std::vector m_storedBuffer; +}; + +/** + * A wrapper around a wpi::array that lets us + * treat it as a limited sized vector. + */ +template +struct WpiArrayEmplaceWrapper { + wpi::array m_array{wpi::empty_array_t{}}; + size_t m_currentIndex = 0; + + size_t size() const { return m_currentIndex; } + + template + T& emplace_back(ArgTypes&&... Args) { + m_array[m_currentIndex] = T(std::forward(Args)...); + m_currentIndex++; + return m_array[m_currentIndex - 1]; + } +}; + +/** + * A DirectUnpackCallback backed by a wpi::array. + * + * Any elements in the packed buffer past N will + * be cause decoding to fail. + * + * @tparam T object type + * @tparam N small vector small size/number of expected elements + */ +template +struct WpiArrayUnpackCallback + : public DirectUnpackCallback, N> { + /** + * Constructs a WpiArrayUnpackCallback. + */ + WpiArrayUnpackCallback() + : DirectUnpackCallback, N>{m_array} { + this->SetLimits(DecodeLimits::Fail); + } + + /** + * Returns if the buffer is completely filled up. + * + * @return true if buffer is full + */ + bool IsFull() const noexcept { return m_array.m_currentIndex == N; } + + /** + * Returns the number of elements in the buffer. + * + * @return number of elements + */ + size_t Size() const noexcept { return m_array.m_currentIndex; } + + /** + * Returns a reference to the backing array. + * + * @return array reference + */ + wpi::array& Array() noexcept { return m_array.m_array; } + + private: + WpiArrayEmplaceWrapper m_array; +}; + +/** + * A callback method that will pack elements when called. + * + * @tparam T object type + */ +template +class PackCallback { + public: + /** + * Constructs a pack callback from a span of elements. The elements in the + * buffer _MUST_ stay alive throughout the entire encode call. + */ + explicit PackCallback(std::span buffer) : m_buffer{buffer} { + m_callback.funcs.encode = CallbackFunc; + m_callback.arg = this; + } + + /** + * Constructs a pack callback from a pointer to a single element. + * This element _MUST_ stay alive throughout the entire encode call. + * Do not pass a temporary here (This is why its a pointer and not a + * reference) + */ + explicit PackCallback(const T* element) + : m_buffer{std::span{element, 1}} { + m_callback.funcs.encode = CallbackFunc; + m_callback.arg = this; + } + PackCallback(const PackCallback&) = delete; + PackCallback(PackCallback&&) = delete; + PackCallback& operator=(const PackCallback&) = delete; + PackCallback& operator=(PackCallback&&) = delete; + + /** + * Gets the nanopb callback pointing to this object. + * + * @return nanopb callback + */ + pb_callback_t Callback() const { return m_callback; } + + /** + * Gets a span pointing to the items + * + * @return span + */ + std::span Bufs() const { return m_buffer; } + + private: + static auto EncodeStreamTypeFinder() { + if constexpr (ProtobufSerializable) { + return ProtoOutputStream(nullptr); + } else { + return pb_ostream_t{}; + } + } + using EncodeStreamType = decltype(EncodeStreamTypeFinder()); + + bool EncodeItem(EncodeStreamType& stream, const pb_field_t* field, + const T& value) const { + if constexpr (std::floating_point) { + pb_type_t fieldType = PB_LTYPE(field->type); + switch (fieldType) { + case PB_LTYPE_FIXED32: { + float flt = static_cast(value); + return pb_encode_fixed32(&stream, &flt); + } + case PB_LTYPE_FIXED64: { + double dbl = static_cast(value); + return pb_encode_fixed64(&stream, &dbl); + } + default: + return false; + } + } else if constexpr (std::integral || ProtoEnumeration) { + pb_type_t fieldType = PB_LTYPE(field->type); + switch (fieldType) { + case PB_LTYPE_BOOL: + case PB_LTYPE_VARINT: + case PB_LTYPE_UVARINT: + return pb_encode_varint(&stream, value); + case PB_LTYPE_SVARINT: + return pb_encode_svarint(&stream, value); + case PB_LTYPE_FIXED32: { + uint32_t f = value; + return pb_encode_fixed32(&stream, &f); + } + case PB_LTYPE_FIXED64: { + uint64_t f = value; + return pb_encode_fixed64(&stream, &f); + } + default: + return false; + } + } else if constexpr (StringLike) { + std::string_view view{value}; + return pb_encode_string(&stream, + reinterpret_cast(view.data()), + view.size()); + } else if constexpr (ConstVectorLike) { + std::span view{value}; + return pb_encode_string(&stream, + reinterpret_cast(view.data()), + view.size()); + } else if constexpr (ProtobufSerializable) { + return wpi::Protobuf::Pack(stream, value); + } + } + + bool EncodeLoop(pb_ostream_t* stream, const pb_field_t* field, + bool writeTag) const { + if constexpr (ProtobufSerializable) { + ProtoOutputStream ostream{stream}; + for (auto&& i : m_buffer) { + if (writeTag) { + if (!pb_encode_tag_for_field(stream, field)) { + return false; + } + } + if (!EncodeItem(ostream, field, i)) { + return false; + } + } + } else { + for (auto&& i : m_buffer) { + if (writeTag) { + if (!pb_encode_tag_for_field(stream, field)) { + return false; + } + } + if (!EncodeItem(*stream, field, i)) { + return false; + } + } + } + + return true; + } + + bool PackedEncode(pb_ostream_t* stream, const pb_field_t* field) const { + // We're always going to used packed encoding. + // So first we need to get the packed size. + + pb_ostream_t substream = PB_OSTREAM_SIZING; + if (!EncodeLoop(&substream, field, false)) { + return false; + } + + // Encode as a string tag + if (!pb_encode_tag(stream, PB_WT_STRING, field->tag)) { + return false; + } + + // Write length as varint + size_t size = substream.bytes_written; + if (!pb_encode_varint(stream, static_cast(size))) { + return false; + } + + return EncodeLoop(stream, field, false); + } + + bool CallbackFunc(pb_ostream_t* stream, const pb_field_t* field) const { + // First off, if we're empty, do nothing, but say we were successful + if (m_buffer.empty()) { + return true; + } + + pb_type_t fieldType = PB_LTYPE(field->type); + + if (!detail::ValidateType(fieldType)) { + return false; + } + + if constexpr (ProtoPackable) { + return PackedEncode(stream, field); + } else { + return EncodeLoop(stream, field, true); + } + } + + static bool CallbackFunc(pb_ostream_t* stream, const pb_field_t* field, + void* const* arg) { + return reinterpret_cast(*arg)->CallbackFunc(stream, + field); + } + + std::span m_buffer; + pb_callback_t m_callback; +}; + +} // namespace wpi diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/__init__.py b/wpiutil/src/main/native/thirdparty/nanopb/generator/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator b/wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator new file mode 100644 index 0000000000..429aa13ee2 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator @@ -0,0 +1,7 @@ +#!/usr/bin/env python3 +# Allow calling nanopb_generator.py as simply nanopb_generator. +# This provides consistency with packages installed through CMake or pip. + +from nanopb_generator import * +if __name__ == '__main__': + main_cli() diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator.bat b/wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator.bat new file mode 100644 index 0000000000..d2083164ad --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator.bat @@ -0,0 +1,5 @@ +@echo off +:: Allow calling nanopb_generator.py as simply nanopb_generator. +:: This provides consistency with packages installed through CMake or pip. +set mydir=%~dp0 +python "%mydir%\nanopb_generator.py" %* diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator.py b/wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator.py new file mode 100644 index 0000000000..01fc349538 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator.py @@ -0,0 +1,2780 @@ +#!/usr/bin/env python3 +# kate: replace-tabs on; indent-width 4; + +# Modified for WPILib use + +from __future__ import unicode_literals + +'''Generate header file for nanopb from a ProtoBuf FileDescriptorSet.''' +nanopb_version = "nanopb-0.4.9" + +import sys +import re +import codecs +import copy +import itertools +import tempfile +import shutil +import shlex +import os +from functools import reduce + +# Python-protobuf breaks easily with protoc version differences if +# using the cpp or upb implementation. Force it to use pure Python +# implementation. Performance is not very important in the generator. +if not os.getenv("PROTOCOL_BUFFERS_PYTHON_IMPLEMENTATION"): + os.putenv("PROTOCOL_BUFFERS_PYTHON_IMPLEMENTATION", "python") + os.environ["PROTOCOL_BUFFERS_PYTHON_IMPLEMENTATION"] = "python" + +try: + # Make sure grpc_tools gets included in binary package if it is available + import grpc_tools.protoc +except: + pass + +try: + import google.protobuf.text_format as text_format + import google.protobuf.descriptor_pb2 as descriptor + import google.protobuf.compiler.plugin_pb2 as plugin_pb2 + import google.protobuf.reflection as reflection + import google.protobuf.descriptor +except: + sys.stderr.write(''' + ********************************************************************** + *** Could not import the Google protobuf Python libraries *** + *** *** + *** Easiest solution is often to install the dependencies via pip: *** + *** pip install protobuf grpcio-tools *** + ********************************************************************** + ''' + '\n') + raise + +# Depending on how this script is run, we may or may not have PEP366 package name +# available for relative imports. +if not __package__: + import proto + from proto._utils import invoke_protoc + from proto import TemporaryDirectory +else: + from . import proto + from .proto._utils import invoke_protoc + from .proto import TemporaryDirectory + +if getattr(sys, 'frozen', False): + # Binary package, just import the file + from proto import nanopb_pb2 +else: + # Import nanopb_pb2.py, rebuilds if necessary and not disabled + # by env variable NANOPB_PB2_NO_REBUILD + nanopb_pb2 = proto.load_nanopb_pb2() + +try: + # Add some dummy imports to keep packaging tools happy. + import google # bbfreeze seems to need these + from proto import nanopb_pb2 # pyinstaller seems to need this +except: + # Don't care, we will error out later if it is actually important. + pass + +# --------------------------------------------------------------------------- +# Generation of single fields +# --------------------------------------------------------------------------- + +import time +import os.path + +# Values are tuple (c type, pb type, encoded size, data_size) +FieldD = descriptor.FieldDescriptorProto +datatypes = { + FieldD.TYPE_BOOL: ('bool', 'BOOL', 1, 4), + FieldD.TYPE_DOUBLE: ('double', 'DOUBLE', 8, 8), + FieldD.TYPE_FIXED32: ('uint32_t', 'FIXED32', 4, 4), + FieldD.TYPE_FIXED64: ('uint64_t', 'FIXED64', 8, 8), + FieldD.TYPE_FLOAT: ('float', 'FLOAT', 4, 4), + FieldD.TYPE_INT32: ('int32_t', 'INT32', 10, 4), + FieldD.TYPE_INT64: ('int64_t', 'INT64', 10, 8), + FieldD.TYPE_SFIXED32: ('int32_t', 'SFIXED32', 4, 4), + FieldD.TYPE_SFIXED64: ('int64_t', 'SFIXED64', 8, 8), + FieldD.TYPE_SINT32: ('int32_t', 'SINT32', 5, 4), + FieldD.TYPE_SINT64: ('int64_t', 'SINT64', 10, 8), + FieldD.TYPE_UINT32: ('uint32_t', 'UINT32', 5, 4), + FieldD.TYPE_UINT64: ('uint64_t', 'UINT64', 10, 8), + + # Integer size override option + (FieldD.TYPE_ENUM, nanopb_pb2.IS_8): ('uint8_t', 'ENUM', 4, 1), + (FieldD.TYPE_ENUM, nanopb_pb2.IS_16): ('uint16_t', 'ENUM', 4, 2), + (FieldD.TYPE_ENUM, nanopb_pb2.IS_32): ('uint32_t', 'ENUM', 4, 4), + (FieldD.TYPE_ENUM, nanopb_pb2.IS_64): ('uint64_t', 'ENUM', 4, 8), + (FieldD.TYPE_INT32, nanopb_pb2.IS_8): ('int8_t', 'INT32', 10, 1), + (FieldD.TYPE_INT32, nanopb_pb2.IS_16): ('int16_t', 'INT32', 10, 2), + (FieldD.TYPE_INT32, nanopb_pb2.IS_32): ('int32_t', 'INT32', 10, 4), + (FieldD.TYPE_INT32, nanopb_pb2.IS_64): ('int64_t', 'INT32', 10, 8), + (FieldD.TYPE_SINT32, nanopb_pb2.IS_8): ('int8_t', 'SINT32', 2, 1), + (FieldD.TYPE_SINT32, nanopb_pb2.IS_16): ('int16_t', 'SINT32', 3, 2), + (FieldD.TYPE_SINT32, nanopb_pb2.IS_32): ('int32_t', 'SINT32', 5, 4), + (FieldD.TYPE_SINT32, nanopb_pb2.IS_64): ('int64_t', 'SINT32', 10, 8), + (FieldD.TYPE_UINT32, nanopb_pb2.IS_8): ('uint8_t', 'UINT32', 2, 1), + (FieldD.TYPE_UINT32, nanopb_pb2.IS_16): ('uint16_t','UINT32', 3, 2), + (FieldD.TYPE_UINT32, nanopb_pb2.IS_32): ('uint32_t','UINT32', 5, 4), + (FieldD.TYPE_UINT32, nanopb_pb2.IS_64): ('uint64_t','UINT32', 10, 8), + (FieldD.TYPE_INT64, nanopb_pb2.IS_8): ('int8_t', 'INT64', 10, 1), + (FieldD.TYPE_INT64, nanopb_pb2.IS_16): ('int16_t', 'INT64', 10, 2), + (FieldD.TYPE_INT64, nanopb_pb2.IS_32): ('int32_t', 'INT64', 10, 4), + (FieldD.TYPE_INT64, nanopb_pb2.IS_64): ('int64_t', 'INT64', 10, 8), + (FieldD.TYPE_SINT64, nanopb_pb2.IS_8): ('int8_t', 'SINT64', 2, 1), + (FieldD.TYPE_SINT64, nanopb_pb2.IS_16): ('int16_t', 'SINT64', 3, 2), + (FieldD.TYPE_SINT64, nanopb_pb2.IS_32): ('int32_t', 'SINT64', 5, 4), + (FieldD.TYPE_SINT64, nanopb_pb2.IS_64): ('int64_t', 'SINT64', 10, 8), + (FieldD.TYPE_UINT64, nanopb_pb2.IS_8): ('uint8_t', 'UINT64', 2, 1), + (FieldD.TYPE_UINT64, nanopb_pb2.IS_16): ('uint16_t','UINT64', 3, 2), + (FieldD.TYPE_UINT64, nanopb_pb2.IS_32): ('uint32_t','UINT64', 5, 4), + (FieldD.TYPE_UINT64, nanopb_pb2.IS_64): ('uint64_t','UINT64', 10, 8), +} + +class NamingStyle: + def enum_name(self, name): + return "_%s" % (name) + + def struct_name(self, name): + return "_%s" % (name) + + def type_name(self, name): + return "%s" % (name) + + def define_name(self, name): + return "%s" % (name) + + def var_name(self, name): + return "%s" % (name) + + def enum_entry(self, name): + return "%s" % (name) + + def func_name(self, name): + return "%s" % (name) + + def bytes_type(self, struct_name, name): + return "%s_%s_t" % (struct_name, name) + +class NamingStyleC(NamingStyle): + def enum_name(self, name): + return self.underscore(name) + + def struct_name(self, name): + return self.underscore(name) + + def type_name(self, name): + return "%s_t" % self.underscore(name) + + def define_name(self, name): + return self.underscore(name).upper() + + def var_name(self, name): + return self.underscore(name) + + def enum_entry(self, name): + return self.underscore(name).upper() + + def func_name(self, name): + return self.underscore(name) + + def bytes_type(self, struct_name, name): + return "%s_%s_t" % (self.underscore(struct_name), self.underscore(name)) + + def underscore(self, word): + word = str(word) + word = re.sub(r"([A-Z]+)([A-Z][a-z])", r'\1_\2', word) + word = re.sub(r"([a-z\d])([A-Z])", r'\1_\2', word) + word = word.replace("-", "_") + return word.lower() + +class Globals: + '''Ugly global variables, should find a good way to pass these.''' + verbose_options = False + separate_options = [] + matched_namemasks = set() + protoc_insertion_points = False + naming_style = NamingStyle() + +# String types and file encoding for Python2 UTF-8 support +if sys.version_info.major == 2: + import codecs + open = codecs.open + strtypes = (unicode, str) + + def str(x): + try: + return strtypes[1](x) + except UnicodeEncodeError: + return strtypes[0](x) +else: + strtypes = (str, ) + + +class Names: + '''Keeps a set of nested names and formats them to C identifier.''' + def __init__(self, parts = ()): + if isinstance(parts, Names): + parts = parts.parts + elif isinstance(parts, strtypes): + parts = (parts,) + self.parts = tuple(parts) + + if self.parts == ('',): + self.parts = () + + def __str__(self): + return '_'.join(self.parts) + + def __repr__(self): + return 'Names(%s)' % ','.join("'%s'" % x for x in self.parts) + + def __add__(self, other): + if isinstance(other, strtypes): + return Names(self.parts + (other,)) + elif isinstance(other, Names): + return Names(self.parts + other.parts) + elif isinstance(other, tuple): + return Names(self.parts + other) + else: + raise ValueError("Name parts should be of type str") + + def __eq__(self, other): + return isinstance(other, Names) and self.parts == other.parts + + def __lt__(self, other): + if not isinstance(other, Names): + return NotImplemented + return str(self) < str(other) + +def names_from_type_name(type_name): + '''Parse Names() from FieldDescriptorProto type_name''' + if type_name[0] != '.': + raise NotImplementedError("Lookup of non-absolute type names is not supported") + return Names(type_name[1:].split('.')) + +def varint_max_size(max_value): + '''Returns the maximum number of bytes a varint can take when encoded.''' + if max_value < 0: + max_value = 2**64 - max_value + for i in range(1, 11): + if (max_value >> (i * 7)) == 0: + return i + raise ValueError("Value too large for varint: " + str(max_value)) + +assert varint_max_size(-1) == 10 +assert varint_max_size(0) == 1 +assert varint_max_size(127) == 1 +assert varint_max_size(128) == 2 + +class EncodedSize: + '''Class used to represent the encoded size of a field or a message. + Consists of a combination of symbolic sizes and integer sizes.''' + def __init__(self, value = 0, symbols = [], declarations = [], required_defines = []): + if isinstance(value, EncodedSize): + self.value = value.value + self.symbols = value.symbols + self.declarations = value.declarations + self.required_defines = value.required_defines + elif isinstance(value, strtypes + (Names,)): + self.symbols = [str(value)] + self.value = 0 + self.declarations = [] + self.required_defines = [str(value)] + else: + self.value = value + self.symbols = symbols + self.declarations = declarations + self.required_defines = required_defines + + def __add__(self, other): + if isinstance(other, int): + return EncodedSize(self.value + other, self.symbols, self.declarations, self.required_defines) + elif isinstance(other, strtypes + (Names,)): + return EncodedSize(self.value, self.symbols + [str(other)], self.declarations, self.required_defines + [str(other)]) + elif isinstance(other, EncodedSize): + return EncodedSize(self.value + other.value, self.symbols + other.symbols, + self.declarations + other.declarations, self.required_defines + other.required_defines) + else: + raise ValueError("Cannot add size: " + repr(other)) + + def __mul__(self, other): + if isinstance(other, int): + return EncodedSize(self.value * other, [str(other) + '*' + s for s in self.symbols], + self.declarations, self.required_defines) + else: + raise ValueError("Cannot multiply size: " + repr(other)) + + def __str__(self): + if not self.symbols: + return str(self.value) + else: + return '(' + str(self.value) + ' + ' + ' + '.join(self.symbols) + ')' + + def __repr__(self): + return 'EncodedSize(%s, %s, %s, %s)' % (self.value, self.symbols, self.declarations, self.required_defines) + + def get_declarations(self): + '''Get any declarations that must appear alongside this encoded size definition, + such as helper union {} types.''' + return '\n'.join(self.declarations) + + def get_cpp_guard(self, local_defines): + '''Get an #if preprocessor statement listing all defines that are required for this definition.''' + needed = [x for x in self.required_defines if x not in local_defines] + if needed: + return '#if ' + ' && '.join(['defined(%s)' % x for x in needed]) + "\n" + else: + return '' + + def upperlimit(self): + if not self.symbols: + return self.value + else: + return 2**32 - 1 + +class ProtoElement(object): + # Constants regarding path of proto elements in file descriptor. + # They are used to connect proto elements with source code information (comments) + # These values come from: + # https://github.com/google/protobuf/blob/master/src/google/protobuf/descriptor.proto + FIELD = 2 + MESSAGE = 4 + ENUM = 5 + NESTED_TYPE = 3 + NESTED_ENUM = 4 + + def __init__(self, path, comments = None): + ''' + path is a tuple containing integers (type, index, ...) + comments is a dictionary mapping between element path & SourceCodeInfo.Location + (contains information about source comments). + ''' + assert(isinstance(path, tuple)) + self.element_path = path + self.comments = comments or {} + + def get_member_comments(self, index): + '''Get comments for a member of enum or message.''' + return self.get_comments((ProtoElement.FIELD, index), leading_indent = True) + + def format_comment(self, comment): + '''Put comment inside /* */ and sanitize comment contents''' + comment = comment.strip() + comment = comment.replace('/*', '/ *') + comment = comment.replace('*/', '* /') + return "/* %s */" % comment + + def get_comments(self, member_path = (), leading_indent = False): + '''Get leading & trailing comments for a protobuf element. + + member_path is the proto path of an element or member (ex. [5 0] or [4 1 2 0]) + leading_indent is a flag that indicates if leading comments should be indented + ''' + + # Obtain SourceCodeInfo.Location object containing comment + # information (based on the member path) + path = self.element_path + member_path + comment = self.comments.get(path) + + leading_comment = "" + trailing_comment = "" + + if not comment: + return leading_comment, trailing_comment + + if comment.leading_comments: + leading_comment = " " if leading_indent else "" + leading_comment += self.format_comment(comment.leading_comments) + + if comment.trailing_comments: + trailing_comment = self.format_comment(comment.trailing_comments) + + return leading_comment, trailing_comment + + +class Enum(ProtoElement): + def __init__(self, names, desc, enum_options, element_path, comments): + ''' + desc is EnumDescriptorProto + index is the index of this enum element inside the file + comments is a dictionary mapping between element path & SourceCodeInfo.Location + (contains information about source comments) + ''' + super(Enum, self).__init__(element_path, comments) + + self.options = enum_options + self.names = names + + # by definition, `names` include this enum's name + base_name = Names(names.parts[:-1]) + + if enum_options.long_names: + self.values = [(names + x.name, x.number) for x in desc.value] + else: + self.values = [(base_name + x.name, x.number) for x in desc.value] + + self.value_longnames = [self.names + x.name for x in desc.value] + self.packed = enum_options.packed_enum + + def has_negative(self): + for n, v in self.values: + if v < 0: + return True + return False + + def encoded_size(self): + return max([varint_max_size(v) for n,v in self.values]) + + def __repr__(self): + return 'Enum(%s)' % self.names + + def __str__(self): + leading_comment, trailing_comment = self.get_comments() + + result = '' + if leading_comment: + result = '%s\n' % leading_comment + + result += 'typedef enum %s' % Globals.naming_style.enum_name(self.names) + + # Override the enum size if user wants to use smaller integers + if (FieldD.TYPE_ENUM, self.options.enum_intsize) in datatypes: + self.ctype, self.pbtype, self.enc_size, self.data_item_size = datatypes[(FieldD.TYPE_ENUM, self.options.enum_intsize)] + result += ': ' + self.ctype + + result += ' {' + + if trailing_comment: + result += " " + trailing_comment + + result += "\n" + + enum_length = len(self.values) + enum_values = [] + for index, (name, value) in enumerate(self.values): + leading_comment, trailing_comment = self.get_member_comments(index) + + if leading_comment: + enum_values.append(leading_comment) + + comma = "," + if index == enum_length - 1: + # last enum member should not end with a comma + comma = "" + + enum_value = " %s = %d%s" % (Globals.naming_style.enum_entry(name), value, comma) + if trailing_comment: + enum_value += " " + trailing_comment + + enum_values.append(enum_value) + + result += '\n'.join(enum_values) + result += '\n}' + + if self.packed: + result += ' pb_packed' + + result += ' %s;' % Globals.naming_style.type_name(self.names) + return result + + def auxiliary_defines(self): + # sort the enum by value + sorted_values = sorted(self.values, key = lambda x: (x[1], x[0])) + + unmangledName = self.protofile.manglenames.unmangle(self.names) + identifier = Globals.naming_style.define_name('_%s_MIN' % self.names) + result = '#define %s %s\n' % ( + identifier, + Globals.naming_style.enum_entry(sorted_values[0][0])) + if unmangledName: + unmangledIdentifier = Globals.naming_style.define_name('_%s_MIN' % unmangledName) + self.protofile.manglenames.reverse_name_mapping[identifier] = unmangledIdentifier + + identifier = Globals.naming_style.define_name('_%s_MAX' % self.names) + result += '#define %s %s\n' % ( + identifier, + Globals.naming_style.enum_entry(sorted_values[-1][0])) + if unmangledName: + unmangledIdentifier = Globals.naming_style.define_name('_%s_MAX' % unmangledName) + self.protofile.manglenames.reverse_name_mapping[identifier] = unmangledIdentifier + + identifier = Globals.naming_style.define_name('_%s_ARRAYSIZE' % self.names) + result += '#define %s ((%s)(%s+1))\n' % ( + identifier, + Globals.naming_style.type_name(self.names), + Globals.naming_style.enum_entry(sorted_values[-1][0])) + if unmangledName: + unmangledIdentifier = Globals.naming_style.define_name('_%s_ARRAYSIZE' % unmangledName) + self.protofile.manglenames.reverse_name_mapping[identifier] = unmangledIdentifier + + if not self.options.long_names: + # Define the long names always so that enum value references + # from other files work properly. + for i, x in enumerate(self.values): + result += '#define %s %s\n' % (Globals.naming_style.define_name(self.value_longnames[i]), Globals.naming_style.enum_entry(x[0])) + + if self.options.enum_to_string: + result += 'const char *%s(%s v);\n' % ( + Globals.naming_style.func_name('%s_name' % self.names), + Globals.naming_style.type_name(self.names)) + + if self.options.enum_validate: + result += 'bool %s(%s v);\n' % ( + Globals.naming_style.func_name('%s_valid' % self.names), + Globals.naming_style.type_name(self.names)) + + return result + + def enum_to_string_definition(self): + if not self.options.enum_to_string: + return "" + + result = 'const char *%s(%s v) {\n' % ( + Globals.naming_style.func_name('%s_name' % self.names), + Globals.naming_style.type_name(self.names)) + + result += ' switch (v) {\n' + + for ((enumname, _), strname) in zip(self.values, self.value_longnames): + # Strip off the leading type name from the string value. + strval = str(strname)[len(str(self.names)) + 1:] + result += ' case %s: return "%s";\n' % ( + Globals.naming_style.enum_entry(enumname), + Globals.naming_style.enum_entry(strval)) + + result += ' }\n' + result += ' return "unknown";\n' + result += '}\n' + + return result + + def enum_validate(self): + if not self.options.enum_validate: + return "" + + result = 'bool %s(%s v) {\n' % ( + Globals.naming_style.func_name('%s_valid' % self.names), + Globals.naming_style.type_name(self.names)) + + result += ' switch (v) {\n' + + for (enumname, _) in self.values: + result += ' case %s: return true;\n' % ( + Globals.naming_style.enum_entry(enumname) + ) + + result += ' }\n' + result += ' return false;\n' + result += '}\n' + + return result + + +class FieldMaxSize: + def __init__(self, worst = 0, checks = [], field_name = 'undefined'): + if isinstance(worst, list): + self.worst = max(i for i in worst if i is not None) + else: + self.worst = worst + + self.worst_field = field_name + self.checks = list(checks) + + def extend(self, extend, field_name = None): + self.worst = max(self.worst, extend.worst) + + if self.worst == extend.worst: + self.worst_field = extend.worst_field + + self.checks.extend(extend.checks) + +class Field(ProtoElement): + macro_x_param = 'X' + macro_a_param = 'a' + + def __init__(self, struct_name, desc, field_options, element_path = (), comments = None): + '''desc is FieldDescriptorProto''' + ProtoElement.__init__(self, element_path, comments) + self.tag = desc.number + self.struct_name = struct_name + self.union_name = None + self.name = desc.name + self.default = None + self.max_size = None + self.max_count = None + self.array_decl = "" + self.enc_size = None + self.data_item_size = None + self.ctype = None + self.fixed_count = False + self.callback_datatype = field_options.callback_datatype + self.math_include_required = False + self.sort_by_tag = field_options.sort_by_tag + + if field_options.type == nanopb_pb2.FT_INLINE: + # Before nanopb-0.3.8, fixed length bytes arrays were specified + # by setting type to FT_INLINE. But to handle pointer typed fields, + # it makes sense to have it as a separate option. + field_options.type = nanopb_pb2.FT_STATIC + field_options.fixed_length = True + + # Parse field options + if field_options.HasField("max_size"): + self.max_size = field_options.max_size + + if field_options.HasField("initializer"): + self.initializer = field_options.initializer + else: + self.initializer = None + + self.default_has = field_options.default_has + + if desc.type == FieldD.TYPE_STRING and field_options.HasField("max_length"): + # max_length overrides max_size for strings + self.max_size = field_options.max_length + 1 + + if field_options.HasField("max_count"): + self.max_count = field_options.max_count + + if desc.HasField('default_value'): + self.default = desc.default_value + + # Check field rules, i.e. required/optional/repeated. + if field_options.HasField("label_override"): + desc.label = field_options.label_override + + can_be_static = True + if desc.label == FieldD.LABEL_REPEATED: + self.rules = 'REPEATED' + if self.max_count is None: + can_be_static = False + else: + self.array_decl = '[%d]' % self.max_count + if field_options.fixed_count: + self.rules = 'FIXARRAY' + + elif desc.label == FieldD.LABEL_REQUIRED: + # We allow LABEL_REQUIRED using label_override even for proto3 (see #962) + self.rules = 'REQUIRED' + elif field_options.proto3: + if desc.type == FieldD.TYPE_MESSAGE and not field_options.proto3_singular_msgs: + # In most other protobuf libraries proto3 submessages have + # "null" status. For nanopb, that is implemented as has_ field. + self.rules = 'OPTIONAL' + elif hasattr(desc, "proto3_optional") and desc.proto3_optional: + # Protobuf 3.12 introduced optional fields for proto3 syntax + self.rules = 'OPTIONAL' + else: + # Proto3 singular fields (without has_field) + self.rules = 'SINGULAR' + elif desc.label == FieldD.LABEL_OPTIONAL: + self.rules = 'OPTIONAL' + else: + raise NotImplementedError(desc.label) + + # Check if the field can be implemented with static allocation + # i.e. whether the data size is known. + if desc.type == FieldD.TYPE_STRING and self.max_size is None: + can_be_static = False + + if desc.type == FieldD.TYPE_BYTES and self.max_size is None: + can_be_static = False + + # Decide how the field data will be allocated + if field_options.type == nanopb_pb2.FT_DEFAULT: + if desc.type == FieldD.TYPE_MESSAGE: + field_options.type = nanopb_pb2.FT_CALLBACK + elif can_be_static: + field_options.type = nanopb_pb2.FT_STATIC + else: + field_options.type = nanopb_pb2.FT_CALLBACK + + if field_options.type == nanopb_pb2.FT_STATIC and not can_be_static: + raise Exception("Field '%s' is defined as static, but max_size or " + "max_count is not given." % self.name) + + if field_options.fixed_count and self.max_count is None: + raise Exception("Field '%s' is defined as fixed count, " + "but max_count is not given." % self.name) + + if field_options.type == nanopb_pb2.FT_STATIC: + self.allocation = 'STATIC' + elif field_options.type == nanopb_pb2.FT_POINTER: + self.allocation = 'POINTER' + elif field_options.type == nanopb_pb2.FT_CALLBACK: + self.allocation = 'CALLBACK' + else: + raise NotImplementedError(field_options.type) + + if field_options.HasField("type_override"): + desc.type = field_options.type_override + + # Decide the C data type to use in the struct. + if desc.type in datatypes: + self.ctype, self.pbtype, self.enc_size, self.data_item_size = datatypes[desc.type] + + # Override the field size if user wants to use smaller integers + if (desc.type, field_options.int_size) in datatypes: + self.ctype, self.pbtype, self.enc_size, self.data_item_size = datatypes[(desc.type, field_options.int_size)] + elif desc.type == FieldD.TYPE_ENUM: + self.pbtype = 'ENUM' + self.data_item_size = 4 + self.ctype = names_from_type_name(desc.type_name) + if self.default is not None: + self.default = self.ctype + self.default + self.enc_size = None # Needs to be filled in when enum values are known + elif desc.type == FieldD.TYPE_STRING: + self.pbtype = 'STRING' + self.ctype = 'char' + if self.allocation == 'STATIC': + self.ctype = 'char' + self.array_decl += '[%d]' % self.max_size + # -1 because of null terminator. Both pb_encode and pb_decode + # check the presence of it. + self.enc_size = varint_max_size(self.max_size) + self.max_size - 1 + elif desc.type == FieldD.TYPE_BYTES: + if field_options.fixed_length: + self.pbtype = 'FIXED_LENGTH_BYTES' + + if self.max_size is None: + raise Exception("Field '%s' is defined as fixed length, " + "but max_size is not given." % self.name) + + self.enc_size = varint_max_size(self.max_size) + self.max_size + self.ctype = 'pb_byte_t' + self.array_decl += '[%d]' % self.max_size + else: + self.pbtype = 'BYTES' + self.ctype = 'pb_bytes_array_t' + if self.allocation == 'STATIC': + self.ctype = Globals.naming_style.bytes_type(self.struct_name, self.name) + self.enc_size = varint_max_size(self.max_size) + self.max_size + elif desc.type == FieldD.TYPE_MESSAGE: + self.pbtype = 'MESSAGE' + self.ctype = self.submsgname = names_from_type_name(desc.type_name) + self.enc_size = None # Needs to be filled in after the message type is available + if field_options.submsg_callback and self.allocation == 'STATIC': + self.pbtype = 'MSG_W_CB' + else: + raise NotImplementedError(desc.type) + + if self.default and self.pbtype in ['FLOAT', 'DOUBLE']: + if 'inf' in self.default or 'nan' in self.default: + self.math_include_required = True + + def __lt__(self, other): + return self.tag < other.tag + + def __repr__(self): + return 'Field(%s)' % self.name + + def __str__(self): + result = '' + + var_name = Globals.naming_style.var_name(self.name) + type_name = Globals.naming_style.type_name(self.ctype) if isinstance(self.ctype, Names) else self.ctype + + if self.allocation == 'POINTER': + if self.rules == 'REPEATED': + if self.pbtype == 'MSG_W_CB': + result += ' pb_callback_t cb_' + var_name + ';\n' + result += ' pb_size_t ' + var_name + '_count;\n' + + if self.rules == 'FIXARRAY' and self.pbtype in ['STRING', 'BYTES']: + # Pointer to fixed size array of pointers + result += ' %s* (*%s)%s;' % (type_name, var_name, self.array_decl) + elif self.pbtype == 'FIXED_LENGTH_BYTES' or self.rules == 'FIXARRAY': + # Pointer to fixed size array of items + result += ' %s (*%s)%s;' % (type_name, var_name, self.array_decl) + elif self.rules == 'REPEATED' and self.pbtype in ['STRING', 'BYTES']: + # String/bytes arrays need to be defined as pointers to pointers + result += ' %s **%s;' % (type_name, var_name) + elif self.pbtype in ['MESSAGE', 'MSG_W_CB']: + # Use struct definition, so recursive submessages are possible + result += ' struct %s *%s;' % (Globals.naming_style.struct_name(self.ctype), var_name) + else: + # Normal case, just a pointer to single item + result += ' %s *%s;' % (type_name, var_name) + elif self.allocation == 'CALLBACK': + result += ' %s %s;' % (self.callback_datatype, var_name) + else: + if self.pbtype == 'MSG_W_CB' and self.rules in ['OPTIONAL', 'REPEATED']: + result += ' pb_callback_t cb_' + var_name + ';\n' + + if self.rules == 'OPTIONAL': + result += ' bool has_' + var_name + ';\n' + elif self.rules == 'REPEATED': + result += ' pb_size_t ' + var_name + '_count;\n' + + result += ' %s %s%s;' % (type_name, var_name, self.array_decl) + + leading_comment, trailing_comment = self.get_comments(leading_indent = True) + if leading_comment: result = leading_comment + "\n" + result + if trailing_comment: result = result + " " + trailing_comment + + return result + + def types(self): + '''Return definitions for any special types this field might need.''' + if self.pbtype == 'BYTES' and self.allocation == 'STATIC': + result = 'typedef PB_BYTES_ARRAY_T(%d) %s;\n' % (self.max_size, Globals.naming_style.var_name(self.ctype)) + else: + result = '' + return result + + def get_dependencies(self): + '''Get list of type names used by this field.''' + if self.allocation == 'STATIC': + return [str(self.ctype)] + elif self.allocation == 'POINTER' and self.rules == 'FIXARRAY': + return [str(self.ctype)] + else: + return [] + + def get_initializer(self, null_init, inner_init_only = False): + '''Return literal expression for this field's default value. + null_init: If True, initialize to a 0 value instead of default from .proto + inner_init_only: If True, exclude initialization for any count/has fields + ''' + + inner_init = None + if self.initializer is not None: + inner_init = self.initializer + elif self.pbtype in ['MESSAGE', 'MSG_W_CB']: + if null_init: + inner_init = Globals.naming_style.define_name('%s_init_zero' % self.ctype) + else: + inner_init = Globals.naming_style.define_name('%s_init_default' % self.ctype) + elif self.default is None or null_init: + if self.pbtype == 'STRING': + inner_init = '""' + elif self.pbtype == 'BYTES': + inner_init = '{0, {0}}' + elif self.pbtype == 'FIXED_LENGTH_BYTES': + inner_init = '{0}' + elif self.pbtype in ('ENUM', 'UENUM'): + inner_init = '_%s_MIN' % Globals.naming_style.define_name(self.ctype) + else: + inner_init = '0' + else: + if self.pbtype == 'STRING': + data = codecs.escape_encode(self.default.encode('utf-8'))[0] + inner_init = '"' + data.decode('ascii') + '"' + elif self.pbtype == 'BYTES': + data = codecs.escape_decode(self.default)[0] + data = ["0x%02x" % c for c in bytearray(data)] + if len(data) == 0: + inner_init = '{0, {0}}' + else: + inner_init = '{%d, {%s}}' % (len(data), ','.join(data)) + elif self.pbtype == 'FIXED_LENGTH_BYTES': + data = codecs.escape_decode(self.default)[0] + data = ["0x%02x" % c for c in bytearray(data)] + if len(data) == 0: + inner_init = '{0}' + else: + inner_init = '{%s}' % ','.join(data) + elif self.pbtype in ['FIXED32', 'UINT32']: + inner_init = str(self.default) + 'u' + elif self.pbtype in ['FIXED64', 'UINT64']: + inner_init = str(self.default) + 'ull' + elif self.pbtype in ['SFIXED64', 'INT64']: + inner_init = str(self.default) + 'll' + elif self.pbtype in ['FLOAT', 'DOUBLE']: + inner_init = str(self.default) + if 'inf' in inner_init: + inner_init = inner_init.replace('inf', 'INFINITY') + elif 'nan' in inner_init: + inner_init = inner_init.replace('nan', 'NAN') + elif (not '.' in inner_init) and self.pbtype == 'FLOAT': + inner_init += '.0f' + elif self.pbtype == 'FLOAT': + inner_init += 'f' + else: + inner_init = str(self.default) + + if inner_init_only: + return inner_init + + outer_init = None + if self.allocation == 'STATIC': + if self.rules == 'REPEATED': + outer_init = '0, {' + ', '.join([inner_init] * self.max_count) + '}' + elif self.rules == 'FIXARRAY': + outer_init = '{' + ', '.join([inner_init] * self.max_count) + '}' + elif self.rules == 'OPTIONAL': + if null_init or not self.default_has: + outer_init = 'false, ' + inner_init + else: + outer_init = 'true, ' + inner_init + else: + outer_init = inner_init + elif self.allocation == 'POINTER': + if self.rules == 'REPEATED': + outer_init = '0, NULL' + else: + outer_init = 'NULL' + elif self.allocation == 'CALLBACK': + if self.pbtype == 'EXTENSION': + outer_init = 'NULL' + elif self.callback_datatype == 'pb_callback_t': + outer_init = '{{NULL}, NULL}' + elif self.initializer is not None: + outer_init = inner_init + elif self.callback_datatype.strip().endswith('*'): + outer_init = 'NULL' + else: + outer_init = '{0}' + + if self.pbtype == 'MSG_W_CB' and self.rules in ['REPEATED', 'OPTIONAL']: + outer_init = '{{NULL}, NULL}, ' + outer_init + + return outer_init + + def tags(self): + '''Return the #define for the tag number of this field.''' + identifier = Globals.naming_style.define_name('%s_%s_tag' % (self.struct_name, self.name)) + return '#define %-40s %d\n' % (identifier, self.tag) + + def fieldlist(self): + '''Return the FIELDLIST macro entry for this field. + Format is: X(a, ATYPE, HTYPE, LTYPE, field_name, tag) + ''' + name = Globals.naming_style.var_name(self.name) + + if self.rules == "ONEOF": + # For oneofs, make a tuple of the union name, union member name, + # and the name inside the parent struct. + if not self.anonymous: + name = '(%s,%s,%s)' % ( + Globals.naming_style.var_name(self.union_name), + Globals.naming_style.var_name(self.name), + Globals.naming_style.var_name(self.union_name) + '.' + + Globals.naming_style.var_name(self.name)) + else: + name = '(%s,%s,%s)' % ( + Globals.naming_style.var_name(self.union_name), + Globals.naming_style.var_name(self.name), + Globals.naming_style.var_name(self.name)) + + return '%s(%s, %-9s %-9s %-9s %-16s %3d)' % (self.macro_x_param, + self.macro_a_param, + self.allocation + ',', + self.rules + ',', + self.pbtype + ',', + name + ',', + self.tag) + + def data_size(self, dependencies): + '''Return estimated size of this field in the C struct. + This is used to try to automatically pick right descriptor size. + If the estimate is wrong, it will result in compile time error and + user having to specify descriptor_width option. + ''' + if self.allocation == 'POINTER' or self.pbtype == 'EXTENSION': + size = 8 + alignment = 8 + elif self.allocation == 'CALLBACK': + size = 16 + alignment = 8 + elif self.pbtype in ['MESSAGE', 'MSG_W_CB']: + alignment = 8 + if str(self.submsgname) in dependencies: + other_dependencies = dict(x for x in dependencies.items() if x[0] != str(self.struct_name)) + size = dependencies[str(self.submsgname)].data_size(other_dependencies) + else: + size = 256 # Message is in other file, this is reasonable guess for most cases + sys.stderr.write('Could not determine size for submessage %s, using default %d\n' % (self.submsgname, size)) + + if self.pbtype == 'MSG_W_CB': + size += 16 + elif self.pbtype in ['STRING', 'FIXED_LENGTH_BYTES']: + size = self.max_size + alignment = 4 + elif self.pbtype == 'BYTES': + size = self.max_size + 4 + alignment = 4 + elif self.data_item_size is not None: + size = self.data_item_size + alignment = 4 + if self.data_item_size >= 8: + alignment = 8 + else: + raise Exception("Unhandled field type: %s" % self.pbtype) + + if self.rules in ['REPEATED', 'FIXARRAY'] and self.allocation == 'STATIC': + size *= self.max_count + + if self.rules not in ('REQUIRED', 'SINGULAR'): + size += 4 + + if size % alignment != 0: + # Estimate how much alignment requirements will increase the size. + size += alignment - (size % alignment) + + return size + + def encoded_size(self, dependencies): + '''Return the maximum size that this field can take when encoded, + including the field tag. If the size cannot be determined, returns + None.''' + + if self.allocation != 'STATIC': + return None + + if self.pbtype in ['MESSAGE', 'MSG_W_CB']: + encsize = None + if str(self.submsgname) in dependencies: + submsg = dependencies[str(self.submsgname)] + other_dependencies = dict(x for x in dependencies.items() if x[0] != str(self.struct_name)) + encsize = submsg.encoded_size(other_dependencies) + + my_msg = dependencies.get(str(self.struct_name)) + external = (not my_msg or submsg.protofile != my_msg.protofile) + + if encsize and encsize.symbols and external: + # Couldn't fully resolve the size of a dependency from + # another file. Instead of including the symbols directly, + # just use the #define SubMessage_size from the header. + encsize = None + + if encsize is not None: + # Include submessage length prefix + encsize += varint_max_size(encsize.upperlimit()) + elif not external: + # The dependency is from the same file and size cannot be + # determined for it, thus we know it will not be possible + # in runtime either. + return None + + if encsize is None: + # Submessage or its size cannot be found. + # This can occur if submessage is defined in different + # file, and it or its .options could not be found. + # Instead of direct numeric value, reference the size that + # has been #defined in the other file. + encsize = EncodedSize(self.submsgname + 'size') + + # We will have to make a conservative assumption on the length + # prefix size, though. + encsize += 5 + + elif self.pbtype in ['ENUM', 'UENUM']: + if str(self.ctype) in dependencies: + enumtype = dependencies[str(self.ctype)] + encsize = enumtype.encoded_size() + else: + # Conservative assumption + encsize = 10 + + elif self.enc_size is None: + raise RuntimeError("Could not determine encoded size for %s.%s" + % (self.struct_name, self.name)) + else: + encsize = EncodedSize(self.enc_size) + + encsize += varint_max_size(self.tag << 3) # Tag + wire type + + if self.rules in ['REPEATED', 'FIXARRAY']: + # Decoders must be always able to handle unpacked arrays. + # Therefore we have to reserve space for it, even though + # we emit packed arrays ourselves. For length of 1, packed + # arrays are larger however so we need to add allowance + # for the length byte. + encsize *= self.max_count + + if self.max_count == 1: + encsize += 1 + + return encsize + + def has_callbacks(self): + return self.allocation == 'CALLBACK' + + def requires_custom_field_callback(self): + return self.allocation == 'CALLBACK' and self.callback_datatype != 'pb_callback_t' + +class ExtensionRange(Field): + def __init__(self, struct_name, range_start, field_options): + '''Implements a special pb_extension_t* field in an extensible message + structure. The range_start signifies the index at which the extensions + start. Not necessarily all tags above this are extensions, it is merely + a speed optimization. + ''' + self.tag = range_start + self.struct_name = struct_name + self.name = 'extensions' + self.pbtype = 'EXTENSION' + self.rules = 'OPTIONAL' + self.allocation = 'CALLBACK' + self.ctype = 'pb_extension_t' + self.array_decl = '' + self.default = None + self.max_size = 0 + self.max_count = 0 + self.data_item_size = 0 + self.fixed_count = False + self.callback_datatype = 'pb_extension_t*' + self.initializer = None + + def requires_custom_field_callback(self): + return False + + def __str__(self): + return ' pb_extension_t *extensions;' + + def types(self): + return '' + + def tags(self): + return '' + + def encoded_size(self, dependencies): + # We exclude extensions from the count, because they cannot be known + # until runtime. Other option would be to return None here, but this + # way the value remains useful if extensions are not used. + return EncodedSize(0) + +class ExtensionField(Field): + def __init__(self, fullname, desc, field_options): + self.fullname = fullname + self.extendee_name = names_from_type_name(desc.extendee) + Field.__init__(self, self.fullname + "extmsg", desc, field_options) + + if self.rules != 'OPTIONAL': + self.skip = True + else: + self.skip = False + self.rules = 'REQUIRED' # We don't really want the has_field for extensions + # currently no support for comments for extension fields => provide (), {} + self.msg = Message(self.fullname + "extmsg", None, field_options, (), {}) + self.msg.fields.append(self) + + def tags(self): + '''Return the #define for the tag number of this field.''' + identifier = Globals.naming_style.define_name('%s_tag' % (self.fullname)) + return '#define %-40s %d\n' % (identifier, self.tag) + + def extension_decl(self): + '''Declaration of the extension type in the .pb.h file''' + if self.skip: + msg = '/* Extension field %s was skipped because only "optional"\n' % self.fullname + msg +=' type of extension fields is currently supported. */\n' + return msg + + return ('extern const pb_extension_type_t %s; /* field type: %s */\n' % + (Globals.naming_style.var_name(self.fullname), str(self).strip())) + + def extension_def(self, dependencies): + '''Definition of the extension type in the .pb.c file''' + + if self.skip: + return '' + + result = "/* Definition for extension field %s */\n" % self.fullname + result += str(self.msg) + result += self.msg.fields_declaration(dependencies) + result += 'pb_byte_t %s_default[] = {0x00};\n' % self.msg.name + result += self.msg.fields_definition(dependencies) + result += 'const pb_extension_type_t %s = {\n' % Globals.naming_style.var_name(self.fullname) + result += ' NULL,\n' + result += ' NULL,\n' + result += ' &%s_msg\n' % Globals.naming_style.type_name(self.msg.name) + result += '};\n' + return result + + +# --------------------------------------------------------------------------- +# Generation of oneofs (unions) +# --------------------------------------------------------------------------- + +class OneOf(Field): + def __init__(self, struct_name, oneof_desc, oneof_options): + self.struct_name = struct_name + self.name = oneof_desc.name + self.ctype = 'union' + self.pbtype = 'oneof' + self.fields = [] + self.allocation = 'ONEOF' + self.default = None + self.rules = 'ONEOF' + self.anonymous = oneof_options.anonymous_oneof + self.sort_by_tag = oneof_options.sort_by_tag + self.has_msg_cb = False + + def add_field(self, field): + field.union_name = self.name + field.rules = 'ONEOF' + field.anonymous = self.anonymous + self.fields.append(field) + + if self.sort_by_tag: + self.fields.sort() + + if field.pbtype == 'MSG_W_CB': + self.has_msg_cb = True + + # Sort by the lowest tag number inside union + self.tag = min([f.tag for f in self.fields]) + + def __str__(self): + result = '' + if self.fields: + if self.has_msg_cb: + result += ' pb_callback_t cb_' + Globals.naming_style.var_name(self.name) + ';\n' + + result += ' pb_size_t which_' + Globals.naming_style.var_name(self.name) + ";\n" + result += ' union {\n' + for f in self.fields: + result += ' ' + str(f).replace('\n', '\n ') + '\n' + if self.anonymous: + result += ' };' + else: + result += ' } ' + Globals.naming_style.var_name(self.name) + ';' + return result + + def types(self): + return ''.join([f.types() for f in self.fields]) + + def get_dependencies(self): + deps = [] + for f in self.fields: + deps += f.get_dependencies() + return deps + + def get_initializer(self, null_init): + if self.has_msg_cb: + return '{{NULL}, NULL}, 0, {' + self.fields[0].get_initializer(null_init) + '}' + else: + return '0, {' + self.fields[0].get_initializer(null_init) + '}' + + def tags(self): + return ''.join([f.tags() for f in self.fields]) + + def data_size(self, dependencies): + return max(f.data_size(dependencies) for f in self.fields) + + def encoded_size(self, dependencies): + '''Returns the size of the largest oneof field.''' + largest = 0 + dynamic_sizes = {} + for f in self.fields: + size = EncodedSize(f.encoded_size(dependencies)) + if size is None or size.value is None: + return None + elif size.symbols: + dynamic_sizes[f.tag] = size + elif size.value > largest: + largest = size.value + + if not dynamic_sizes: + # Simple case, all sizes were known at generator time + return EncodedSize(largest) + + if largest > 0: + # Some sizes were known, some were not + dynamic_sizes[0] = EncodedSize(largest) + + # Couldn't find size for submessage at generation time, + # have to rely on macro resolution at compile time. + if len(dynamic_sizes) == 1: + # Only one symbol was needed + return list(dynamic_sizes.values())[0] + else: + # Use sizeof(union{}) construct to find the maximum size of + # submessages. + union_name = "%s_%s_size_union" % (self.struct_name, self.name) + union_def = 'union %s {%s};\n' % (union_name, ' '.join('char f%d[%s];' % (k, s) for k,s in dynamic_sizes.items())) + required_defs = list(itertools.chain.from_iterable(s.required_defines for k,s in dynamic_sizes.items())) + return EncodedSize(0, ['sizeof(union %s)' % union_name], [union_def], required_defs) + + def has_callbacks(self): + return bool([f for f in self.fields if f.has_callbacks()]) + + def requires_custom_field_callback(self): + return bool([f for f in self.fields if f.requires_custom_field_callback()]) + +# --------------------------------------------------------------------------- +# Generation of messages (structures) +# --------------------------------------------------------------------------- + + +class Message(ProtoElement): + def __init__(self, names, desc, message_options, element_path, comments): + super(Message, self).__init__(element_path, comments) + self.name = names + self.fields = [] + self.oneofs = {} + self.desc = desc + self.math_include_required = False + self.packed = message_options.packed_struct + self.descriptorsize = message_options.descriptorsize + + if message_options.msgid: + self.msgid = message_options.msgid + + if desc is not None: + self.load_fields(desc, message_options) + + self.callback_function = message_options.callback_function + if not message_options.HasField('callback_function'): + # Automatically assign a per-message callback if any field has + # a special callback_datatype. + for field in self.fields: + if field.requires_custom_field_callback(): + self.callback_function = "%s_callback" % self.name + break + + def load_fields(self, desc, message_options): + '''Load field list from DescriptorProto''' + + no_unions = [] + + if hasattr(desc, 'oneof_decl'): + for i, f in enumerate(desc.oneof_decl): + oneof_options = get_nanopb_suboptions(desc, message_options, self.name + f.name) + if oneof_options.no_unions: + no_unions.append(i) # No union, but add fields normally + elif oneof_options.type == nanopb_pb2.FT_IGNORE: + pass # No union and skip fields also + else: + oneof = OneOf(self.name, f, oneof_options) + self.oneofs[i] = oneof + else: + sys.stderr.write('Note: This Python protobuf library has no OneOf support\n') + + for index, f in enumerate(desc.field): + field_options = get_nanopb_suboptions(f, message_options, self.name + f.name) + + if field_options.type == nanopb_pb2.FT_IGNORE: + continue + + if field_options.discard_deprecated and f.options.deprecated: + continue + + if field_options.descriptorsize > self.descriptorsize: + self.descriptorsize = field_options.descriptorsize + + field = Field(self.name, f, field_options, self.element_path + (ProtoElement.FIELD, index), self.comments) + if hasattr(f, 'oneof_index') and f.HasField('oneof_index'): + if hasattr(f, 'proto3_optional') and f.proto3_optional: + no_unions.append(f.oneof_index) + + if f.oneof_index in no_unions: + self.fields.append(field) + elif f.oneof_index in self.oneofs: + self.oneofs[f.oneof_index].add_field(field) + + if self.oneofs[f.oneof_index] not in self.fields: + self.fields.append(self.oneofs[f.oneof_index]) + else: + self.fields.append(field) + + if field.math_include_required: + self.math_include_required = True + + if len(desc.extension_range) > 0: + field_options = get_nanopb_suboptions(desc, message_options, self.name + 'extensions') + range_start = min([r.start for r in desc.extension_range]) + if field_options.type != nanopb_pb2.FT_IGNORE: + self.fields.append(ExtensionRange(self.name, range_start, field_options)) + + if message_options.sort_by_tag: + self.fields.sort() + + def get_dependencies(self): + '''Get list of type names that this structure refers to.''' + deps = [] + for f in self.fields: + deps += f.get_dependencies() + return deps + + def __repr__(self): + return 'Message(%s)' % self.name + + def __str__(self): + leading_comment, trailing_comment = self.get_comments() + + result = '' + if leading_comment: + result = '%s\n' % leading_comment + + result += 'typedef struct %s {' % Globals.naming_style.struct_name(self.name) + if trailing_comment: + result += " " + trailing_comment + + result += '\n' + + result += ' static const pb_msgdesc_t* msg_descriptor(void) noexcept;\n' + result += ' static std::string_view msg_name(void) noexcept;\n' + result += ' static pb_filedesc_t file_descriptor(void) noexcept;\n' + + result += '\n' + + if not self.fields: + # Empty structs are not allowed in C standard. + # Therefore add a dummy field if an empty message occurs. + result += ' char dummy_field;' + + result += '\n'.join([str(f) for f in self.fields]) + + if Globals.protoc_insertion_points: + result += '\n/* @@protoc_insertion_point(struct:%s) */' % self.name + + result += '\n}' + + if self.packed: + result += ' pb_packed' + + result += ' %s;' % Globals.naming_style.type_name(self.name) + + if self.packed: + result = 'PB_PACKED_STRUCT_START\n' + result + result += '\nPB_PACKED_STRUCT_END' + + return result + '\n' + + def types(self): + return ''.join([f.types() for f in self.fields]) + + def get_initializer(self, null_init): + if not self.fields: + return '{0}' + + parts = [] + for field in self.fields: + parts.append(field.get_initializer(null_init)) + return '{' + ', '.join(parts) + '}' + + def count_required_fields(self): + '''Returns number of required fields inside this message''' + count = 0 + for f in self.fields: + if not isinstance(f, OneOf): + if f.rules == 'REQUIRED': + count += 1 + return count + + def all_fields(self): + '''Iterate over all fields in this message, including nested OneOfs.''' + for f in self.fields: + if isinstance(f, OneOf): + for f2 in f.fields: + yield f2 + else: + yield f + + + def field_for_tag(self, tag): + '''Given a tag number, return the Field instance.''' + for field in self.all_fields(): + if field.tag == tag: + return field + return None + + def count_all_fields(self): + '''Count the total number of fields in this message.''' + count = 0 + for f in self.fields: + if isinstance(f, OneOf): + count += len(f.fields) + else: + count += 1 + return count + + def fields_declaration(self, dependencies): + '''Return X-macro declaration of all fields in this message.''' + Field.macro_x_param = 'X' + Field.macro_a_param = 'a' + while any(field.name == Field.macro_x_param for field in self.all_fields()): + Field.macro_x_param += '_' + while any(field.name == Field.macro_a_param for field in self.all_fields()): + Field.macro_a_param += '_' + + # Field descriptor array must be sorted by tag number, pb_common.c relies on it. + sorted_fields = list(self.all_fields()) + sorted_fields.sort(key = lambda x: x.tag) + + result = '#define %s_FIELDLIST(%s, %s) \\\n' % ( + Globals.naming_style.define_name(self.name), + Field.macro_x_param, + Field.macro_a_param) + result += ' \\\n'.join(x.fieldlist() for x in sorted_fields) + result += '\n' + + has_callbacks = bool([f for f in self.fields if f.has_callbacks()]) + if has_callbacks: + if self.callback_function != 'pb_default_field_callback': + result += "extern bool %s(pb_istream_t *istream, pb_ostream_t *ostream, const pb_field_t *field);\n" % self.callback_function + result += "#define %s_CALLBACK %s\n" % ( + Globals.naming_style.define_name(self.name), + self.callback_function) + else: + result += "#define %s_CALLBACK NULL\n" % Globals.naming_style.define_name(self.name) + + defval = self.default_value(dependencies) + if defval: + hexcoded = ''.join("\\x%02x" % ord(defval[i:i+1]) for i in range(len(defval))) + result += '#define %s_DEFAULT (const pb_byte_t*)"%s\\x00"\n' % ( + Globals.naming_style.define_name(self.name), + hexcoded) + else: + result += '#define %s_DEFAULT NULL\n' % Globals.naming_style.define_name(self.name) + + for field in sorted_fields: + if field.pbtype in ['MESSAGE', 'MSG_W_CB']: + if field.rules == 'ONEOF': + result += "#define %s_%s_%s_MSGTYPE %s\n" % ( + Globals.naming_style.type_name(self.name), + Globals.naming_style.var_name(field.union_name), + Globals.naming_style.var_name(field.name), + Globals.naming_style.type_name(field.ctype) + ) + else: + result += "#define %s_%s_MSGTYPE %s\n" % ( + Globals.naming_style.type_name(self.name), + Globals.naming_style.var_name(field.name), + Globals.naming_style.type_name(field.ctype) + ) + + return result + + def enumtype_defines(self): + '''Defines to allow user code to refer to enum type of a specific field''' + result = '' + for field in self.all_fields(): + if field.pbtype in ['ENUM', "UENUM"]: + if field.rules == 'ONEOF': + result += "#define %s_%s_%s_ENUMTYPE %s\n" % ( + Globals.naming_style.type_name(self.name), + Globals.naming_style.var_name(field.union_name), + Globals.naming_style.var_name(field.name), + Globals.naming_style.type_name(field.ctype) + ) + else: + result += "#define %s_%s_ENUMTYPE %s\n" % ( + Globals.naming_style.type_name(self.name), + Globals.naming_style.var_name(field.name), + Globals.naming_style.type_name(field.ctype) + ) + + return result + + def fields_declaration_cpp_lookup(self, local_defines): + result = 'template <>\n' + result += 'struct MessageDescriptor<%s> {\n' % (self.name) + result += ' static PB_INLINE_CONSTEXPR const pb_size_t fields_array_length = %d;\n' % (self.count_all_fields()) + + size_define = "%s_size" % (self.name) + if size_define in local_defines: + result += ' static PB_INLINE_CONSTEXPR const pb_size_t size = %s;\n' % (size_define) + + result += ' static inline const pb_msgdesc_t* fields() {\n' + result += ' return &%s_msg;\n' % (self.name) + result += ' }\n' + result += ' static inline bool has_msgid() {\n' + result += ' return %s;\n' % ("true" if hasattr(self, "msgid") else "false", ) + result += ' }\n' + result += ' static inline uint32_t msgid() {\n' + result += ' return %d;\n' % (getattr(self, "msgid", 0), ) + result += ' }\n' + result += '};' + return result + + def fields_definition(self, dependencies): + '''Return the field descriptor definition that goes in .pb.c file.''' + width = self.required_descriptor_width(dependencies) + if width == 1: + width = 'AUTO' + + result = 'PB_BIND(%s, %s, %s)\n' % ( + Globals.naming_style.define_name(self.name), + Globals.naming_style.type_name(self.name), + width) + return result + + def required_descriptor_width(self, dependencies): + '''Estimate how many words are necessary for each field descriptor.''' + if self.descriptorsize != nanopb_pb2.DS_AUTO: + return int(self.descriptorsize) + + if not self.fields: + return 1 + + max_tag = max(field.tag for field in self.all_fields()) + max_offset = self.data_size(dependencies) + max_arraysize = max((field.max_count or 0) for field in self.all_fields()) + max_datasize = max(field.data_size(dependencies) for field in self.all_fields()) + + if max_arraysize > 0xFFFF: + return 8 + elif (max_tag > 0x3FF or max_offset > 0xFFFF or + max_arraysize > 0x0FFF or max_datasize > 0x0FFF): + return 4 + elif max_tag > 0x3F or max_offset > 0xFF: + return 2 + else: + # NOTE: Macro logic in pb.h ensures that width 1 will + # be raised to 2 automatically for string/submsg fields + # and repeated fields. Thus only tag and offset need to + # be checked. + return 1 + + def data_size(self, dependencies): + '''Return approximate sizeof(struct) in the compiled code.''' + return sum(f.data_size(dependencies) for f in self.fields) + + def encoded_size(self, dependencies): + '''Return the maximum size that this message can take when encoded. + If the size cannot be determined, returns None. + ''' + size = EncodedSize(0) + for field in self.fields: + fsize = field.encoded_size(dependencies) + if fsize is None: + return None + size += fsize + + return size + + def default_value(self, dependencies): + '''Generate serialized protobuf message that contains the + default values for optional fields.''' + + if not self.desc: + return b'' + + if self.desc.options.map_entry: + return b'' + + optional_only = copy.deepcopy(self.desc) + + # Remove fields without default values + # The iteration is done in reverse order to avoid remove() messing up iteration. + for field in reversed(list(optional_only.field)): + field.ClearField(str('extendee')) + parsed_field = self.field_for_tag(field.number) + if parsed_field is None or parsed_field.allocation != 'STATIC': + optional_only.field.remove(field) + elif (field.label == FieldD.LABEL_REPEATED or + field.type == FieldD.TYPE_MESSAGE): + optional_only.field.remove(field) + elif hasattr(field, 'oneof_index') and field.HasField('oneof_index'): + optional_only.field.remove(field) + elif field.type == FieldD.TYPE_ENUM: + # The partial descriptor doesn't include the enum type + # so we fake it with int64. + enumname = names_from_type_name(field.type_name) + try: + enumtype = dependencies[str(enumname)] + except KeyError: + raise Exception("Could not find enum type %s while generating default values for %s.\n" % (enumname, self.name) + + "Try passing all source files to generator at once, or use -I option.") + + if not isinstance(enumtype, Enum): + raise Exception("Expected enum type as %s, got %s" % (enumname, repr(enumtype))) + + if field.HasField('default_value'): + defvals = [v for n,v in enumtype.values if n.parts[-1] == field.default_value] + else: + # If no default is specified, the default is the first value. + defvals = [v for n,v in enumtype.values] + if defvals and defvals[0] != 0: + field.type = FieldD.TYPE_INT64 + field.default_value = str(defvals[0]) + field.ClearField(str('type_name')) + else: + optional_only.field.remove(field) + elif not field.HasField('default_value'): + optional_only.field.remove(field) + + if len(optional_only.field) == 0: + return b'' + + optional_only.ClearField(str('oneof_decl')) + optional_only.ClearField(str('nested_type')) + optional_only.ClearField(str('extension')) + optional_only.ClearField(str('enum_type')) + optional_only.name += str(id(self)) + + desc = google.protobuf.descriptor.MakeDescriptor(optional_only) + msg = reflection.MakeClass(desc)() + + for field in optional_only.field: + if field.type == FieldD.TYPE_STRING: + setattr(msg, field.name, field.default_value) + elif field.type == FieldD.TYPE_BYTES: + setattr(msg, field.name, codecs.escape_decode(field.default_value)[0]) + elif field.type in [FieldD.TYPE_FLOAT, FieldD.TYPE_DOUBLE]: + setattr(msg, field.name, float(field.default_value)) + elif field.type == FieldD.TYPE_BOOL: + setattr(msg, field.name, field.default_value == 'true') + else: + setattr(msg, field.name, int(field.default_value)) + + return msg.SerializeToString() + + +# --------------------------------------------------------------------------- +# Processing of entire .proto files +# --------------------------------------------------------------------------- + +def iterate_messages(desc, flatten = False, names = Names(), comment_path = ()): + '''Recursively find all messages. For each, yield name, DescriptorProto, comment_path.''' + if hasattr(desc, 'message_type'): + submsgs = desc.message_type + comment_path += (ProtoElement.MESSAGE,) + else: + submsgs = desc.nested_type + comment_path += (ProtoElement.NESTED_TYPE,) + + for idx, submsg in enumerate(submsgs): + sub_names = names + submsg.name + sub_path = comment_path + (idx,) + if flatten: + yield Names(submsg.name), submsg, sub_path + else: + yield sub_names, submsg, sub_path + + for x in iterate_messages(submsg, flatten, sub_names, sub_path): + yield x + +def iterate_extensions(desc, flatten = False, names = Names()): + '''Recursively find all extensions. + For each, yield name, FieldDescriptorProto. + ''' + for extension in desc.extension: + yield names, extension + + for subname, subdesc, comment_path in iterate_messages(desc, flatten, names): + for extension in subdesc.extension: + yield subname, extension + +def check_recursive_dependencies(message, all_messages, root = None): + '''Returns True if message has a recursive dependency on root (or itself if root is None).''' + + if not isinstance(all_messages, dict): + all_messages = dict((str(m.name), m) for m in all_messages) + + if not root: + root = message + + for dep in message.get_dependencies(): + if dep == str(root.name): + return True + elif dep in all_messages: + if check_recursive_dependencies(all_messages[dep], all_messages, root): + return True + + return False + +def sort_dependencies(messages): + '''Sort a list of Messages based on dependencies.''' + + # Construct first level list of dependencies + dependencies = {} + for message in messages: + dependencies[str(message.name)] = set(message.get_dependencies()) + + # Emit messages after all their dependencies have been processed + remaining = list(messages) + remainset = set(str(m.name) for m in remaining) + while remaining: + for candidate in remaining: + if not remainset.intersection(dependencies[str(candidate.name)]): + remaining.remove(candidate) + remainset.remove(str(candidate.name)) + yield candidate + break + else: + sys.stderr.write("Circular dependency in messages: " + ', '.join(remainset) + " (consider changing to FT_POINTER or FT_CALLBACK)\n") + candidate = remaining.pop(0) + remainset.remove(str(candidate.name)) + yield candidate + +def make_identifier(headername): + '''Make #ifndef identifier that contains uppercase A-Z and digits 0-9''' + result = "" + for c in headername.upper(): + if c.isalnum(): + result += c + else: + result += '_' + return result + +class MangleNames: + '''Handles conversion of type names according to mangle_names option: + M_NONE = 0; // Default, no typename mangling + M_STRIP_PACKAGE = 1; // Strip current package name + M_FLATTEN = 2; // Only use last path component + M_PACKAGE_INITIALS = 3; // Replace the package name by the initials + ''' + def __init__(self, fdesc, file_options): + self.file_options = file_options + self.mangle_names = file_options.mangle_names + self.flatten = (self.mangle_names == nanopb_pb2.M_FLATTEN) + self.strip_prefix = None + self.replacement_prefix = None + self.name_mapping = {} + self.reverse_name_mapping = {} + self.canonical_base = Names(fdesc.package.split('.')) + + if self.mangle_names == nanopb_pb2.M_STRIP_PACKAGE: + self.strip_prefix = "." + fdesc.package + elif self.mangle_names == nanopb_pb2.M_PACKAGE_INITIALS: + self.strip_prefix = "." + fdesc.package + self.replacement_prefix = "" + for part in fdesc.package.split("."): + self.replacement_prefix += part[0] + elif file_options.package: + self.strip_prefix = "." + fdesc.package + self.replacement_prefix = file_options.package + + if self.strip_prefix == '.': + self.strip_prefix = '' + + if self.replacement_prefix is not None: + self.base_name = Names(self.replacement_prefix.split('.')) + elif fdesc.package: + self.base_name = Names(fdesc.package.split('.')) + else: + self.base_name = Names() + + def create_name(self, names): + '''Create name for a new message / enum. + Argument can be either string or Names instance. + ''' + if str(names) not in self.name_mapping: + if self.mangle_names in (nanopb_pb2.M_NONE, nanopb_pb2.M_PACKAGE_INITIALS): + new_name = self.base_name + names + elif self.mangle_names == nanopb_pb2.M_STRIP_PACKAGE: + new_name = Names(names) + elif isinstance(names, Names): + new_name = Names(names.parts[-1]) + else: + new_name = Names(names) + + if str(new_name) in self.reverse_name_mapping: + sys.stderr.write("Warning: Duplicate name with mangle_names=%s: %s and %s map to %s\n" % + (self.mangle_names, self.reverse_name_mapping[str(new_name)], names, new_name)) + + self.name_mapping[str(names)] = new_name + self.reverse_name_mapping[str(new_name)] = self.canonical_base + names + + return self.name_mapping[str(names)] + + def mangle_field_typename(self, typename): + '''Mangle type name for a submessage / enum crossreference. + Argument is a string. + ''' + if self.mangle_names == nanopb_pb2.M_FLATTEN: + return "." + typename.split(".")[-1] + + canonical_mangled_typename = str(Names(typename.strip(".").split("."))) + if not canonical_mangled_typename.startswith(str(self.canonical_base) + "_"): + return typename + + if self.strip_prefix is not None and typename.startswith(self.strip_prefix): + if self.replacement_prefix is not None: + return "." + self.replacement_prefix + typename[len(self.strip_prefix):] + else: + return typename[len(self.strip_prefix):] + + if self.file_options.package: + return "." + self.replacement_prefix + typename + + return typename + + def unmangle(self, names): + return self.reverse_name_mapping.get(str(names), names) + +class ProtoFile: + def __init__(self, fdesc, file_options): + '''Takes a FileDescriptorProto and parses it.''' + self.fdesc = fdesc + self.file_options = file_options + self.dependencies = {} + self.math_include_required = False + self.parse() + self.discard_unused_automatic_types() + for message in self.messages: + if message.math_include_required: + self.math_include_required = True + break + + # Some of types used in this file probably come from the file itself. + # Thus it has implicit dependency on itself. + self.add_dependency(self) + + def parse(self): + self.enums = [] + self.messages = [] + self.extensions = [] + self.manglenames = MangleNames(self.fdesc, self.file_options) + + # process source code comment locations + # ignores any locations that do not contain any comment information + self.comment_locations = { + tuple(location.path): location + for location in self.fdesc.source_code_info.location + if location.leading_comments or location.leading_detached_comments or location.trailing_comments + } + + for index, enum in enumerate(self.fdesc.enum_type): + name = self.manglenames.create_name(enum.name) + enum_options = get_nanopb_suboptions(enum, self.file_options, name) + enum_path = (ProtoElement.ENUM, index) + self.enums.append(Enum(name, enum, enum_options, enum_path, self.comment_locations)) + + for names, message, comment_path in iterate_messages(self.fdesc, self.manglenames.flatten): + name = self.manglenames.create_name(names) + message_options = get_nanopb_suboptions(message, self.file_options, name) + + if message_options.skip_message: + continue + + if message_options.discard_deprecated and message.options.deprecated: + continue + + # Apply any configured typename mangling options + message = copy.deepcopy(message) + for field in message.field: + if field.type in (FieldD.TYPE_MESSAGE, FieldD.TYPE_ENUM): + field.type_name = self.manglenames.mangle_field_typename(field.type_name) + + # Check for circular dependencies + msgobject = Message(name, message, message_options, comment_path, self.comment_locations) + if check_recursive_dependencies(msgobject, self.messages): + message_options.type = message_options.fallback_type + sys.stderr.write('Breaking circular dependency at message %s by converting to %s\n' + % (msgobject.name, nanopb_pb2.FieldType.Name(message_options.type))) + msgobject = Message(name, message, message_options, comment_path, self.comment_locations) + self.messages.append(msgobject) + + # Process any nested enums + for index, enum in enumerate(message.enum_type): + name = self.manglenames.create_name(names + enum.name) + enum_options = get_nanopb_suboptions(enum, message_options, name) + enum_path = comment_path + (ProtoElement.NESTED_ENUM, index) + self.enums.append(Enum(name, enum, enum_options, enum_path, self.comment_locations)) + + for names, extension in iterate_extensions(self.fdesc, self.manglenames.flatten): + name = self.manglenames.create_name(names + extension.name) + field_options = get_nanopb_suboptions(extension, self.file_options, name) + + extension = copy.deepcopy(extension) + if extension.type in (FieldD.TYPE_MESSAGE, FieldD.TYPE_ENUM): + extension.type_name = self.manglenames.mangle_field_typename(extension.type_name) + + if field_options.type != nanopb_pb2.FT_IGNORE: + self.extensions.append(ExtensionField(name, extension, field_options)) + + def discard_unused_automatic_types(self): + '''Discard unused types that are automatically generated by protoc if they are not actually + needed. Currently this applies to map< > types when the field is ignored by options. + ''' + + if not self.file_options.discard_unused_automatic_types: + return + + map_entries = {} + types_used = set() + for msg in self.messages: + if msg.desc.options.map_entry: + map_entries[str(msg.name)] = msg + + for field in msg.all_fields(): + if field.pbtype == 'MESSAGE': + types_used.add(str(field.submsgname)) + + for name, msg in map_entries.items(): + if name not in types_used: + self.messages.remove(msg) + + def add_dependency(self, other): + for enum in other.enums: + self.dependencies[str(enum.names)] = enum + self.dependencies[str(other.manglenames.unmangle(enum.names))] = enum + enum.protofile = other + + for msg in other.messages: + canonical_mangled_typename = str(other.manglenames.unmangle(msg.name)) + self.dependencies[str(msg.name)] = msg + self.dependencies[canonical_mangled_typename] = msg + msg.protofile = other + + # Fix references to submessages with different mangling rules + for message in self.messages: + for field in message.all_fields(): + if field.ctype == canonical_mangled_typename: + field.ctype = msg.name + + # Fix field default values where enum short names are used. + for enum in other.enums: + if not enum.options.long_names: + for message in self.messages: + for field in message.all_fields(): + if field.default in enum.value_longnames: + idx = enum.value_longnames.index(field.default) + field.default = enum.values[idx][0] + + # Fix field data types where enums have negative values. + for enum in other.enums: + if not enum.has_negative(): + for message in self.messages: + for field in message.all_fields(): + if field.pbtype == 'ENUM' and field.ctype == enum.names: + field.pbtype = 'UENUM' + + def generate_header(self, includes, headername, options): + '''Generate content for a header file. + Generates strings, which should be concatenated and stored to file. + ''' + + yield '/* Automatically generated nanopb header */\n' + if options.notimestamp: + yield '/* Generated by %s */\n\n' % (nanopb_version) + else: + yield '/* Generated by %s at %s. */\n\n' % (nanopb_version, time.asctime()) + + if self.fdesc.package: + symbol = make_identifier(self.fdesc.package + '_' + headername) + else: + symbol = make_identifier(headername) + yield '#ifndef PB_%s_INCLUDED\n' % symbol + yield '#define PB_%s_INCLUDED\n' % symbol + if self.math_include_required: + yield '#include \n' + try: + yield options.libformat % ('pb.h') + except TypeError: + # no %s specified - use whatever was passed in as options.libformat + yield options.libformat + yield '\n' + yield "#include \n" + yield "#include \n" + + for incfile in self.file_options.include: + # allow including system headers + if (incfile.startswith('<')): + yield '#include %s\n' % incfile + else: + yield options.genformat % incfile + yield '\n' + + for incfile in includes: + noext = os.path.splitext(incfile)[0] + yield options.genformat % (noext + options.extension + options.header_extension) + yield '\n' + + if Globals.protoc_insertion_points: + yield '/* @@protoc_insertion_point(includes) */\n' + + yield '\n' + + yield '#if PB_PROTO_HEADER_VERSION != 40\n' + yield '#error Regenerate this file with the current version of nanopb generator.\n' + yield '#endif\n' + yield '\n' + + if self.enums: + yield '/* Enum definitions */\n' + for enum in self.enums: + yield str(enum) + '\n\n' + + if self.messages: + yield '/* Struct definitions */\n' + for msg in sort_dependencies(self.messages): + yield msg.types() + yield str(msg) + '\n' + yield '\n' + + if self.extensions: + yield '/* Extensions */\n' + for extension in self.extensions: + yield extension.extension_decl() + yield '\n' + + if self.enums: + yield '/* Helper constants for enums */\n' + for enum in self.enums: + yield enum.auxiliary_defines() + '\n' + + for msg in self.messages: + yield msg.enumtype_defines() + '\n' + yield '\n' + + if self.messages: + yield '/* Initializer values for message structs */\n' + for msg in self.messages: + identifier = Globals.naming_style.define_name('%s_init_default' % msg.name) + yield '#define %-40s %s\n' % (identifier, msg.get_initializer(False)) + unmangledName = self.manglenames.unmangle(msg.name) + if unmangledName: + unmangledIdentifier = Globals.naming_style.define_name('%s_init_default' % unmangledName) + self.manglenames.reverse_name_mapping[identifier] = unmangledIdentifier + for msg in self.messages: + identifier = Globals.naming_style.define_name('%s_init_zero' % msg.name) + yield '#define %-40s %s\n' % (identifier, msg.get_initializer(True)) + unmangledName = self.manglenames.unmangle(msg.name) + if unmangledName: + unmangledIdentifier = Globals.naming_style.define_name('%s_init_zero' % unmangledName) + self.manglenames.reverse_name_mapping[identifier] = unmangledIdentifier + yield '\n' + + yield '/* Field tags (for use in manual encoding/decoding) */\n' + for msg in sort_dependencies(self.messages): + for field in msg.fields: + yield field.tags() + for extension in self.extensions: + yield extension.tags() + yield '\n' + + yield '/* Struct field encoding specification for nanopb */\n' + for msg in self.messages: + yield msg.fields_declaration(self.dependencies) + '\n' + + yield '/* Maximum encoded size of messages (where known) */\n' + messagesizes = [] + for msg in self.messages: + identifier = '%s_size' % msg.name + messagesizes.append((identifier, msg.encoded_size(self.dependencies))) + + # If we require a symbol from another file, put a preprocessor if statement + # around it to prevent compilation errors if the symbol is not actually available. + local_defines = [identifier for identifier, msize in messagesizes if msize is not None] + + # emit size_unions, if any + oneof_sizes = [] + for msg in self.messages: + for f in msg.fields: + if isinstance(f, OneOf): + msize = f.encoded_size(self.dependencies) + if msize is not None: + oneof_sizes.append(msize) + for msize in oneof_sizes: + guard = msize.get_cpp_guard(local_defines) + if guard: + yield guard + yield msize.get_declarations() + if guard: + yield '#endif\n' + + guards = {} + # Provide a #define of the maximum message size, which faciliates setting the size of static arrays to be the largest possible encoded message size + max_messagesize = max(messagesizes, key=lambda messagesize: messagesize[1].value if messagesize[1] else 0) + for identifier, msize in messagesizes: + if msize is not None: + cpp_guard = msize.get_cpp_guard(local_defines) + if cpp_guard not in guards: + guards[cpp_guard] = set() + guards[cpp_guard].add('#define %-40s %s' % ( + Globals.naming_style.define_name(identifier), msize)) + + if identifier == max_messagesize[0]: + guards[cpp_guard].add('#define %-40s %s' % ( + Globals.naming_style.define_name(symbol + "_MAX_SIZE"), Globals.naming_style.define_name(identifier))) + + else: + yield '/* %s depends on runtime parameters */\n' % identifier + for guard, values in guards.items(): + if guard: + yield guard + for v in sorted(values): + yield v + yield '\n' + if guard: + yield '#endif\n' + yield '\n' + + if [msg for msg in self.messages if hasattr(msg,'msgid')]: + yield '/* Message IDs (where set with "msgid" option) */\n' + for msg in self.messages: + if hasattr(msg,'msgid'): + yield '#define PB_MSG_%d %s\n' % (msg.msgid, msg.name) + yield '\n' + + symbol = make_identifier(headername.split('.')[0]) + yield '#define %s_MESSAGES \\\n' % symbol + + for msg in self.messages: + m = "-1" + msize = msg.encoded_size(self.dependencies) + if msize is not None: + m = msize + if hasattr(msg,'msgid'): + yield '\tPB_MSG(%d,%s,%s) \\\n' % (msg.msgid, m, msg.name) + yield '\n' + + for msg in self.messages: + if hasattr(msg,'msgid'): + yield '#define %s_msgid %d\n' % (msg.name, msg.msgid) + yield '\n' + + # Check if there is any name mangling active + pairs = [x for x in self.manglenames.reverse_name_mapping.items() if str(x[0]) != str(x[1])] + if pairs: + yield '/* Mapping from canonical names (mangle_names or overridden package name) */\n' + for shortname, longname in pairs: + yield '#define %s %s\n' % (longname, shortname) + yield '\n' + + if options.cpp_descriptors: + yield '\n' + yield '#ifdef __cplusplus\n' + yield '/* Message descriptors for nanopb */\n' + yield 'namespace nanopb {\n' + for msg in self.messages: + yield msg.fields_declaration_cpp_lookup(local_defines) + '\n' + yield '} // namespace nanopb\n' + yield '\n' + yield '#endif /* __cplusplus */\n' + yield '\n' + + if Globals.protoc_insertion_points: + yield '/* @@protoc_insertion_point(eof) */\n' + + # End of header + yield '\n#endif\n' + + def generate_source(self, headername, options): + '''Generate content for a source file.''' + + yield '/* Automatically generated nanopb constant definitions */\n' + if options.notimestamp: + yield '/* Generated by %s */\n\n' % (nanopb_version) + else: + yield '/* Generated by %s at %s. */\n\n' % (nanopb_version, time.asctime()) + yield options.genformat % (headername) + yield '\n' + + if Globals.protoc_insertion_points: + yield '/* @@protoc_insertion_point(includes) */\n' + + yield '#if PB_PROTO_HEADER_VERSION != 40\n' + yield '#error Regenerate this file with the current version of nanopb generator.\n' + yield '#endif\n' + yield '\n' + + yield "#include \n" + yield "#include \n" + + yield "static const uint8_t file_descriptor[] {\n" + + line_count = 0 + + for b in self.fdesc.SerializeToString(): + yield '0x' + format(b, '02x') + ',' + line_count += 1 + if line_count == 10: + yield '\n' + line_count = 0 + yield '\n' + + yield "};\n" + yield 'static const char file_name[] = "%s";\n' % self.fdesc.name + + # Check if any messages exceed the 64 kB limit of 16-bit pb_size_t + exceeds_64kB = [] + for msg in self.messages: + size = msg.data_size(self.dependencies) + if size >= 65536: + exceeds_64kB.append(str(msg.name)) + + if exceeds_64kB: + yield '\n/* The following messages exceed 64kB in size: ' + ', '.join(exceeds_64kB) + ' */\n' + yield '\n/* The PB_FIELD_32BIT compilation option must be defined to support messages that exceed 64 kB in size. */\n' + yield '#ifndef PB_FIELD_32BIT\n' + yield '#error Enable PB_FIELD_32BIT to support messages exceeding 64kB in size: ' + ', '.join(exceeds_64kB) + '\n' + yield '#endif\n' + + # Generate the message field definitions (PB_BIND() call) + for msg in self.messages: + if self.fdesc.package: + full_name = self.fdesc.package + '.' + msg.desc.name + else: + full_name = msg.desc.name + yield 'static const char %s_name[] = "%s";\n' % (msg.name, full_name) + yield 'std::string_view %s::msg_name(void) noexcept { return %s_name; }\n' % (msg.name, msg.name) + yield 'pb_filedesc_t %s::file_descriptor(void) noexcept { return {::file_name, ::file_descriptor}; }\n' % msg.name + yield msg.fields_definition(self.dependencies) + '\n\n' + + # Generate pb_extension_type_t definitions if extensions are used in proto file + for ext in self.extensions: + yield ext.extension_def(self.dependencies) + '\n' + + # Generate enum_name function if enum_to_string option is defined + for enum in self.enums: + yield enum.enum_to_string_definition() + '\n' + + # Generate enum_valid function if enum_valid option is defined + for enum in self.enums: + yield enum.enum_validate() + '\n' + + # Add checks for numeric limits + if self.messages: + largest_msg = max(self.messages, key = lambda m: m.count_required_fields()) + largest_count = largest_msg.count_required_fields() + if largest_count > 64: + yield '\n/* Check that missing required fields will be properly detected */\n' + yield '#if PB_MAX_REQUIRED_FIELDS < %d\n' % largest_count + yield '#error Properly detecting missing required fields in %s requires \\\n' % largest_msg.name + yield ' setting PB_MAX_REQUIRED_FIELDS to %d or more.\n' % largest_count + yield '#endif\n' + + # Add check for sizeof(double) + has_double = False + for msg in self.messages: + for field in msg.all_fields(): + if field.ctype == 'double': + has_double = True + + if has_double: + yield '\n' + yield '#ifndef PB_CONVERT_DOUBLE_FLOAT\n' + yield '/* On some platforms (such as AVR), double is really float.\n' + yield ' * To be able to encode/decode double on these platforms, you need.\n' + yield ' * to define PB_CONVERT_DOUBLE_FLOAT in pb.h or compiler command line.\n' + yield ' */\n' + yield 'PB_STATIC_ASSERT(sizeof(double) == 8, DOUBLE_MUST_BE_8_BYTES)\n' + yield '#endif\n' + + yield '\n' + + if Globals.protoc_insertion_points: + yield '/* @@protoc_insertion_point(eof) */\n' + +# --------------------------------------------------------------------------- +# Options parsing for the .proto files +# --------------------------------------------------------------------------- + +from fnmatch import fnmatchcase + +def read_options_file(infile): + '''Parse a separate options file to list: + [(namemask, options), ...] + ''' + results = [] + data = infile.read() + data = re.sub(r'/\*.*?\*/', '', data, flags = re.MULTILINE) + data = re.sub(r'//.*?$', '', data, flags = re.MULTILINE) + data = re.sub(r'#.*?$', '', data, flags = re.MULTILINE) + for i, line in enumerate(data.split('\n')): + line = line.strip() + if not line: + continue + + parts = line.split(None, 1) + + if len(parts) < 2: + sys.stderr.write("%s:%d: " % (infile.name, i + 1) + + "Option lines should have space between field name and options. " + + "Skipping line: '%s'\n" % line) + sys.exit(1) + + opts = nanopb_pb2.NanoPBOptions() + + try: + text_format.Merge(parts[1], opts) + except Exception as e: + sys.stderr.write("%s:%d: " % (infile.name, i + 1) + + "Unparsable option line: '%s'. " % line + + "Error: %s\n" % str(e)) + sys.exit(1) + results.append((parts[0], opts)) + + return results + +def get_nanopb_suboptions(subdesc, options, name): + '''Get copy of options, and merge information from subdesc.''' + new_options = nanopb_pb2.NanoPBOptions() + new_options.CopyFrom(options) + + if hasattr(subdesc, 'syntax') and subdesc.syntax == "proto3": + new_options.proto3 = True + + # Handle options defined in a separate file + dotname = '.'.join(name.parts) + for namemask, options in Globals.separate_options: + if fnmatchcase(dotname, namemask): + Globals.matched_namemasks.add(namemask) + new_options.MergeFrom(options) + + # Handle options defined in .proto + if isinstance(subdesc.options, descriptor.FieldOptions): + ext_type = nanopb_pb2.nanopb + elif isinstance(subdesc.options, descriptor.FileOptions): + ext_type = nanopb_pb2.nanopb_fileopt + elif isinstance(subdesc.options, descriptor.MessageOptions): + ext_type = nanopb_pb2.nanopb_msgopt + elif isinstance(subdesc.options, descriptor.EnumOptions): + ext_type = nanopb_pb2.nanopb_enumopt + else: + raise Exception("Unknown options type") + + if subdesc.options.HasExtension(ext_type): + ext = subdesc.options.Extensions[ext_type] + new_options.MergeFrom(ext) + + if Globals.verbose_options: + sys.stderr.write("Options for " + dotname + ": ") + sys.stderr.write(text_format.MessageToString(new_options) + "\n") + + return new_options + + +# --------------------------------------------------------------------------- +# Command line interface +# --------------------------------------------------------------------------- + +import sys +import os.path +from optparse import OptionParser + +optparser = OptionParser( + usage = "Usage: nanopb_generator.py [options] file.pb ...", + epilog = "Compile file.pb from file.proto by: 'protoc -ofile.pb file.proto'. " + + "Output will be written to file.pb.h and file.pb.c.") +optparser.add_option("-V", "--version", dest="version", action="store_true", + help="Show version info and exit (add -v for protoc version info)") +optparser.add_option("-x", dest="exclude", metavar="FILE", action="append", default=[], + help="Exclude file from generated #include list.") +optparser.add_option("-e", "--extension", dest="extension", metavar="EXTENSION", default=".pb", + help="Set extension to use instead of '.pb' for generated files. [default: %default]") +optparser.add_option("-H", "--header-extension", dest="header_extension", metavar="EXTENSION", default=".h", + help="Set extension to use for generated header files. [default: %default]") +optparser.add_option("-S", "--source-extension", dest="source_extension", metavar="EXTENSION", default=".c", + help="Set extension to use for generated source files. [default: %default]") +optparser.add_option("-f", "--options-file", dest="options_file", metavar="FILE", default="%s.options", + help="Set name of a separate generator options file.") +optparser.add_option("-I", "--options-path", "--proto-path", dest="options_path", metavar="DIR", + action="append", default = [], + help="Search path for .options and .proto files. Also determines relative paths for output directory structure.") +optparser.add_option("--error-on-unmatched", dest="error_on_unmatched", action="store_true", default=False, + help ="Stop generation if there are unmatched fields in options file") +optparser.add_option("--no-error-on-unmatched", dest="error_on_unmatched", action="store_false", default=False, + help ="Continue generation if there are unmatched fields in options file (default)") +optparser.add_option("-D", "--output-dir", dest="output_dir", + metavar="OUTPUTDIR", default=None, + help="Output directory of .pb.h and .pb.c files") +optparser.add_option("-Q", "--generated-include-format", dest="genformat", + metavar="FORMAT", default='#include "%s"', + help="Set format string to use for including other .pb.h files. Value can be 'quote', 'bracket' or a format string. [default: %default]") +optparser.add_option("-L", "--library-include-format", dest="libformat", + metavar="FORMAT", default='#include <%s>', + help="Set format string to use for including the nanopb pb.h header. Value can be 'quote', 'bracket' or a format string. [default: %default]") +optparser.add_option("--strip-path", dest="strip_path", action="store_true", default=False, + help="Strip directory path from #included .pb.h file name") +optparser.add_option("--no-strip-path", dest="strip_path", action="store_false", + help="Opposite of --strip-path (default since 0.4.0)") +optparser.add_option("--cpp-descriptors", action="store_true", + help="Generate C++ descriptors to lookup by type (e.g. pb_field_t for a message)") +optparser.add_option("-T", "--no-timestamp", dest="notimestamp", action="store_true", default=True, + help="Don't add timestamp to .pb.h and .pb.c preambles (default since 0.4.0)") +optparser.add_option("-t", "--timestamp", dest="notimestamp", action="store_false", default=True, + help="Add timestamp to .pb.h and .pb.c preambles") +optparser.add_option("-q", "--quiet", dest="quiet", action="store_true", default=False, + help="Don't print anything except errors.") +optparser.add_option("-v", "--verbose", dest="verbose", action="store_true", default=False, + help="Print more information.") +optparser.add_option("-s", dest="settings", metavar="OPTION:VALUE", action="append", default=[], + help="Set generator option (max_size, max_count etc.).") +optparser.add_option("--protoc-opt", dest="protoc_opts", action="append", default = [], metavar="OPTION", + help="Pass an option to protoc when compiling .proto files") +optparser.add_option("--protoc-insertion-points", dest="protoc_insertion_points", action="store_true", default=False, + help="Include insertion point comments in output for use by custom protoc plugins") +optparser.add_option("-C", "--c-style", dest="c_style", action="store_true", default=False, + help="Use C naming convention.") + +def process_cmdline(args, is_plugin): + '''Process command line options. Returns list of options, filenames.''' + + options, filenames = optparser.parse_args(args) + + if options.version: + if is_plugin: + sys.stderr.write('%s\n' % (nanopb_version)) + else: + print(nanopb_version) + + if options.verbose: + proto.print_versions() + + sys.exit(0) + + if not filenames and not is_plugin: + optparser.print_help() + sys.exit(1) + + if options.quiet: + options.verbose = False + + include_formats = {'quote': '#include "%s"', 'bracket': '#include <%s>'} + options.libformat = include_formats.get(options.libformat, options.libformat) + options.genformat = include_formats.get(options.genformat, options.genformat) + + if options.c_style: + Globals.naming_style = NamingStyleC() + + Globals.verbose_options = options.verbose + + if options.verbose: + sys.stderr.write("Nanopb version %s\n" % nanopb_version) + sys.stderr.write('Google Python protobuf library imported from %s, version %s\n' + % (google.protobuf.__file__, google.protobuf.__version__)) + + return options, filenames + + +def parse_file(filename, fdesc, options): + '''Parse a single file. Returns a ProtoFile instance.''' + toplevel_options = nanopb_pb2.NanoPBOptions() + for s in options.settings: + if ':' not in s and '=' in s: + s = s.replace('=', ':') + text_format.Merge(s, toplevel_options) + + if not fdesc: + data = open(filename, 'rb').read() + fdesc = descriptor.FileDescriptorSet.FromString(data).file[0] + + # Check if there is a separate .options file + had_abspath = False + try: + optfilename = options.options_file % os.path.splitext(filename)[0] + except TypeError: + # No %s specified, use the filename as-is + optfilename = options.options_file + had_abspath = True + + paths = ['.'] + options.options_path + for p in paths: + if os.path.isfile(os.path.join(p, optfilename)): + optfilename = os.path.join(p, optfilename) + if options.verbose: + sys.stderr.write('Reading options from ' + optfilename + '\n') + Globals.separate_options = read_options_file(open(optfilename, 'r', encoding = 'utf-8')) + break + else: + # If we are given a full filename and it does not exist, give an error. + # However, don't give error when we automatically look for .options file + # with the same name as .proto. + if options.verbose or had_abspath: + sys.stderr.write('Options file not found: ' + optfilename + '\n') + Globals.separate_options = [] + + Globals.matched_namemasks = set() + Globals.protoc_insertion_points = options.protoc_insertion_points + + # Parse the file + file_options = get_nanopb_suboptions(fdesc, toplevel_options, Names([filename])) + f = ProtoFile(fdesc, file_options) + f.optfilename = optfilename + + return f + +def process_file(filename, fdesc, options, other_files = {}): + '''Process a single file. + filename: The full path to the .proto or .pb source file, as string. + fdesc: The loaded FileDescriptorSet, or None to read from the input file. + options: Command line options as they come from OptionsParser. + + Returns a dict: + {'headername': Name of header file, + 'headerdata': Data for the .h header file, + 'sourcename': Name of the source code file, + 'sourcedata': Data for the .c source code file + } + ''' + f = parse_file(filename, fdesc, options) + + # Check the list of dependencies, and if they are available in other_files, + # add them to be considered for import resolving. Recursively add any files + # imported by the dependencies. + deps = list(f.fdesc.dependency) + while deps: + dep = deps.pop(0) + if dep in other_files: + f.add_dependency(other_files[dep]) + deps += list(other_files[dep].fdesc.dependency) + + # Decide the file names + noext = os.path.splitext(filename)[0] + headername = noext + options.extension + options.header_extension + sourcename = noext + options.extension + options.source_extension + + if options.strip_path: + headerbasename = os.path.basename(headername) + else: + headerbasename = headername + + # List of .proto files that should not be included in the C header file + # even if they are mentioned in the source .proto. + excludes = ['nanopb.proto', 'google/protobuf/descriptor.proto'] + options.exclude + list(f.file_options.exclude) + includes = [d for d in f.fdesc.dependency if d not in excludes] + + headerdata = ''.join(f.generate_header(includes, headerbasename, options)) + sourcedata = ''.join(f.generate_source(headerbasename, options)) + + # Check if there were any lines in .options that did not match a member + unmatched = [n for n,o in Globals.separate_options if n not in Globals.matched_namemasks] + if unmatched: + if options.error_on_unmatched: + raise Exception("Following patterns in " + f.optfilename + " did not match any fields: " + + ', '.join(unmatched)); + elif not options.quiet: + sys.stderr.write("Following patterns in " + f.optfilename + " did not match any fields: " + + ', '.join(unmatched) + "\n") + + if not Globals.verbose_options: + sys.stderr.write("Use protoc --nanopb-out=-v:. to see a list of the field names.\n") + + return {'headername': headername, 'headerdata': headerdata, + 'sourcename': sourcename, 'sourcedata': sourcedata} + +def main_cli(): + '''Main function when invoked directly from the command line.''' + + options, filenames = process_cmdline(sys.argv[1:], is_plugin = False) + + if options.output_dir and not os.path.exists(options.output_dir): + optparser.print_help() + sys.stderr.write("\noutput_dir does not exist: %s\n" % options.output_dir) + sys.exit(1) + + # Load .pb files into memory and compile any .proto files. + include_path = ['-I%s' % p for p in options.options_path] + all_fdescs = {} + out_fdescs = {} + for filename in filenames: + if filename.endswith(".proto"): + with TemporaryDirectory() as tmpdir: + tmpname = os.path.join(tmpdir, os.path.basename(filename) + ".pb") + args = ["protoc"] + include_path + args += options.protoc_opts + args += ['--include_imports', '--include_source_info', '-o' + tmpname, filename] + status = invoke_protoc(args) + if status != 0: sys.exit(status) + data = open(tmpname, 'rb').read() + else: + data = open(filename, 'rb').read() + + fdescs = descriptor.FileDescriptorSet.FromString(data).file + last_fdesc = fdescs[-1] + + for fdesc in fdescs: + all_fdescs[fdesc.name] = fdesc + + out_fdescs[last_fdesc.name] = last_fdesc + + # Process any include files first, in order to have them + # available as dependencies + other_files = {} + for fdesc in all_fdescs.values(): + other_files[fdesc.name] = parse_file(fdesc.name, fdesc, options) + + # Then generate the headers / sources + for fdesc in out_fdescs.values(): + results = process_file(fdesc.name, fdesc, options, other_files) + + base_dir = options.output_dir or '' + to_write = [ + (os.path.join(base_dir, results['headername']), results['headerdata']), + (os.path.join(base_dir, results['sourcename']), results['sourcedata']), + ] + + if not options.quiet: + paths = " and ".join([x[0] for x in to_write]) + sys.stderr.write("Writing to %s\n" % paths) + + for path, data in to_write: + dirname = os.path.dirname(path) + if dirname and not os.path.exists(dirname): + os.makedirs(dirname) + + with open(path, 'w', encoding='utf-8') as f: + f.write(data) + +def main_plugin(): + '''Main function when invoked as a protoc plugin.''' + + import io, sys + if sys.platform == "win32": + import os, msvcrt + # Set stdin and stdout to binary mode + msvcrt.setmode(sys.stdin.fileno(), os.O_BINARY) + msvcrt.setmode(sys.stdout.fileno(), os.O_BINARY) + + data = io.open(sys.stdin.fileno(), "rb").read() + + request = plugin_pb2.CodeGeneratorRequest.FromString(data) + + try: + # Versions of Python prior to 2.7.3 do not support unicode + # input to shlex.split(). Try to convert to str if possible. + params = str(request.parameter) + except UnicodeEncodeError: + params = request.parameter + + if ',' not in params and ' -' in params: + # Nanopb has traditionally supported space as separator in options + args = shlex.split(params) + else: + # Protoc separates options passed to plugins by comma + # This allows also giving --nanopb_opt option multiple times. + lex = shlex.shlex(params) + lex.whitespace_split = True + lex.whitespace = ',' + lex.commenters = '' + args = list(lex) + + optparser.usage = "protoc --nanopb_out=outdir [--nanopb_opt=option] ['--nanopb_opt=option with spaces'] file.proto" + optparser.epilog = "Output will be written to file.pb.h and file.pb.c." + + if '-h' in args or '--help' in args: + # By default optparser prints help to stdout, which doesn't work for + # protoc plugins. + optparser.print_help(sys.stderr) + sys.exit(1) + + options, dummy = process_cmdline(args, is_plugin = True) + + response = plugin_pb2.CodeGeneratorResponse() + + # Google's protoc does not currently indicate the full path of proto files. + # Instead always add the main file path to the search dirs, that works for + # the common case. + import os.path + options.options_path.append(os.path.dirname(request.file_to_generate[0])) + + # Process any include files first, in order to have them + # available as dependencies + other_files = {} + for fdesc in request.proto_file: + other_files[fdesc.name] = parse_file(fdesc.name, fdesc, options) + + for filename in request.file_to_generate: + for fdesc in request.proto_file: + if fdesc.name == filename: + results = process_file(filename, fdesc, options, other_files) + + f = response.file.add() + f.name = results['headername'] + f.content = results['headerdata'] + + f = response.file.add() + f.name = results['sourcename'] + f.content = results['sourcedata'] + + if hasattr(plugin_pb2.CodeGeneratorResponse, "FEATURE_PROTO3_OPTIONAL"): + response.supported_features = plugin_pb2.CodeGeneratorResponse.FEATURE_PROTO3_OPTIONAL + + io.open(sys.stdout.fileno(), "wb").write(response.SerializeToString()) + +if __name__ == '__main__': + # Check if we are running as a plugin under protoc + if 'protoc-gen-' in sys.argv[0] or '--protoc-plugin' in sys.argv: + main_plugin() + else: + main_cli() diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator.py2 b/wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator.py2 new file mode 100644 index 0000000000..0469461d67 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/generator/nanopb_generator.py2 @@ -0,0 +1,13 @@ +#!/usr/bin/env python2 +# This file is a wrapper around nanopb_generator.py in case you want to run +# it with Python 2 instead of default Python 3. This only exists for backwards +# compatibility, do not use for new projects. + +from nanopb_generator import * + +if __name__ == '__main__': + # Check if we are running as a plugin under protoc + if 'protoc-gen-' in sys.argv[0] or '--protoc-plugin' in sys.argv: + main_plugin() + else: + main_cli() diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/platformio_generator.py b/wpiutil/src/main/native/thirdparty/nanopb/generator/platformio_generator.py new file mode 100644 index 0000000000..0be4cfd173 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/generator/platformio_generator.py @@ -0,0 +1,157 @@ +import os +import hashlib +import pathlib +import shlex +import subprocess + +import SCons.Action +from platformio import fs + +Import("env") + +# We don't use `env.Execute` because it does not handle spaces in path +# See https://github.com/nanopb/nanopb/pull/834 +# So, we resolve the path to the executable and then use `subprocess.run` +python_exe = env.subst("$PYTHONEXE") + +try: + import google.protobuf +except ImportError: + print("[nanopb] Installing Protocol Buffers dependencies"); + + # We need to specify protobuf version. In other case got next (on Ubuntu 20.04): + # Requirement already satisfied: protobuf in /usr/lib/python3/dist-packages (3.6.1) + subprocess.run([python_exe, '-m', 'pip', 'install', "protobuf>=3.19.1"]) + +try: + import grpc_tools.protoc +except ImportError: + print("[nanopb] Installing gRPC dependencies"); + subprocess.run([python_exe, '-m', 'pip', 'install', "grpcio-tools>=1.43.0"]) + + +nanopb_root = os.path.join(os.getcwd(), '..') + +project_dir = env.subst("$PROJECT_DIR") +build_dir = env.subst("$BUILD_DIR") + +generated_src_dir = os.path.join(build_dir, 'nanopb', 'generated-src') +generated_build_dir = os.path.join(build_dir, 'nanopb', 'generated-build') +md5_dir = os.path.join(build_dir, 'nanopb', 'md5') + +nanopb_protos = env.subst(env.GetProjectOption("custom_nanopb_protos", "")) +nanopb_plugin_options = env.GetProjectOption("custom_nanopb_options", "") + +if not nanopb_protos: + print("[nanopb] No generation needed.") +else: + if isinstance(nanopb_plugin_options, (list, tuple)): + nanopb_plugin_options = " ".join(nanopb_plugin_options) + + nanopb_plugin_options = shlex.split(nanopb_plugin_options) + + protos_files = fs.match_src_files(project_dir, nanopb_protos) + if not len(protos_files): + print("[nanopb] ERROR: No files matched pattern:") + print(f"custom_nanopb_protos: {nanopb_protos}") + exit(1) + + nanopb_generator = os.path.join(nanopb_root, 'generator', 'nanopb_generator.py') + + nanopb_options = [] + nanopb_options.extend(["--output-dir", generated_src_dir]) + for opt in nanopb_plugin_options: + nanopb_options.append(opt) + + try: + os.makedirs(generated_src_dir) + except FileExistsError: + pass + + try: + os.makedirs(md5_dir) + except FileExistsError: + pass + + # Collect include dirs based on + proto_include_dirs = set() + for proto_file in protos_files: + proto_file_abs = os.path.join(project_dir, proto_file) + proto_dir = os.path.dirname(proto_file_abs) + proto_include_dirs.add(proto_dir) + + for proto_include_dir in proto_include_dirs: + nanopb_options.extend(["--proto-path", proto_include_dir]) + + for proto_file in protos_files: + proto_file_abs = os.path.join(project_dir, proto_file) + + proto_file_path_abs = os.path.dirname(proto_file_abs) + proto_file_basename = os.path.basename(proto_file_abs) + proto_file_without_ext = os.path.splitext(proto_file_basename)[0] + + proto_file_md5_abs = os.path.join(md5_dir, proto_file_basename + '.md5') + proto_file_current_md5 = hashlib.md5(pathlib.Path(proto_file_abs).read_bytes()).hexdigest() + + options_file = proto_file_without_ext + ".options" + options_file_abs = os.path.join(proto_file_path_abs, options_file) + options_file_md5_abs = None + options_file_current_md5 = None + if pathlib.Path(options_file_abs).exists(): + options_file_md5_abs = os.path.join(md5_dir, options_file + '.md5') + options_file_current_md5 = hashlib.md5(pathlib.Path(options_file_abs).read_bytes()).hexdigest() + else: + options_file = None + + header_file = proto_file_without_ext + ".pb.h" + source_file = proto_file_without_ext + ".pb.c" + + header_file_abs = os.path.join(generated_src_dir, source_file) + source_file_abs = os.path.join(generated_src_dir, header_file) + + need_generate = False + + # Check proto file md5 + try: + last_md5 = pathlib.Path(proto_file_md5_abs).read_text() + if last_md5 != proto_file_current_md5: + need_generate = True + except FileNotFoundError: + need_generate = True + + if options_file: + # Check options file md5 + try: + last_md5 = pathlib.Path(options_file_md5_abs).read_text() + if last_md5 != options_file_current_md5: + need_generate = True + except FileNotFoundError: + need_generate = True + + options_info = f"{options_file}" if options_file else "no options" + + if not need_generate: + print(f"[nanopb] Skipping '{proto_file}' ({options_info})") + else: + print(f"[nanopb] Processing '{proto_file}' ({options_info})") + cmd = [python_exe, nanopb_generator] + nanopb_options + [proto_file_basename] + action = SCons.Action.CommandAction(cmd) + result = env.Execute(action) + if result != 0: + print(f"[nanopb] ERROR: ({result}) processing cmd: '{cmd}'") + exit(1) + pathlib.Path(proto_file_md5_abs).write_text(proto_file_current_md5) + if options_file: + pathlib.Path(options_file_md5_abs).write_text(options_file_current_md5) + + # + # Add generated includes and sources to build environment + # + env.Append(CPPPATH=[generated_src_dir]) + + # Fix for ESP32 ESP-IDF https://github.com/nanopb/nanopb/issues/734#issuecomment-1001544447 + global_env = DefaultEnvironment() + already_called_env_name = "_PROTOBUF_GENERATOR_ALREADY_CALLED_" + env['PIOENV'].replace("-", "_") + if not global_env.get(already_called_env_name, False): + env.BuildSources(generated_build_dir, generated_src_dir) + global_env[already_called_env_name] = True diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/proto/Makefile b/wpiutil/src/main/native/thirdparty/nanopb/generator/proto/Makefile new file mode 100644 index 0000000000..a93d88ff2c --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/generator/proto/Makefile @@ -0,0 +1,10 @@ +PROTOC?=../protoc + +all: nanopb_pb2.py + +%_pb2.py: %.proto + $(PROTOC) --python_out=. $< + +.PHONY: clean +clean: + rm nanopb_pb2.py diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/proto/__init__.py b/wpiutil/src/main/native/thirdparty/nanopb/generator/proto/__init__.py new file mode 100644 index 0000000000..b2b47b69d7 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/generator/proto/__init__.py @@ -0,0 +1,126 @@ +'''This file dynamically builds the proto definitions for Python.''' +from __future__ import absolute_import + +import os +import os.path +import sys +import tempfile +import shutil +import traceback +from ._utils import has_grpcio_protoc, invoke_protoc, print_versions + +# Compatibility layer to make TemporaryDirectory() available on Python 2. +try: + from tempfile import TemporaryDirectory +except ImportError: + class TemporaryDirectory: + '''TemporaryDirectory fallback for Python 2''' + def __init__(self, prefix = 'tmp', dir = None): + self.prefix = prefix + self.dir = dir + + def __enter__(self): + self.dir = tempfile.mkdtemp(prefix = self.prefix, dir = self.dir) + return self.dir + + def __exit__(self, *args): + shutil.rmtree(self.dir) + +def build_nanopb_proto(protosrc, dirname): + '''Try to build a .proto file for python-protobuf. + Returns True if successful. + ''' + + cmd = [ + "protoc", + "--python_out={}".format(dirname), + protosrc, + "-I={}".format(dirname), + ] + + if has_grpcio_protoc(): + # grpcio-tools has an extra CLI argument + # from grpc.tools.protoc __main__ invocation. + cmd.append("-I={}".format(_utils.get_grpc_tools_proto_path())) + + try: + invoke_protoc(argv=cmd) + except: + sys.stderr.write("Failed to build nanopb_pb2.py: " + ' '.join(cmd) + "\n") + sys.stderr.write(traceback.format_exc() + "\n") + return False + + return True + +def load_nanopb_pb2(): + # To work, the generator needs python-protobuf built version of nanopb.proto. + # There are three methods to provide this: + # + # 1) Load a previously generated generator/proto/nanopb_pb2.py + # 2) Use protoc to build it and store it permanently generator/proto/nanopb_pb2.py + # 3) Use protoc to build it, but store only temporarily in system-wide temp folder + # + # By default these are tried in numeric order. + # If NANOPB_PB2_TEMP_DIR environment variable is defined, the 2) is skipped. + # If the value of the $NANOPB_PB2_TEMP_DIR exists as a directory, it is used instead + # of system temp folder. + + tmpdir = os.getenv("NANOPB_PB2_TEMP_DIR") + temporary_only = (tmpdir is not None) + dirname = os.path.dirname(__file__) + protosrc = os.path.join(dirname, "nanopb.proto") + protodst = os.path.join(dirname, "nanopb_pb2.py") + + if tmpdir is not None and not os.path.isdir(tmpdir): + tmpdir = None # Use system-wide temp dir + + no_rebuild = bool(int(os.getenv("NANOPB_PB2_NO_REBUILD", default = 0))) + if bool(no_rebuild): + # Don't attempt to autogenerate nanopb_pb2.py, external build rules + # should have already done so. + import nanopb_pb2 as nanopb_pb2_mod + return nanopb_pb2_mod + + if os.path.isfile(protosrc): + src_date = os.path.getmtime(protosrc) + if os.path.isfile(protodst) and os.path.getmtime(protodst) >= src_date: + try: + from . import nanopb_pb2 as nanopb_pb2_mod + return nanopb_pb2_mod + except Exception as e: + sys.stderr.write("Failed to import nanopb_pb2.py: " + str(e) + "\n" + "Will automatically attempt to rebuild this.\n" + "Verify that python-protobuf and protoc versions match.\n") + print_versions() + + # Try to rebuild into generator/proto directory + if not temporary_only: + build_nanopb_proto(protosrc, dirname) + + try: + from . import nanopb_pb2 as nanopb_pb2_mod + return nanopb_pb2_mod + except: + sys.stderr.write("Failed to import generator/proto/nanopb_pb2.py:\n") + sys.stderr.write(traceback.format_exc() + "\n") + + # Try to rebuild into temporary directory + with TemporaryDirectory(prefix = 'nanopb-', dir = tmpdir) as protodir: + build_nanopb_proto(protosrc, protodir) + + if protodir not in sys.path: + sys.path.insert(0, protodir) + + try: + import nanopb_pb2 as nanopb_pb2_mod + return nanopb_pb2_mod + except: + sys.stderr.write("Failed to import %s/nanopb_pb2.py:\n" % protodir) + sys.stderr.write(traceback.format_exc() + "\n") + + # If everything fails + sys.stderr.write("\n\nGenerating nanopb_pb2.py failed.\n") + sys.stderr.write("Make sure that a protoc generator is available and matches python-protobuf version.\n") + print_versions() + sys.exit(1) + diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/proto/_utils.py b/wpiutil/src/main/native/thirdparty/nanopb/generator/proto/_utils.py new file mode 100644 index 0000000000..705629f308 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/generator/proto/_utils.py @@ -0,0 +1,104 @@ +import sys +import subprocess +import os.path + +import traceback + +def has_grpcio_protoc(verbose = False): + # type: () -> bool + """ checks if grpcio-tools protoc is installed""" + + try: + import grpc_tools.protoc + except ImportError: + if verbose: + sys.stderr.write("Failed to import grpc_tools: %s\n" % traceback.format_exc()) + return False + + return True + +def get_grpc_tools_proto_path(): + if sys.hexversion > 0x03090000: + import importlib.resources as ir + with ir.as_file(ir.files('grpc_tools') / '_proto') as path: + return str(path) + else: + import pkg_resources + return pkg_resources.resource_filename('grpc_tools', '_proto') + +def get_proto_builtin_include_path(): + """Find include path for standard google/protobuf includes and for + nanopb.proto. + """ + + if getattr(sys, 'frozen', False): + # Pyinstaller package + paths = [ + os.path.join(os.path.dirname(os.path.abspath(sys.executable)), 'proto'), + os.path.join(os.path.dirname(os.path.abspath(sys.executable)), 'grpc_tools', '_proto') + ] + + else: + # Stand-alone script + paths = [ + os.path.dirname(os.path.abspath(__file__)) + ] + + if has_grpcio_protoc(): + paths.append(get_grpc_tools_proto_path()) + + return paths + +def invoke_protoc(argv): + # type: (list) -> typing.Any + """ + Invoke protoc. + + This routine will use grpcio-provided protoc if it exists, + using system-installed protoc as a fallback. + + Args: + argv: protoc CLI invocation, first item must be 'protoc' + """ + + # Add current directory to include path if nothing else is specified + if not [x for x in argv if x.startswith('-I')]: + argv.append("-I.") + + # Add default protoc include paths + for incpath in get_proto_builtin_include_path(): + argv.append('-I' + incpath) + + if has_grpcio_protoc(): + import grpc_tools.protoc as protoc + return protoc.main(argv) + else: + return subprocess.call(argv) + +def print_versions(): + try: + if has_grpcio_protoc(verbose = True): + import grpc_tools.protoc + sys.stderr.write("Using grpcio-tools protoc from " + grpc_tools.protoc.__file__ + "\n") + else: + sys.stderr.write("Using protoc from system path\n") + + invoke_protoc(['protoc', '--version']) + except Exception as e: + sys.stderr.write("Failed to determine protoc version: " + str(e) + "\n") + + try: + sys.stderr.write("protoc builtin include path: " + str(get_proto_builtin_include_path()) + "\n") + except Exception as e: + sys.stderr.write("Failed to construct protoc include path: " + str(e) + "\n") + + try: + import google.protobuf + sys.stderr.write("Python version " + sys.version + "\n") + sys.stderr.write("Using python-protobuf from " + google.protobuf.__file__ + "\n") + sys.stderr.write("Python-protobuf version: " + google.protobuf.__version__ + "\n") + except Exception as e: + sys.stderr.write("Failed to determine python-protobuf version: " + str(e) + "\n") + +if __name__ == '__main__': + print_versions() diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/proto/google/protobuf/descriptor.proto b/wpiutil/src/main/native/thirdparty/nanopb/generator/proto/google/protobuf/descriptor.proto new file mode 100644 index 0000000000..4752e3d533 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/generator/proto/google/protobuf/descriptor.proto @@ -0,0 +1,1293 @@ +// Protocol Buffers - Google's data interchange format +// Copyright 2008 Google Inc. All rights reserved. +// https://developers.google.com/protocol-buffers/ +// +// Redistribution and use in source and binary forms, with or without +// modification, are permitted provided that the following conditions are +// met: +// +// * Redistributions of source code must retain the above copyright +// notice, this list of conditions and the following disclaimer. +// * Redistributions in binary form must reproduce the above +// copyright notice, this list of conditions and the following disclaimer +// in the documentation and/or other materials provided with the +// distribution. +// * Neither the name of Google Inc. nor the names of its +// contributors may be used to endorse or promote products derived from +// this software without specific prior written permission. +// +// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR +// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT +// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, +// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT +// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, +// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY +// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE +// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + +// Author: kenton@google.com (Kenton Varda) +// Based on original Protocol Buffers design by +// Sanjay Ghemawat, Jeff Dean, and others. +// +// The messages in this file describe the definitions found in .proto files. +// A valid .proto file can be translated directly to a FileDescriptorProto +// without any other information (e.g. without reading its imports). + +syntax = "proto2"; + +package google.protobuf; + +option go_package = "google.golang.org/protobuf/types/descriptorpb"; +option java_package = "com.google.protobuf"; +option java_outer_classname = "DescriptorProtos"; +option csharp_namespace = "Google.Protobuf.Reflection"; +option objc_class_prefix = "GPB"; +option cc_enable_arenas = true; + +// descriptor.proto must be optimized for speed because reflection-based +// algorithms don't work during bootstrapping. +option optimize_for = SPEED; + +// The protocol compiler can output a FileDescriptorSet containing the .proto +// files it parses. +message FileDescriptorSet { + repeated FileDescriptorProto file = 1; +} + +// The full set of known editions. +enum Edition { + // A placeholder for an unknown edition value. + EDITION_UNKNOWN = 0; + + // A placeholder edition for specifying default behaviors *before* a feature + // was first introduced. This is effectively an "infinite past". + EDITION_LEGACY = 900; + + // Legacy syntax "editions". These pre-date editions, but behave much like + // distinct editions. These can't be used to specify the edition of proto + // files, but feature definitions must supply proto2/proto3 defaults for + // backwards compatibility. + EDITION_PROTO2 = 998; + EDITION_PROTO3 = 999; + + // Editions that have been released. The specific values are arbitrary and + // should not be depended on, but they will always be time-ordered for easy + // comparison. + EDITION_2023 = 1000; + EDITION_2024 = 1001; + + // Placeholder editions for testing feature resolution. These should not be + // used or relyed on outside of tests. + EDITION_1_TEST_ONLY = 1; + EDITION_2_TEST_ONLY = 2; + EDITION_99997_TEST_ONLY = 99997; + EDITION_99998_TEST_ONLY = 99998; + EDITION_99999_TEST_ONLY = 99999; + + // Placeholder for specifying unbounded edition support. This should only + // ever be used by plugins that can expect to never require any changes to + // support a new edition. + EDITION_MAX = 0x7FFFFFFF; +} + +// Describes a complete .proto file. +message FileDescriptorProto { + optional string name = 1; // file name, relative to root of source tree + optional string package = 2; // e.g. "foo", "foo.bar", etc. + + // Names of files imported by this file. + repeated string dependency = 3; + // Indexes of the public imported files in the dependency list above. + repeated int32 public_dependency = 10; + // Indexes of the weak imported files in the dependency list. + // For Google-internal migration only. Do not use. + repeated int32 weak_dependency = 11; + + // All top-level definitions in this file. + repeated DescriptorProto message_type = 4; + repeated EnumDescriptorProto enum_type = 5; + repeated ServiceDescriptorProto service = 6; + repeated FieldDescriptorProto extension = 7; + + optional FileOptions options = 8; + + // This field contains optional information about the original source code. + // You may safely remove this entire field without harming runtime + // functionality of the descriptors -- the information is needed only by + // development tools. + optional SourceCodeInfo source_code_info = 9; + + // The syntax of the proto file. + // The supported values are "proto2", "proto3", and "editions". + // + // If `edition` is present, this value must be "editions". + optional string syntax = 12; + + // The edition of the proto file. + optional Edition edition = 14; +} + +// Describes a message type. +message DescriptorProto { + optional string name = 1; + + repeated FieldDescriptorProto field = 2; + repeated FieldDescriptorProto extension = 6; + + repeated DescriptorProto nested_type = 3; + repeated EnumDescriptorProto enum_type = 4; + + message ExtensionRange { + optional int32 start = 1; // Inclusive. + optional int32 end = 2; // Exclusive. + + optional ExtensionRangeOptions options = 3; + } + repeated ExtensionRange extension_range = 5; + + repeated OneofDescriptorProto oneof_decl = 8; + + optional MessageOptions options = 7; + + // Range of reserved tag numbers. Reserved tag numbers may not be used by + // fields or extension ranges in the same message. Reserved ranges may + // not overlap. + message ReservedRange { + optional int32 start = 1; // Inclusive. + optional int32 end = 2; // Exclusive. + } + repeated ReservedRange reserved_range = 9; + // Reserved field names, which may not be used by fields in the same message. + // A given name may only be reserved once. + repeated string reserved_name = 10; +} + +message ExtensionRangeOptions { + // The parser stores options it doesn't recognize here. See above. + repeated UninterpretedOption uninterpreted_option = 999; + + message Declaration { + // The extension number declared within the extension range. + optional int32 number = 1; + + // The fully-qualified name of the extension field. There must be a leading + // dot in front of the full name. + optional string full_name = 2; + + // The fully-qualified type name of the extension field. Unlike + // Metadata.type, Declaration.type must have a leading dot for messages + // and enums. + optional string type = 3; + + // If true, indicates that the number is reserved in the extension range, + // and any extension field with the number will fail to compile. Set this + // when a declared extension field is deleted. + optional bool reserved = 5; + + // If true, indicates that the extension must be defined as repeated. + // Otherwise the extension must be defined as optional. + optional bool repeated = 6; + + reserved 4; // removed is_repeated + } + + // For external users: DO NOT USE. We are in the process of open sourcing + // extension declaration and executing internal cleanups before it can be + // used externally. + repeated Declaration declaration = 2 [retention = RETENTION_SOURCE]; + + // Any features defined in the specific edition. + optional FeatureSet features = 50; + + // The verification state of the extension range. + enum VerificationState { + // All the extensions of the range must be declared. + DECLARATION = 0; + UNVERIFIED = 1; + } + + // The verification state of the range. + // TODO: flip the default to DECLARATION once all empty ranges + // are marked as UNVERIFIED. + optional VerificationState verification = 3 + [default = UNVERIFIED, retention = RETENTION_SOURCE]; + + // Clients can define custom options in extensions of this message. See above. + extensions 1000 to max; +} + +// Describes a field within a message. +message FieldDescriptorProto { + enum Type { + // 0 is reserved for errors. + // Order is weird for historical reasons. + TYPE_DOUBLE = 1; + TYPE_FLOAT = 2; + // Not ZigZag encoded. Negative numbers take 10 bytes. Use TYPE_SINT64 if + // negative values are likely. + TYPE_INT64 = 3; + TYPE_UINT64 = 4; + // Not ZigZag encoded. Negative numbers take 10 bytes. Use TYPE_SINT32 if + // negative values are likely. + TYPE_INT32 = 5; + TYPE_FIXED64 = 6; + TYPE_FIXED32 = 7; + TYPE_BOOL = 8; + TYPE_STRING = 9; + // Tag-delimited aggregate. + // Group type is deprecated and not supported after google.protobuf. However, Proto3 + // implementations should still be able to parse the group wire format and + // treat group fields as unknown fields. In Editions, the group wire format + // can be enabled via the `message_encoding` feature. + TYPE_GROUP = 10; + TYPE_MESSAGE = 11; // Length-delimited aggregate. + + // New in version 2. + TYPE_BYTES = 12; + TYPE_UINT32 = 13; + TYPE_ENUM = 14; + TYPE_SFIXED32 = 15; + TYPE_SFIXED64 = 16; + TYPE_SINT32 = 17; // Uses ZigZag encoding. + TYPE_SINT64 = 18; // Uses ZigZag encoding. + } + + enum Label { + // 0 is reserved for errors + LABEL_OPTIONAL = 1; + LABEL_REPEATED = 3; + // The required label is only allowed in google.protobuf. In proto3 and Editions + // it's explicitly prohibited. In Editions, the `field_presence` feature + // can be used to get this behavior. + LABEL_REQUIRED = 2; + } + + optional string name = 1; + optional int32 number = 3; + optional Label label = 4; + + // If type_name is set, this need not be set. If both this and type_name + // are set, this must be one of TYPE_ENUM, TYPE_MESSAGE or TYPE_GROUP. + optional Type type = 5; + + // For message and enum types, this is the name of the type. If the name + // starts with a '.', it is fully-qualified. Otherwise, C++-like scoping + // rules are used to find the type (i.e. first the nested types within this + // message are searched, then within the parent, on up to the root + // namespace). + optional string type_name = 6; + + // For extensions, this is the name of the type being extended. It is + // resolved in the same manner as type_name. + optional string extendee = 2; + + // For numeric types, contains the original text representation of the value. + // For booleans, "true" or "false". + // For strings, contains the default text contents (not escaped in any way). + // For bytes, contains the C escaped value. All bytes >= 128 are escaped. + optional string default_value = 7; + + // If set, gives the index of a oneof in the containing type's oneof_decl + // list. This field is a member of that oneof. + optional int32 oneof_index = 9; + + // JSON name of this field. The value is set by protocol compiler. If the + // user has set a "json_name" option on this field, that option's value + // will be used. Otherwise, it's deduced from the field's name by converting + // it to camelCase. + optional string json_name = 10; + + optional FieldOptions options = 8; + + // If true, this is a proto3 "optional". When a proto3 field is optional, it + // tracks presence regardless of field type. + // + // When proto3_optional is true, this field must belong to a oneof to signal + // to old proto3 clients that presence is tracked for this field. This oneof + // is known as a "synthetic" oneof, and this field must be its sole member + // (each proto3 optional field gets its own synthetic oneof). Synthetic oneofs + // exist in the descriptor only, and do not generate any API. Synthetic oneofs + // must be ordered after all "real" oneofs. + // + // For message fields, proto3_optional doesn't create any semantic change, + // since non-repeated message fields always track presence. However it still + // indicates the semantic detail of whether the user wrote "optional" or not. + // This can be useful for round-tripping the .proto file. For consistency we + // give message fields a synthetic oneof also, even though it is not required + // to track presence. This is especially important because the parser can't + // tell if a field is a message or an enum, so it must always create a + // synthetic oneof. + // + // Proto2 optional fields do not set this flag, because they already indicate + // optional with `LABEL_OPTIONAL`. + optional bool proto3_optional = 17; +} + +// Describes a oneof. +message OneofDescriptorProto { + optional string name = 1; + optional OneofOptions options = 2; +} + +// Describes an enum type. +message EnumDescriptorProto { + optional string name = 1; + + repeated EnumValueDescriptorProto value = 2; + + optional EnumOptions options = 3; + + // Range of reserved numeric values. Reserved values may not be used by + // entries in the same enum. Reserved ranges may not overlap. + // + // Note that this is distinct from DescriptorProto.ReservedRange in that it + // is inclusive such that it can appropriately represent the entire int32 + // domain. + message EnumReservedRange { + optional int32 start = 1; // Inclusive. + optional int32 end = 2; // Inclusive. + } + + // Range of reserved numeric values. Reserved numeric values may not be used + // by enum values in the same enum declaration. Reserved ranges may not + // overlap. + repeated EnumReservedRange reserved_range = 4; + + // Reserved enum value names, which may not be reused. A given name may only + // be reserved once. + repeated string reserved_name = 5; +} + +// Describes a value within an enum. +message EnumValueDescriptorProto { + optional string name = 1; + optional int32 number = 2; + + optional EnumValueOptions options = 3; +} + +// Describes a service. +message ServiceDescriptorProto { + optional string name = 1; + repeated MethodDescriptorProto method = 2; + + optional ServiceOptions options = 3; +} + +// Describes a method of a service. +message MethodDescriptorProto { + optional string name = 1; + + // Input and output type names. These are resolved in the same way as + // FieldDescriptorProto.type_name, but must refer to a message type. + optional string input_type = 2; + optional string output_type = 3; + + optional MethodOptions options = 4; + + // Identifies if client streams multiple client messages + optional bool client_streaming = 5 [default = false]; + // Identifies if server streams multiple server messages + optional bool server_streaming = 6 [default = false]; +} + +// =================================================================== +// Options + +// Each of the definitions above may have "options" attached. These are +// just annotations which may cause code to be generated slightly differently +// or may contain hints for code that manipulates protocol messages. +// +// Clients may define custom options as extensions of the *Options messages. +// These extensions may not yet be known at parsing time, so the parser cannot +// store the values in them. Instead it stores them in a field in the *Options +// message called uninterpreted_option. This field must have the same name +// across all *Options messages. We then use this field to populate the +// extensions when we build a descriptor, at which point all protos have been +// parsed and so all extensions are known. +// +// Extension numbers for custom options may be chosen as follows: +// * For options which will only be used within a single application or +// organization, or for experimental options, use field numbers 50000 +// through 99999. It is up to you to ensure that you do not use the +// same number for multiple options. +// * For options which will be published and used publicly by multiple +// independent entities, e-mail protobuf-global-extension-registry@google.com +// to reserve extension numbers. Simply provide your project name (e.g. +// Objective-C plugin) and your project website (if available) -- there's no +// need to explain how you intend to use them. Usually you only need one +// extension number. You can declare multiple options with only one extension +// number by putting them in a sub-message. See the Custom Options section of +// the docs for examples: +// https://developers.google.com/protocol-buffers/docs/proto#options +// If this turns out to be popular, a web service will be set up +// to automatically assign option numbers. + +message FileOptions { + + // Sets the Java package where classes generated from this .proto will be + // placed. By default, the proto package is used, but this is often + // inappropriate because proto packages do not normally start with backwards + // domain names. + optional string java_package = 1; + + // Controls the name of the wrapper Java class generated for the .proto file. + // That class will always contain the .proto file's getDescriptor() method as + // well as any top-level extensions defined in the .proto file. + // If java_multiple_files is disabled, then all the other classes from the + // .proto file will be nested inside the single wrapper outer class. + optional string java_outer_classname = 8; + + // If enabled, then the Java code generator will generate a separate .java + // file for each top-level message, enum, and service defined in the .proto + // file. Thus, these types will *not* be nested inside the wrapper class + // named by java_outer_classname. However, the wrapper class will still be + // generated to contain the file's getDescriptor() method as well as any + // top-level extensions defined in the file. + optional bool java_multiple_files = 10 [default = false]; + + // This option does nothing. + optional bool java_generate_equals_and_hash = 20 [deprecated=true]; + + // A proto2 file can set this to true to opt in to UTF-8 checking for Java, + // which will throw an exception if invalid UTF-8 is parsed from the wire or + // assigned to a string field. + // + // TODO: clarify exactly what kinds of field types this option + // applies to, and update these docs accordingly. + // + // Proto3 files already perform these checks. Setting the option explicitly to + // false has no effect: it cannot be used to opt proto3 files out of UTF-8 + // checks. + optional bool java_string_check_utf8 = 27 [default = false]; + + // Generated classes can be optimized for speed or code size. + enum OptimizeMode { + SPEED = 1; // Generate complete code for parsing, serialization, + // etc. + CODE_SIZE = 2; // Use ReflectionOps to implement these methods. + LITE_RUNTIME = 3; // Generate code using MessageLite and the lite runtime. + } + optional OptimizeMode optimize_for = 9 [default = SPEED]; + + // Sets the Go package where structs generated from this .proto will be + // placed. If omitted, the Go package will be derived from the following: + // - The basename of the package import path, if provided. + // - Otherwise, the package statement in the .proto file, if present. + // - Otherwise, the basename of the .proto file, without extension. + optional string go_package = 11; + + // Should generic services be generated in each language? "Generic" services + // are not specific to any particular RPC system. They are generated by the + // main code generators in each language (without additional plugins). + // Generic services were the only kind of service generation supported by + // early versions of google.protobuf. + // + // Generic services are now considered deprecated in favor of using plugins + // that generate code specific to your particular RPC system. Therefore, + // these default to false. Old code which depends on generic services should + // explicitly set them to true. + optional bool cc_generic_services = 16 [default = false]; + optional bool java_generic_services = 17 [default = false]; + optional bool py_generic_services = 18 [default = false]; + reserved 42; // removed php_generic_services + reserved "php_generic_services"; + + // Is this file deprecated? + // Depending on the target platform, this can emit Deprecated annotations + // for everything in the file, or it will be completely ignored; in the very + // least, this is a formalization for deprecating files. + optional bool deprecated = 23 [default = false]; + + // Enables the use of arenas for the proto messages in this file. This applies + // only to generated classes for C++. + optional bool cc_enable_arenas = 31 [default = true]; + + // Sets the objective c class prefix which is prepended to all objective c + // generated classes from this .proto. There is no default. + optional string objc_class_prefix = 36; + + // Namespace for generated classes; defaults to the package. + optional string csharp_namespace = 37; + + // By default Swift generators will take the proto package and CamelCase it + // replacing '.' with underscore and use that to prefix the types/symbols + // defined. When this options is provided, they will use this value instead + // to prefix the types/symbols defined. + optional string swift_prefix = 39; + + // Sets the php class prefix which is prepended to all php generated classes + // from this .proto. Default is empty. + optional string php_class_prefix = 40; + + // Use this option to change the namespace of php generated classes. Default + // is empty. When this option is empty, the package name will be used for + // determining the namespace. + optional string php_namespace = 41; + + // Use this option to change the namespace of php generated metadata classes. + // Default is empty. When this option is empty, the proto file name will be + // used for determining the namespace. + optional string php_metadata_namespace = 44; + + // Use this option to change the package of ruby generated classes. Default + // is empty. When this option is not set, the package name will be used for + // determining the ruby package. + optional string ruby_package = 45; + + // Any features defined in the specific edition. + optional FeatureSet features = 50; + + // The parser stores options it doesn't recognize here. + // See the documentation for the "Options" section above. + repeated UninterpretedOption uninterpreted_option = 999; + + // Clients can define custom options in extensions of this message. + // See the documentation for the "Options" section above. + extensions 1000 to max; + + reserved 38; +} + +message MessageOptions { + // Set true to use the old proto1 MessageSet wire format for extensions. + // This is provided for backwards-compatibility with the MessageSet wire + // format. You should not use this for any other reason: It's less + // efficient, has fewer features, and is more complicated. + // + // The message must be defined exactly as follows: + // message Foo { + // option message_set_wire_format = true; + // extensions 4 to max; + // } + // Note that the message cannot have any defined fields; MessageSets only + // have extensions. + // + // All extensions of your type must be singular messages; e.g. they cannot + // be int32s, enums, or repeated messages. + // + // Because this is an option, the above two restrictions are not enforced by + // the protocol compiler. + optional bool message_set_wire_format = 1 [default = false]; + + // Disables the generation of the standard "descriptor()" accessor, which can + // conflict with a field of the same name. This is meant to make migration + // from proto1 easier; new code should avoid fields named "descriptor". + optional bool no_standard_descriptor_accessor = 2 [default = false]; + + // Is this message deprecated? + // Depending on the target platform, this can emit Deprecated annotations + // for the message, or it will be completely ignored; in the very least, + // this is a formalization for deprecating messages. + optional bool deprecated = 3 [default = false]; + + reserved 4, 5, 6; + + // Whether the message is an automatically generated map entry type for the + // maps field. + // + // For maps fields: + // map map_field = 1; + // The parsed descriptor looks like: + // message MapFieldEntry { + // option map_entry = true; + // optional KeyType key = 1; + // optional ValueType value = 2; + // } + // repeated MapFieldEntry map_field = 1; + // + // Implementations may choose not to generate the map_entry=true message, but + // use a native map in the target language to hold the keys and values. + // The reflection APIs in such implementations still need to work as + // if the field is a repeated message field. + // + // NOTE: Do not set the option in .proto files. Always use the maps syntax + // instead. The option should only be implicitly set by the proto compiler + // parser. + optional bool map_entry = 7; + + reserved 8; // javalite_serializable + reserved 9; // javanano_as_lite + + // Enable the legacy handling of JSON field name conflicts. This lowercases + // and strips underscored from the fields before comparison in proto3 only. + // The new behavior takes `json_name` into account and applies to proto2 as + // well. + // + // This should only be used as a temporary measure against broken builds due + // to the change in behavior for JSON field name conflicts. + // + // TODO This is legacy behavior we plan to remove once downstream + // teams have had time to migrate. + optional bool deprecated_legacy_json_field_conflicts = 11 [deprecated = true]; + + // Any features defined in the specific edition. + optional FeatureSet features = 12; + + // The parser stores options it doesn't recognize here. See above. + repeated UninterpretedOption uninterpreted_option = 999; + + // Clients can define custom options in extensions of this message. See above. + extensions 1000 to max; +} + +message FieldOptions { + // NOTE: ctype is deprecated. Use `features.(pb.cpp).string_type` instead. + // The ctype option instructs the C++ code generator to use a different + // representation of the field than it normally would. See the specific + // options below. This option is only implemented to support use of + // [ctype=CORD] and [ctype=STRING] (the default) on non-repeated fields of + // type "bytes" in the open source release. + // TODO: make ctype actually deprecated. + optional CType ctype = 1 [/*deprecated = true,*/ default = STRING]; + enum CType { + // Default mode. + STRING = 0; + + // The option [ctype=CORD] may be applied to a non-repeated field of type + // "bytes". It indicates that in C++, the data should be stored in a Cord + // instead of a string. For very large strings, this may reduce memory + // fragmentation. It may also allow better performance when parsing from a + // Cord, or when parsing with aliasing enabled, as the parsed Cord may then + // alias the original buffer. + CORD = 1; + + STRING_PIECE = 2; + } + // The packed option can be enabled for repeated primitive fields to enable + // a more efficient representation on the wire. Rather than repeatedly + // writing the tag and type for each element, the entire array is encoded as + // a single length-delimited blob. In proto3, only explicit setting it to + // false will avoid using packed encoding. This option is prohibited in + // Editions, but the `repeated_field_encoding` feature can be used to control + // the behavior. + optional bool packed = 2; + + // The jstype option determines the JavaScript type used for values of the + // field. The option is permitted only for 64 bit integral and fixed types + // (int64, uint64, sint64, fixed64, sfixed64). A field with jstype JS_STRING + // is represented as JavaScript string, which avoids loss of precision that + // can happen when a large value is converted to a floating point JavaScript. + // Specifying JS_NUMBER for the jstype causes the generated JavaScript code to + // use the JavaScript "number" type. The behavior of the default option + // JS_NORMAL is implementation dependent. + // + // This option is an enum to permit additional types to be added, e.g. + // goog.math.Integer. + optional JSType jstype = 6 [default = JS_NORMAL]; + enum JSType { + // Use the default type. + JS_NORMAL = 0; + + // Use JavaScript strings. + JS_STRING = 1; + + // Use JavaScript numbers. + JS_NUMBER = 2; + } + + // Should this field be parsed lazily? Lazy applies only to message-type + // fields. It means that when the outer message is initially parsed, the + // inner message's contents will not be parsed but instead stored in encoded + // form. The inner message will actually be parsed when it is first accessed. + // + // This is only a hint. Implementations are free to choose whether to use + // eager or lazy parsing regardless of the value of this option. However, + // setting this option true suggests that the protocol author believes that + // using lazy parsing on this field is worth the additional bookkeeping + // overhead typically needed to implement it. + // + // This option does not affect the public interface of any generated code; + // all method signatures remain the same. Furthermore, thread-safety of the + // interface is not affected by this option; const methods remain safe to + // call from multiple threads concurrently, while non-const methods continue + // to require exclusive access. + // + // Note that lazy message fields are still eagerly verified to check + // ill-formed wireformat or missing required fields. Calling IsInitialized() + // on the outer message would fail if the inner message has missing required + // fields. Failed verification would result in parsing failure (except when + // uninitialized messages are acceptable). + optional bool lazy = 5 [default = false]; + + // unverified_lazy does no correctness checks on the byte stream. This should + // only be used where lazy with verification is prohibitive for performance + // reasons. + optional bool unverified_lazy = 15 [default = false]; + + // Is this field deprecated? + // Depending on the target platform, this can emit Deprecated annotations + // for accessors, or it will be completely ignored; in the very least, this + // is a formalization for deprecating fields. + optional bool deprecated = 3 [default = false]; + + // For Google-internal migration only. Do not use. + optional bool weak = 10 [default = false]; + + // Indicate that the field value should not be printed out when using debug + // formats, e.g. when the field contains sensitive credentials. + optional bool debug_redact = 16 [default = false]; + + // If set to RETENTION_SOURCE, the option will be omitted from the binary. + enum OptionRetention { + RETENTION_UNKNOWN = 0; + RETENTION_RUNTIME = 1; + RETENTION_SOURCE = 2; + } + + optional OptionRetention retention = 17; + + // This indicates the types of entities that the field may apply to when used + // as an option. If it is unset, then the field may be freely used as an + // option on any kind of entity. + enum OptionTargetType { + TARGET_TYPE_UNKNOWN = 0; + TARGET_TYPE_FILE = 1; + TARGET_TYPE_EXTENSION_RANGE = 2; + TARGET_TYPE_MESSAGE = 3; + TARGET_TYPE_FIELD = 4; + TARGET_TYPE_ONEOF = 5; + TARGET_TYPE_ENUM = 6; + TARGET_TYPE_ENUM_ENTRY = 7; + TARGET_TYPE_SERVICE = 8; + TARGET_TYPE_METHOD = 9; + } + + repeated OptionTargetType targets = 19; + + message EditionDefault { + optional Edition edition = 3; + optional string value = 2; // Textproto value. + } + repeated EditionDefault edition_defaults = 20; + + // Any features defined in the specific edition. + optional FeatureSet features = 21; + + // Information about the support window of a feature. + message FeatureSupport { + // The edition that this feature was first available in. In editions + // earlier than this one, the default assigned to EDITION_LEGACY will be + // used, and proto files will not be able to override it. + optional Edition edition_introduced = 1; + + // The edition this feature becomes deprecated in. Using this after this + // edition may trigger warnings. + optional Edition edition_deprecated = 2; + + // The deprecation warning text if this feature is used after the edition it + // was marked deprecated in. + optional string deprecation_warning = 3; + + // The edition this feature is no longer available in. In editions after + // this one, the last default assigned will be used, and proto files will + // not be able to override it. + optional Edition edition_removed = 4; + } + optional FeatureSupport feature_support = 22; + + // The parser stores options it doesn't recognize here. See above. + repeated UninterpretedOption uninterpreted_option = 999; + + // Clients can define custom options in extensions of this message. See above. + extensions 1000 to max; + + reserved 4; // removed jtype + reserved 18; // reserve target, target_obsolete_do_not_use +} + +message OneofOptions { + // Any features defined in the specific edition. + optional FeatureSet features = 1; + + // The parser stores options it doesn't recognize here. See above. + repeated UninterpretedOption uninterpreted_option = 999; + + // Clients can define custom options in extensions of this message. See above. + extensions 1000 to max; +} + +message EnumOptions { + + // Set this option to true to allow mapping different tag names to the same + // value. + optional bool allow_alias = 2; + + // Is this enum deprecated? + // Depending on the target platform, this can emit Deprecated annotations + // for the enum, or it will be completely ignored; in the very least, this + // is a formalization for deprecating enums. + optional bool deprecated = 3 [default = false]; + + reserved 5; // javanano_as_lite + + // Enable the legacy handling of JSON field name conflicts. This lowercases + // and strips underscored from the fields before comparison in proto3 only. + // The new behavior takes `json_name` into account and applies to proto2 as + // well. + // TODO Remove this legacy behavior once downstream teams have + // had time to migrate. + optional bool deprecated_legacy_json_field_conflicts = 6 [deprecated = true]; + + // Any features defined in the specific edition. + optional FeatureSet features = 7; + + // The parser stores options it doesn't recognize here. See above. + repeated UninterpretedOption uninterpreted_option = 999; + + // Clients can define custom options in extensions of this message. See above. + extensions 1000 to max; +} + +message EnumValueOptions { + // Is this enum value deprecated? + // Depending on the target platform, this can emit Deprecated annotations + // for the enum value, or it will be completely ignored; in the very least, + // this is a formalization for deprecating enum values. + optional bool deprecated = 1 [default = false]; + + // Any features defined in the specific edition. + optional FeatureSet features = 2; + + // Indicate that fields annotated with this enum value should not be printed + // out when using debug formats, e.g. when the field contains sensitive + // credentials. + optional bool debug_redact = 3 [default = false]; + + // Information about the support window of a feature value. + optional FieldOptions.FeatureSupport feature_support = 4; + + // The parser stores options it doesn't recognize here. See above. + repeated UninterpretedOption uninterpreted_option = 999; + + // Clients can define custom options in extensions of this message. See above. + extensions 1000 to max; +} + +message ServiceOptions { + + // Any features defined in the specific edition. + optional FeatureSet features = 34; + + // Note: Field numbers 1 through 32 are reserved for Google's internal RPC + // framework. We apologize for hoarding these numbers to ourselves, but + // we were already using them long before we decided to release Protocol + // Buffers. + + // Is this service deprecated? + // Depending on the target platform, this can emit Deprecated annotations + // for the service, or it will be completely ignored; in the very least, + // this is a formalization for deprecating services. + optional bool deprecated = 33 [default = false]; + + // The parser stores options it doesn't recognize here. See above. + repeated UninterpretedOption uninterpreted_option = 999; + + // Clients can define custom options in extensions of this message. See above. + extensions 1000 to max; +} + +message MethodOptions { + + // Note: Field numbers 1 through 32 are reserved for Google's internal RPC + // framework. We apologize for hoarding these numbers to ourselves, but + // we were already using them long before we decided to release Protocol + // Buffers. + + // Is this method deprecated? + // Depending on the target platform, this can emit Deprecated annotations + // for the method, or it will be completely ignored; in the very least, + // this is a formalization for deprecating methods. + optional bool deprecated = 33 [default = false]; + + // Is this method side-effect-free (or safe in HTTP parlance), or idempotent, + // or neither? HTTP based RPC implementation may choose GET verb for safe + // methods, and PUT verb for idempotent methods instead of the default POST. + enum IdempotencyLevel { + IDEMPOTENCY_UNKNOWN = 0; + NO_SIDE_EFFECTS = 1; // implies idempotent + IDEMPOTENT = 2; // idempotent, but may have side effects + } + optional IdempotencyLevel idempotency_level = 34 + [default = IDEMPOTENCY_UNKNOWN]; + + // Any features defined in the specific edition. + optional FeatureSet features = 35; + + // The parser stores options it doesn't recognize here. See above. + repeated UninterpretedOption uninterpreted_option = 999; + + // Clients can define custom options in extensions of this message. See above. + extensions 1000 to max; +} + +// A message representing a option the parser does not recognize. This only +// appears in options protos created by the compiler::Parser class. +// DescriptorPool resolves these when building Descriptor objects. Therefore, +// options protos in descriptor objects (e.g. returned by Descriptor::options(), +// or produced by Descriptor::CopyTo()) will never have UninterpretedOptions +// in them. +message UninterpretedOption { + // The name of the uninterpreted option. Each string represents a segment in + // a dot-separated name. is_extension is true iff a segment represents an + // extension (denoted with parentheses in options specs in .proto files). + // E.g.,{ ["foo", false], ["bar.baz", true], ["moo", false] } represents + // "foo.(bar.baz).moo". + message NamePart { + required string name_part = 1; + required bool is_extension = 2; + } + repeated NamePart name = 2; + + // The value of the uninterpreted option, in whatever type the tokenizer + // identified it as during parsing. Exactly one of these should be set. + optional string identifier_value = 3; + optional uint64 positive_int_value = 4; + optional int64 negative_int_value = 5; + optional double double_value = 6; + optional bytes string_value = 7; + optional string aggregate_value = 8; +} + +// =================================================================== +// Features + +// TODO Enums in C++ gencode (and potentially other languages) are +// not well scoped. This means that each of the feature enums below can clash +// with each other. The short names we've chosen maximize call-site +// readability, but leave us very open to this scenario. A future feature will +// be designed and implemented to handle this, hopefully before we ever hit a +// conflict here. +message FeatureSet { + enum FieldPresence { + FIELD_PRESENCE_UNKNOWN = 0; + EXPLICIT = 1; + IMPLICIT = 2; + LEGACY_REQUIRED = 3; + } + optional FieldPresence field_presence = 1 [ + retention = RETENTION_RUNTIME, + targets = TARGET_TYPE_FIELD, + targets = TARGET_TYPE_FILE, + feature_support = { + edition_introduced: EDITION_2023, + }, + edition_defaults = { edition: EDITION_LEGACY, value: "EXPLICIT" }, + edition_defaults = { edition: EDITION_PROTO3, value: "IMPLICIT" }, + edition_defaults = { edition: EDITION_2023, value: "EXPLICIT" } + ]; + + enum EnumType { + ENUM_TYPE_UNKNOWN = 0; + OPEN = 1; + CLOSED = 2; + } + optional EnumType enum_type = 2 [ + retention = RETENTION_RUNTIME, + targets = TARGET_TYPE_ENUM, + targets = TARGET_TYPE_FILE, + feature_support = { + edition_introduced: EDITION_2023, + }, + edition_defaults = { edition: EDITION_LEGACY, value: "CLOSED" }, + edition_defaults = { edition: EDITION_PROTO3, value: "OPEN" } + ]; + + enum RepeatedFieldEncoding { + REPEATED_FIELD_ENCODING_UNKNOWN = 0; + PACKED = 1; + EXPANDED = 2; + } + optional RepeatedFieldEncoding repeated_field_encoding = 3 [ + retention = RETENTION_RUNTIME, + targets = TARGET_TYPE_FIELD, + targets = TARGET_TYPE_FILE, + feature_support = { + edition_introduced: EDITION_2023, + }, + edition_defaults = { edition: EDITION_LEGACY, value: "EXPANDED" }, + edition_defaults = { edition: EDITION_PROTO3, value: "PACKED" } + ]; + + enum Utf8Validation { + UTF8_VALIDATION_UNKNOWN = 0; + VERIFY = 2; + NONE = 3; + reserved 1; + } + optional Utf8Validation utf8_validation = 4 [ + retention = RETENTION_RUNTIME, + targets = TARGET_TYPE_FIELD, + targets = TARGET_TYPE_FILE, + feature_support = { + edition_introduced: EDITION_2023, + }, + edition_defaults = { edition: EDITION_LEGACY, value: "NONE" }, + edition_defaults = { edition: EDITION_PROTO3, value: "VERIFY" } + ]; + + enum MessageEncoding { + MESSAGE_ENCODING_UNKNOWN = 0; + LENGTH_PREFIXED = 1; + DELIMITED = 2; + } + optional MessageEncoding message_encoding = 5 [ + retention = RETENTION_RUNTIME, + targets = TARGET_TYPE_FIELD, + targets = TARGET_TYPE_FILE, + feature_support = { + edition_introduced: EDITION_2023, + }, + edition_defaults = { edition: EDITION_LEGACY, value: "LENGTH_PREFIXED" } + ]; + + enum JsonFormat { + JSON_FORMAT_UNKNOWN = 0; + ALLOW = 1; + LEGACY_BEST_EFFORT = 2; + } + optional JsonFormat json_format = 6 [ + retention = RETENTION_RUNTIME, + targets = TARGET_TYPE_MESSAGE, + targets = TARGET_TYPE_ENUM, + targets = TARGET_TYPE_FILE, + feature_support = { + edition_introduced: EDITION_2023, + }, + edition_defaults = { edition: EDITION_LEGACY, value: "LEGACY_BEST_EFFORT" }, + edition_defaults = { edition: EDITION_PROTO3, value: "ALLOW" } + ]; + + reserved 999; + + extensions 1000 to 9994 [ + declaration = { + number: 1000, + full_name: ".pb.cpp", + type: ".pb.CppFeatures" + }, + declaration = { + number: 1001, + full_name: ".pb.java", + type: ".pb.JavaFeatures" + }, + declaration = { number: 1002, full_name: ".pb.go", type: ".pb.GoFeatures" }, + declaration = { + number: 9990, + full_name: ".pb.proto1", + type: ".pb.Proto1Features" + } + ]; + + extensions 9995 to 9999; // For internal testing + extensions 10000; // for https://github.com/bufbuild/protobuf-es +} + +// A compiled specification for the defaults of a set of features. These +// messages are generated from FeatureSet extensions and can be used to seed +// feature resolution. The resolution with this object becomes a simple search +// for the closest matching edition, followed by proto merges. +message FeatureSetDefaults { + // A map from every known edition with a unique set of defaults to its + // defaults. Not all editions may be contained here. For a given edition, + // the defaults at the closest matching edition ordered at or before it should + // be used. This field must be in strict ascending order by edition. + message FeatureSetEditionDefault { + optional Edition edition = 3; + + // Defaults of features that can be overridden in this edition. + optional FeatureSet overridable_features = 4; + + // Defaults of features that can't be overridden in this edition. + optional FeatureSet fixed_features = 5; + + reserved 1, 2; + reserved "features"; + } + repeated FeatureSetEditionDefault defaults = 1; + + // The minimum supported edition (inclusive) when this was constructed. + // Editions before this will not have defaults. + optional Edition minimum_edition = 4; + + // The maximum known edition (inclusive) when this was constructed. Editions + // after this will not have reliable defaults. + optional Edition maximum_edition = 5; +} + +// =================================================================== +// Optional source code info + +// Encapsulates information about the original source file from which a +// FileDescriptorProto was generated. +message SourceCodeInfo { + // A Location identifies a piece of source code in a .proto file which + // corresponds to a particular definition. This information is intended + // to be useful to IDEs, code indexers, documentation generators, and similar + // tools. + // + // For example, say we have a file like: + // message Foo { + // optional string foo = 1; + // } + // Let's look at just the field definition: + // optional string foo = 1; + // ^ ^^ ^^ ^ ^^^ + // a bc de f ghi + // We have the following locations: + // span path represents + // [a,i) [ 4, 0, 2, 0 ] The whole field definition. + // [a,b) [ 4, 0, 2, 0, 4 ] The label (optional). + // [c,d) [ 4, 0, 2, 0, 5 ] The type (string). + // [e,f) [ 4, 0, 2, 0, 1 ] The name (foo). + // [g,h) [ 4, 0, 2, 0, 3 ] The number (1). + // + // Notes: + // - A location may refer to a repeated field itself (i.e. not to any + // particular index within it). This is used whenever a set of elements are + // logically enclosed in a single code segment. For example, an entire + // extend block (possibly containing multiple extension definitions) will + // have an outer location whose path refers to the "extensions" repeated + // field without an index. + // - Multiple locations may have the same path. This happens when a single + // logical declaration is spread out across multiple places. The most + // obvious example is the "extend" block again -- there may be multiple + // extend blocks in the same scope, each of which will have the same path. + // - A location's span is not always a subset of its parent's span. For + // example, the "extendee" of an extension declaration appears at the + // beginning of the "extend" block and is shared by all extensions within + // the block. + // - Just because a location's span is a subset of some other location's span + // does not mean that it is a descendant. For example, a "group" defines + // both a type and a field in a single declaration. Thus, the locations + // corresponding to the type and field and their components will overlap. + // - Code which tries to interpret locations should probably be designed to + // ignore those that it doesn't understand, as more types of locations could + // be recorded in the future. + repeated Location location = 1; + message Location { + // Identifies which part of the FileDescriptorProto was defined at this + // location. + // + // Each element is a field number or an index. They form a path from + // the root FileDescriptorProto to the place where the definition appears. + // For example, this path: + // [ 4, 3, 2, 7, 1 ] + // refers to: + // file.message_type(3) // 4, 3 + // .field(7) // 2, 7 + // .name() // 1 + // This is because FileDescriptorProto.message_type has field number 4: + // repeated DescriptorProto message_type = 4; + // and DescriptorProto.field has field number 2: + // repeated FieldDescriptorProto field = 2; + // and FieldDescriptorProto.name has field number 1: + // optional string name = 1; + // + // Thus, the above path gives the location of a field name. If we removed + // the last element: + // [ 4, 3, 2, 7 ] + // this path refers to the whole field declaration (from the beginning + // of the label to the terminating semicolon). + repeated int32 path = 1 [packed = true]; + + // Always has exactly three or four elements: start line, start column, + // end line (optional, otherwise assumed same as start line), end column. + // These are packed into a single field for efficiency. Note that line + // and column numbers are zero-based -- typically you will want to add + // 1 to each before displaying to a user. + repeated int32 span = 2 [packed = true]; + + // If this SourceCodeInfo represents a complete declaration, these are any + // comments appearing before and after the declaration which appear to be + // attached to the declaration. + // + // A series of line comments appearing on consecutive lines, with no other + // tokens appearing on those lines, will be treated as a single comment. + // + // leading_detached_comments will keep paragraphs of comments that appear + // before (but not connected to) the current element. Each paragraph, + // separated by empty lines, will be one comment element in the repeated + // field. + // + // Only the comment content is provided; comment markers (e.g. //) are + // stripped out. For block comments, leading whitespace and an asterisk + // will be stripped from the beginning of each line other than the first. + // Newlines are included in the output. + // + // Examples: + // + // optional int32 foo = 1; // Comment attached to foo. + // // Comment attached to bar. + // optional int32 bar = 2; + // + // optional string baz = 3; + // // Comment attached to baz. + // // Another line attached to baz. + // + // // Comment attached to moo. + // // + // // Another line attached to moo. + // optional double moo = 4; + // + // // Detached comment for corge. This is not leading or trailing comments + // // to moo or corge because there are blank lines separating it from + // // both. + // + // // Detached comment for corge paragraph 2. + // + // optional string corge = 5; + // /* Block comment attached + // * to corge. Leading asterisks + // * will be removed. */ + // /* Block comment attached to + // * grault. */ + // optional int32 grault = 6; + // + // // ignored detached comments. + optional string leading_comments = 3; + optional string trailing_comments = 4; + repeated string leading_detached_comments = 6; + } +} + +// Describes the relationship between generated code and its original source +// file. A GeneratedCodeInfo message is associated with only one generated +// source file, but may contain references to different source .proto files. +message GeneratedCodeInfo { + // An Annotation connects some span of text in generated code to an element + // of its generating .proto file. + repeated Annotation annotation = 1; + message Annotation { + // Identifies the element in the original source .proto file. This field + // is formatted the same as SourceCodeInfo.Location.path. + repeated int32 path = 1 [packed = true]; + + // Identifies the filesystem path to the original source .proto. + optional string source_file = 2; + + // Identifies the starting offset in bytes in the generated code + // that relates to the identified object. + optional int32 begin = 3; + + // Identifies the ending offset in bytes in the generated code that + // relates to the identified object. The end offset should be one past + // the last relevant byte (so the length of the text = end - begin). + optional int32 end = 4; + + // Represents the identified object's effect on the element in the original + // .proto file. + enum Semantic { + // There is no effect or the effect is indescribable. + NONE = 0; + // The element is set or otherwise mutated. + SET = 1; + // An alias to the element is returned. + ALIAS = 2; + } + optional Semantic semantic = 5; + } +} diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/proto/nanopb.proto b/wpiutil/src/main/native/thirdparty/nanopb/generator/proto/nanopb.proto new file mode 100644 index 0000000000..1a1cc98f36 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/generator/proto/nanopb.proto @@ -0,0 +1,213 @@ +// This file contains definitions of custom options used to control the +// code generator in nanopb protocol buffers library. +// +// Most commonly used options are max_count and max_size, which allow +// the generator to allocate static arrays for repeated and string fields. +// +// There are three ways to use these options: +// 1. Use a separate .options file +// 2. Use command line switches to nanopb_generator.py +// 3. Use [(nanopb).option = value] in your .proto file +// +// For detailed documentation, refer to "Generator options" in docs/reference.md + +syntax = "proto2"; +import "google/protobuf/descriptor.proto"; + +option java_package = "fi.kapsi.koti.jpa.nanopb"; + +enum FieldType { + FT_DEFAULT = 0; // Automatically decide field type, generate static field if possible. + FT_CALLBACK = 1; // Always generate a callback field. + FT_POINTER = 4; // Always generate a dynamically allocated field. + FT_STATIC = 2; // Generate a static field or raise an exception if not possible. + FT_IGNORE = 3; // Ignore the field completely. + FT_INLINE = 5; // Legacy option, use the separate 'fixed_length' option instead +} + +enum IntSize { + IS_DEFAULT = 0; // Default, 32/64bit based on type in .proto + IS_8 = 8; + IS_16 = 16; + IS_32 = 32; + IS_64 = 64; +} + +enum TypenameMangling { + M_NONE = 0; // Default, no typename mangling + M_STRIP_PACKAGE = 1; // Strip current package name + M_FLATTEN = 2; // Only use last path component + M_PACKAGE_INITIALS = 3; // Replace the package name by the initials +} + +enum DescriptorSize { + DS_AUTO = 0; // Select minimal size based on field type + DS_1 = 1; // 1 word; up to 15 byte fields, no arrays + DS_2 = 2; // 2 words; up to 4095 byte fields, 4095 entry arrays + DS_4 = 4; // 4 words; up to 2^32-1 byte fields, 2^16-1 entry arrays + DS_8 = 8; // 8 words; up to 2^32-1 entry arrays +} + +// This is the inner options message, which basically defines options for +// a field. When it is used in message or file scope, it applies to all +// fields. +message NanoPBOptions { + // Allocated size for 'bytes' and 'string' fields. + // For string fields, this should include the space for null terminator. + optional int32 max_size = 1; + + // Maximum length for 'string' fields. Setting this is equivalent + // to setting max_size to a value of length+1. + optional int32 max_length = 14; + + // Allocated number of entries in arrays ('repeated' fields) + optional int32 max_count = 2; + + // Size of integer fields. Can save some memory if you don't need + // full 32 bits for the value. + optional IntSize int_size = 7 [default = IS_DEFAULT]; + + // Size for enum fields. Supported by C++11 and C23 standards. + optional IntSize enum_intsize = 34 [default = IS_DEFAULT]; + + // Force type of field (callback or static allocation) + optional FieldType type = 3 [default = FT_DEFAULT]; + + // Use long names for enums, i.e. EnumName_EnumValue. + optional bool long_names = 4 [default = true]; + + // Add 'packed' attribute to generated structs. + // Note: this cannot be used on CPUs that break on unaligned + // accesses to variables. + optional bool packed_struct = 5 [default = false]; + + // Add 'packed' attribute to generated enums. + optional bool packed_enum = 10 [default = false]; + + // Skip this message + optional bool skip_message = 6 [default = false]; + + // Generate oneof fields as normal optional fields instead of union. + optional bool no_unions = 8 [default = false]; + + // integer type tag for a message + optional uint32 msgid = 9; + + // decode oneof as anonymous union + optional bool anonymous_oneof = 11 [default = false]; + + // Proto3 singular field does not generate a "has_" flag + optional bool proto3 = 12 [default = false]; + + // Force proto3 messages to have no "has_" flag. + // This was default behavior until nanopb-0.4.0. + optional bool proto3_singular_msgs = 21 [default = false]; + + // Generate an enum->string mapping function (can take up lots of space). + optional bool enum_to_string = 13 [default = false]; + + // Generate validation methods for enums + optional bool enum_validate = 32 [default = false]; + + // Generate bytes arrays with fixed length + optional bool fixed_length = 15 [default = false]; + + // Generate repeated field with fixed count + optional bool fixed_count = 16 [default = false]; + + // Generate message-level callback that is called before decoding submessages. + // This can be used to set callback fields for submsgs inside oneofs. + optional bool submsg_callback = 22 [default = false]; + + // Shorten or remove package names from type names. + // This option applies only on the file level. + optional TypenameMangling mangle_names = 17 [default = M_NONE]; + + // Data type for storage associated with callback fields. + optional string callback_datatype = 18 [default = "pb_callback_t"]; + + // Callback function used for encoding and decoding. + // Prior to nanopb-0.4.0, the callback was specified in per-field pb_callback_t + // structure. This is still supported, but does not work inside e.g. oneof or pointer + // fields. Instead, a new method allows specifying a per-message callback that + // will be called for all callback fields in a message type. + optional string callback_function = 19 [default = "pb_default_field_callback"]; + + // Select the size of field descriptors. This option has to be defined + // for the whole message, not per-field. Usually automatic selection is + // ok, but if it results in compilation errors you can increase the field + // size here. + optional DescriptorSize descriptorsize = 20 [default = DS_AUTO]; + + // Set default value for has_ fields. + optional bool default_has = 23 [default = false]; + + // Extra files to include in generated `.pb.h` + repeated string include = 24; + + // Automatic includes to exclude from generated `.pb.h` + // Same as nanopb_generator.py command line flag -x. + repeated string exclude = 26; + + // Package name that applies only for nanopb. + optional string package = 25; + + // Override type of the field in generated C code. Only to be used with related field types + optional google.protobuf.FieldDescriptorProto.Type type_override = 27; + + // Override of the label of the field (see FieldDescriptorProto.Label). Can be used to create + // fields which nanopb considers required in proto3, or whether nanopb treats the field as + // optional/required/repeated. + optional google.protobuf.FieldDescriptorProto.Label label_override = 31; + + // Due to historical reasons, nanopb orders fields in structs by their tag number + // instead of the order in .proto. Set this to false to keep the .proto order. + // The default value will probably change to false in nanopb-0.5.0. + optional bool sort_by_tag = 28 [default = true]; + + // Set the FT_DEFAULT field conversion strategy. + // A field that can become a static member of a c struct (e.g. int, bool, etc) + // will be a a static field. + // Fields with dynamic length are converted to either a pointer or a callback. + optional FieldType fallback_type = 29 [default = FT_CALLBACK]; + + // Override initializer used in generated MyMessage_init_zero and MyMessage_init_default macros + // By default decided automatically based on field default value and datatype. + optional string initializer = 30; + + // Discard unused types that are automatically generated by protoc if they are not actually + // needed. Currently this applies to map< > types when the field is ignored by options. + optional bool discard_unused_automatic_types = 33 [default = true]; + + // Discard messages and fields marked with [deprecated = true] in the proto file. + optional bool discard_deprecated = 35 [default = false]; +} + +// Extensions to protoc 'Descriptor' type in order to define options +// inside a .proto file. +// +// Protocol Buffers extension number registry +// -------------------------------- +// Project: Nanopb +// Contact: Petteri Aimonen +// Web site: http://kapsi.fi/~jpa/nanopb +// Extensions: 1010 (all types) +// -------------------------------- + +extend google.protobuf.FileOptions { + optional NanoPBOptions nanopb_fileopt = 1010; +} + +extend google.protobuf.MessageOptions { + optional NanoPBOptions nanopb_msgopt = 1010; +} + +extend google.protobuf.EnumOptions { + optional NanoPBOptions nanopb_enumopt = 1010; +} + +extend google.protobuf.FieldOptions { + optional NanoPBOptions nanopb = 1010; +} + + diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/protoc b/wpiutil/src/main/native/thirdparty/nanopb/generator/protoc new file mode 100644 index 0000000000..c259702fd0 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/generator/protoc @@ -0,0 +1,45 @@ +#!/usr/bin/env python3 +# This file acts as a drop-in replacement of binary protoc.exe. +# It will use either Python-based protoc from grpcio-tools package, +# or if it is not available, protoc.exe from path if found. + +import sys +import os +import os.path + +# Depending on how this script is run, we may or may not have PEP366 package name +# available for relative imports. +if not __package__: + from proto._utils import invoke_protoc +else: + from .proto._utils import invoke_protoc + +if __name__ == '__main__': + # Get path of the directory where this script is stored. + if getattr(sys, 'frozen', False): + mypath = os.path.dirname(sys.executable) # For pyInstaller + else: + mypath = os.path.dirname(__file__) + + # Avoid recursive calls to self + env_paths = os.environ["PATH"].split(os.pathsep) + if mypath in env_paths: + env_paths.remove(mypath) + os.environ["PATH"] = os.pathsep.join(env_paths) + + # Add argument for finding the nanopb generator when using --nanopb_out= + # argument to protoc. + if os.path.isfile(os.path.join(mypath, "protoc-gen-nanopb.exe")): + protoc_gen_nanopb = os.path.join(mypath, "protoc-gen-nanopb.exe") + elif os.name == 'nt': + protoc_gen_nanopb = os.path.join(mypath, "protoc-gen-nanopb.bat") + else: + protoc_gen_nanopb = os.path.join(mypath, "protoc-gen-nanopb") + + args = sys.argv[1:] + + if os.path.isfile(protoc_gen_nanopb): + args = ['--plugin=protoc-gen-nanopb=%s' % protoc_gen_nanopb] + args + + status = invoke_protoc(['protoc'] + args) + sys.exit(status) diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/protoc-gen-nanopb b/wpiutil/src/main/native/thirdparty/nanopb/generator/protoc-gen-nanopb new file mode 100644 index 0000000000..20a36c79ae --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/generator/protoc-gen-nanopb @@ -0,0 +1,11 @@ +#!/usr/bin/env python3 +# This file is used to invoke nanopb_generator.py as a plugin +# to protoc on Linux and other *nix-style systems. +# Use it like this: +# protoc --plugin=protoc-gen-nanopb=..../protoc-gen-nanopb --nanopb_out=dir foo.proto + +from nanopb_generator import * + +if __name__ == '__main__': + # Assume we are running as a plugin under protoc. + main_plugin() diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/protoc-gen-nanopb-py2 b/wpiutil/src/main/native/thirdparty/nanopb/generator/protoc-gen-nanopb-py2 new file mode 100644 index 0000000000..e6427094c1 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/generator/protoc-gen-nanopb-py2 @@ -0,0 +1,16 @@ +#!/bin/sh + +# This file is used to invoke nanopb_generator.py2 as a plugin +# to protoc on Linux and other *nix-style systems. +# +# The difference from protoc-gen-nanopb is that this executes with Python 2. +# +# Use it like this: +# protoc --plugin=protoc-gen-nanopb=..../protoc-gen-nanopb-py2 --nanopb_out=dir foo.proto +# +# Note that if you use the binary package of nanopb, the protoc +# path is already set up properly and there is no need to give +# --plugin= on the command line. + +MYPATH=$(dirname "$0") +exec "$MYPATH/nanopb_generator.py2" --protoc-plugin diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/protoc-gen-nanopb.bat b/wpiutil/src/main/native/thirdparty/nanopb/generator/protoc-gen-nanopb.bat new file mode 100644 index 0000000000..fa5bdd2be5 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/generator/protoc-gen-nanopb.bat @@ -0,0 +1,12 @@ +@echo off +:: This file is used to invoke nanopb_generator.py as a plugin +:: to protoc on Windows. +:: Use it like this: +:: protoc --plugin=protoc-gen-nanopb=..../protoc-gen-nanopb.bat --nanopb_out=dir foo.proto +:: +:: Note that if you use the binary package of nanopb, the protoc +:: path is already set up properly and there is no need to give +:: --plugin= on the command line. + +set mydir=%~dp0 +python "%mydir%\nanopb_generator.py" --protoc-plugin %* diff --git a/wpiutil/src/main/native/thirdparty/nanopb/generator/protoc.bat b/wpiutil/src/main/native/thirdparty/nanopb/generator/protoc.bat new file mode 100644 index 0000000000..2538c94a6d --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/generator/protoc.bat @@ -0,0 +1,9 @@ +@echo off +:: This file acts as a drop-in replacement of binary protoc.exe. +:: It will use either Python-based protoc from grpcio-tools package, +:: or if it is not available, protoc.exe from path if found. + +setLocal enableDelayedExpansion +set mydir=%~dp0 +python "%mydir%\protoc" %* +exit /b %ERRORLEVEL% diff --git a/wpiutil/src/main/native/thirdparty/nanopb/include/pb.h b/wpiutil/src/main/native/thirdparty/nanopb/include/pb.h new file mode 100644 index 0000000000..832364a609 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/include/pb.h @@ -0,0 +1,931 @@ +/* Common parts of the nanopb library. Most of these are quite low-level + * stuff. For the high-level interface, see pb_encode.h and pb_decode.h. + * + * Modified for WPILib Use + */ + +#ifndef PB_H_INCLUDED +#define PB_H_INCLUDED + +/***************************************************************** + * Nanopb compilation time options. You can change these here by * + * uncommenting the lines, or on the compiler command line. * + *****************************************************************/ + +/* Enable support for dynamically allocated fields */ +/* #define PB_ENABLE_MALLOC 1 */ + +/* Define this if your CPU / compiler combination does not support + * unaligned memory access to packed structures. Note that packed + * structures are only used when requested in .proto options. */ +/* #define PB_NO_PACKED_STRUCTS 1 */ + +/* Increase the number of required fields that are tracked. + * A compiler warning will tell if you need this. */ +/* #define PB_MAX_REQUIRED_FIELDS 256 */ + +/* Add support for tag numbers > 65536 and fields larger than 65536 bytes. */ +/* #define PB_FIELD_32BIT 1 */ + +/* Disable support for error messages in order to save some code space. */ +/* #define PB_NO_ERRMSG 1 */ + +/* Disable support for custom streams (support only memory buffers). */ +/* #define PB_BUFFER_ONLY 1 */ + +/* Disable support for 64-bit datatypes, for compilers without int64_t + or to save some code space. */ +/* #define PB_WITHOUT_64BIT 1 */ + +/* Don't encode scalar arrays as packed. This is only to be used when + * the decoder on the receiving side cannot process packed scalar arrays. + * Such example is older protobuf.js. */ +/* #define PB_ENCODE_ARRAYS_UNPACKED 1 */ + +/* Enable conversion of doubles to floats for platforms that do not + * support 64-bit doubles. Most commonly AVR. */ +/* #define PB_CONVERT_DOUBLE_FLOAT 1 */ + +/* Check whether incoming strings are valid UTF-8 sequences. Slows down + * the string processing slightly and slightly increases code size. */ +/* #define PB_VALIDATE_UTF8 1 */ + +/* This can be defined if the platform is little-endian and has 8-bit bytes. + * Normally it is automatically detected based on __BYTE_ORDER__ macro. */ +/* #define PB_LITTLE_ENDIAN_8BIT 1 */ + +/* Configure static assert mechanism. Instead of changing these, set your + * compiler to C11 standard mode if possible. */ +/* #define PB_C99_STATIC_ASSERT 1 */ +/* #define PB_NO_STATIC_ASSERT 1 */ + +/****************************************************************** + * You usually don't need to change anything below this line. * + * Feel free to look around and use the defined macros, though. * + ******************************************************************/ + + +/* Version of the nanopb library. Just in case you want to check it in + * your own program. */ +#define NANOPB_VERSION "nanopb-0.4.9" + +/* Include all the system headers needed by nanopb. You will need the + * definitions of the following: + * - strlen, memcpy, memset functions + * - [u]int_least8_t, uint_fast8_t, [u]int_least16_t, [u]int32_t, [u]int64_t + * - size_t + * - bool + * + * If you don't have the standard header files, you can instead provide + * a custom header that defines or includes all this. In that case, + * define PB_SYSTEM_HEADER to the path of this file. + */ +#ifdef PB_SYSTEM_HEADER +#include PB_SYSTEM_HEADER +#else +#include +#include +#include +#include +#include + +#include +#include + +#ifdef PB_ENABLE_MALLOC +#include +#endif +#endif + +/* Macro for defining packed structures (compiler dependent). + * This just reduces memory requirements, but is not required. + */ +#if defined(PB_NO_PACKED_STRUCTS) + /* Disable struct packing */ +# define PB_PACKED_STRUCT_START +# define PB_PACKED_STRUCT_END +# define pb_packed +#elif defined(__GNUC__) || defined(__clang__) + /* For GCC and clang */ +# define PB_PACKED_STRUCT_START +# define PB_PACKED_STRUCT_END +# define pb_packed __attribute__((packed)) +#elif defined(__ICCARM__) || defined(__CC_ARM) + /* For IAR ARM and Keil MDK-ARM compilers */ +# define PB_PACKED_STRUCT_START _Pragma("pack(push, 1)") +# define PB_PACKED_STRUCT_END _Pragma("pack(pop)") +# define pb_packed +#elif defined(_MSC_VER) && (_MSC_VER >= 1500) + /* For Microsoft Visual C++ */ +# define PB_PACKED_STRUCT_START __pragma(pack(push, 1)) +# define PB_PACKED_STRUCT_END __pragma(pack(pop)) +# define pb_packed +#else + /* Unknown compiler */ +# define PB_PACKED_STRUCT_START +# define PB_PACKED_STRUCT_END +# define pb_packed +#endif + +/* Detect endianness */ +#ifndef PB_LITTLE_ENDIAN_8BIT +#if ((defined(__BYTE_ORDER) && __BYTE_ORDER == __LITTLE_ENDIAN) || \ + (defined(__BYTE_ORDER__) && __BYTE_ORDER__ == __ORDER_LITTLE_ENDIAN__) || \ + defined(__LITTLE_ENDIAN__) || defined(__ARMEL__) || \ + defined(__THUMBEL__) || defined(__AARCH64EL__) || defined(_MIPSEL) || \ + defined(_M_IX86) || defined(_M_X64) || defined(_M_ARM)) \ + && CHAR_BIT == 8 +#define PB_LITTLE_ENDIAN_8BIT 1 +#endif +#endif + +/* Handly macro for suppressing unreferenced-parameter compiler warnings. */ +#ifndef PB_UNUSED +#define PB_UNUSED(x) (void)(x) +#endif + +/* Harvard-architecture processors may need special attributes for storing + * field information in program memory. */ +#ifndef PB_PROGMEM +#ifdef __AVR__ +#include +#define PB_PROGMEM PROGMEM +#define PB_PROGMEM_READU32(x) pgm_read_dword(&x) +#else +#define PB_PROGMEM +#define PB_PROGMEM_READU32(x) (x) +#endif +#endif + +/* Compile-time assertion, used for checking compatible compilation options. + * If this does not work properly on your compiler, use + * #define PB_NO_STATIC_ASSERT to disable it. + * + * But before doing that, check carefully the error message / place where it + * comes from to see if the error has a real cause. Unfortunately the error + * message is not always very clear to read, but you can see the reason better + * in the place where the PB_STATIC_ASSERT macro was called. + */ +#ifndef PB_NO_STATIC_ASSERT +# ifndef PB_STATIC_ASSERT +# if defined(__ICCARM__) + /* IAR has static_assert keyword but no _Static_assert */ +# define PB_STATIC_ASSERT(COND,MSG) static_assert(COND,#MSG); +# elif defined(_MSC_VER) && (!defined(__STDC_VERSION__) || __STDC_VERSION__ < 201112) + /* MSVC in C89 mode supports static_assert() keyword anyway */ +# define PB_STATIC_ASSERT(COND,MSG) static_assert(COND,#MSG); +# elif defined(PB_C99_STATIC_ASSERT) + /* Classic negative-size-array static assert mechanism */ +# define PB_STATIC_ASSERT(COND,MSG) typedef char PB_STATIC_ASSERT_MSG(MSG, __LINE__, __COUNTER__)[(COND)?1:-1]; +# define PB_STATIC_ASSERT_MSG(MSG, LINE, COUNTER) PB_STATIC_ASSERT_MSG_(MSG, LINE, COUNTER) +# define PB_STATIC_ASSERT_MSG_(MSG, LINE, COUNTER) pb_static_assertion_##MSG##_##LINE##_##COUNTER +# elif defined(__cplusplus) + /* C++11 standard static_assert mechanism */ +# define PB_STATIC_ASSERT(COND,MSG) static_assert(COND,#MSG); +# else + /* C11 standard _Static_assert mechanism */ +# define PB_STATIC_ASSERT(COND,MSG) _Static_assert(COND,#MSG); +# endif +# endif +#else + /* Static asserts disabled by PB_NO_STATIC_ASSERT */ +# define PB_STATIC_ASSERT(COND,MSG) +#endif + +/* Test that PB_STATIC_ASSERT works + * If you get errors here, you may need to do one of these: + * - Enable C11 standard support in your compiler + * - Define PB_C99_STATIC_ASSERT to enable C99 standard support + * - Define PB_NO_STATIC_ASSERT to disable static asserts altogether + */ +PB_STATIC_ASSERT(1, STATIC_ASSERT_IS_NOT_WORKING) + +/* Number of required fields to keep track of. */ +#ifndef PB_MAX_REQUIRED_FIELDS +#define PB_MAX_REQUIRED_FIELDS 64 +#endif + +#if PB_MAX_REQUIRED_FIELDS < 64 +#error You should not lower PB_MAX_REQUIRED_FIELDS from the default value (64). +#endif + +#ifdef PB_WITHOUT_64BIT +#ifdef PB_CONVERT_DOUBLE_FLOAT +/* Cannot use doubles without 64-bit types */ +#undef PB_CONVERT_DOUBLE_FLOAT +#endif +#endif + +/* Data type for storing encoded data and other byte streams. + * This typedef exists to support platforms where uint8_t does not exist. + * You can regard it as equivalent on uint8_t on other platforms. + */ +#if defined(PB_BYTE_T_OVERRIDE) +typedef PB_BYTE_T_OVERRIDE pb_byte_t; +#elif defined(UINT8_MAX) +typedef uint8_t pb_byte_t; +#else +typedef uint_least8_t pb_byte_t; +#endif + +/* List of possible field types. These are used in the autogenerated code. + * Least-significant 4 bits tell the scalar type + * Most-significant 4 bits specify repeated/required/packed etc. + */ +typedef pb_byte_t pb_type_t; + +/**** Field data types ****/ + +/* Numeric types */ +#define PB_LTYPE_BOOL 0x00U /* bool */ +#define PB_LTYPE_VARINT 0x01U /* int32, int64, enum, bool */ +#define PB_LTYPE_UVARINT 0x02U /* uint32, uint64 */ +#define PB_LTYPE_SVARINT 0x03U /* sint32, sint64 */ +#define PB_LTYPE_FIXED32 0x04U /* fixed32, sfixed32, float */ +#define PB_LTYPE_FIXED64 0x05U /* fixed64, sfixed64, double */ + +/* Marker for last packable field type. */ +#define PB_LTYPE_LAST_PACKABLE 0x05U + +/* Byte array with pre-allocated buffer. + * data_size is the length of the allocated PB_BYTES_ARRAY structure. */ +#define PB_LTYPE_BYTES 0x06U + +/* String with pre-allocated buffer. + * data_size is the maximum length. */ +#define PB_LTYPE_STRING 0x07U + +/* Submessage + * submsg_fields is pointer to field descriptions */ +#define PB_LTYPE_SUBMESSAGE 0x08U + +/* Submessage with pre-decoding callback + * The pre-decoding callback is stored as pb_callback_t right before pSize. + * submsg_fields is pointer to field descriptions */ +#define PB_LTYPE_SUBMSG_W_CB 0x09U + +/* Extension pseudo-field + * The field contains a pointer to pb_extension_t */ +#define PB_LTYPE_EXTENSION 0x0AU + +/* Byte array with inline, pre-allocated byffer. + * data_size is the length of the inline, allocated buffer. + * This differs from PB_LTYPE_BYTES by defining the element as + * pb_byte_t[data_size] rather than pb_bytes_array_t. */ +#define PB_LTYPE_FIXED_LENGTH_BYTES 0x0BU + +/* Number of declared LTYPES */ +#define PB_LTYPES_COUNT 0x0CU +#define PB_LTYPE_MASK 0x0FU + +/**** Field repetition rules ****/ + +#define PB_HTYPE_REQUIRED 0x00U +#define PB_HTYPE_OPTIONAL 0x10U +#define PB_HTYPE_SINGULAR 0x10U +#define PB_HTYPE_REPEATED 0x20U +#define PB_HTYPE_FIXARRAY 0x20U +#define PB_HTYPE_ONEOF 0x30U +#define PB_HTYPE_MASK 0x30U + +/**** Field allocation types ****/ + +#define PB_ATYPE_STATIC 0x00U +#define PB_ATYPE_POINTER 0x80U +#define PB_ATYPE_CALLBACK 0x40U +#define PB_ATYPE_MASK 0xC0U + +#define PB_ATYPE(x) ((x) & PB_ATYPE_MASK) +#define PB_HTYPE(x) ((x) & PB_HTYPE_MASK) +#define PB_LTYPE(x) ((x) & PB_LTYPE_MASK) +#define PB_LTYPE_IS_SUBMSG(x) (PB_LTYPE(x) == PB_LTYPE_SUBMESSAGE || \ + PB_LTYPE(x) == PB_LTYPE_SUBMSG_W_CB) + +/* Data type used for storing sizes of struct fields + * and array counts. + */ +#if defined(PB_FIELD_32BIT) + typedef uint32_t pb_size_t; + typedef int32_t pb_ssize_t; +#else + typedef uint_least16_t pb_size_t; + typedef int_least16_t pb_ssize_t; +#endif +#define PB_SIZE_MAX ((pb_size_t)-1) + +/* Forward declaration of struct types */ +typedef struct pb_istream_s pb_istream_t; +typedef struct pb_ostream_s pb_ostream_t; +typedef struct pb_field_iter_s pb_field_iter_t; + +typedef struct pb_filedesc_s pb_filedesc_t; +struct pb_filedesc_s { + std::string_view file_name; + std::span file_descriptor; +}; + +/* This structure is used in auto-generated constants + * to specify struct fields. + */ +typedef struct pb_msgdesc_s pb_msgdesc_t; +struct pb_msgdesc_s { + const uint32_t *field_info; + const pb_msgdesc_t * const * submsg_info; + const pb_byte_t *default_value; + + bool (*field_callback)(pb_istream_t *istream, pb_ostream_t *ostream, const pb_field_iter_t *field); + + pb_size_t field_count; + pb_size_t required_field_count; + pb_size_t largest_tag; + + pb_filedesc_t file_descriptor; + std::string_view proto_name; +}; + +/* Iterator for message descriptor */ +struct pb_field_iter_s { + const pb_msgdesc_t *descriptor; /* Pointer to message descriptor constant */ + void *message; /* Pointer to start of the structure */ + + pb_size_t index; /* Index of the field */ + pb_size_t field_info_index; /* Index to descriptor->field_info array */ + pb_size_t required_field_index; /* Index that counts only the required fields */ + pb_size_t submessage_index; /* Index that counts only submessages */ + + pb_size_t tag; /* Tag of current field */ + pb_size_t data_size; /* sizeof() of a single item */ + pb_size_t array_size; /* Number of array entries */ + pb_type_t type; /* Type of current field */ + + void *pField; /* Pointer to current field in struct */ + void *pData; /* Pointer to current data contents. Different than pField for arrays and pointers. */ + void *pSize; /* Pointer to count/has field */ + + const pb_msgdesc_t *submsg_desc; /* For submessage fields, pointer to field descriptor for the submessage. */ +}; + +/* For compatibility with legacy code */ +typedef pb_field_iter_t pb_field_t; + +/* Make sure that the standard integer types are of the expected sizes. + * Otherwise fixed32/fixed64 fields can break. + * + * If you get errors here, it probably means that your stdint.h is not + * correct for your platform. + */ +#ifndef PB_WITHOUT_64BIT +PB_STATIC_ASSERT(sizeof(int64_t) == 2 * sizeof(int32_t), INT64_T_WRONG_SIZE) +PB_STATIC_ASSERT(sizeof(uint64_t) == 2 * sizeof(uint32_t), UINT64_T_WRONG_SIZE) +#endif + +/* This structure is used for 'bytes' arrays. + * It has the number of bytes in the beginning, and after that an array. + * Note that actual structs used will have a different length of bytes array. + */ +#define PB_BYTES_ARRAY_T(n) struct { pb_size_t size; pb_byte_t bytes[n]; } +#define PB_BYTES_ARRAY_T_ALLOCSIZE(n) ((size_t)n + offsetof(pb_bytes_array_t, bytes)) + +struct pb_bytes_array_s { + pb_size_t size; + pb_byte_t bytes[1]; +}; +typedef struct pb_bytes_array_s pb_bytes_array_t; + +/* This structure is used for giving the callback function. + * It is stored in the message structure and filled in by the method that + * calls pb_decode. + * + * The decoding callback will be given a limited-length stream + * If the wire type was string, the length is the length of the string. + * If the wire type was a varint/fixed32/fixed64, the length is the length + * of the actual value. + * The function may be called multiple times (especially for repeated types, + * but also otherwise if the message happens to contain the field multiple + * times.) + * + * The encoding callback will receive the actual output stream. + * It should write all the data in one call, including the field tag and + * wire type. It can write multiple fields. + * + * The callback can be null if you want to skip a field. + */ +typedef struct pb_callback_s pb_callback_t; +struct pb_callback_s { + /* Callback functions receive a pointer to the arg field. + * You can access the value of the field as *arg, and modify it if needed. + */ + union { + bool (*decode)(pb_istream_t *stream, const pb_field_t *field, void **arg); + bool (*encode)(pb_ostream_t *stream, const pb_field_t *field, void * const *arg); + } funcs; + + /* Free arg for use by callback */ + void *arg; +}; + +extern bool pb_default_field_callback(pb_istream_t *istream, pb_ostream_t *ostream, const pb_field_t *field); + +/* Wire types. Library user needs these only in encoder callbacks. */ +typedef enum { + PB_WT_VARINT = 0, + PB_WT_64BIT = 1, + PB_WT_STRING = 2, + PB_WT_32BIT = 5, + PB_WT_PACKED = 255 /* PB_WT_PACKED is internal marker for packed arrays. */ +} pb_wire_type_t; + +/* Structure for defining the handling of unknown/extension fields. + * Usually the pb_extension_type_t structure is automatically generated, + * while the pb_extension_t structure is created by the user. However, + * if you want to catch all unknown fields, you can also create a custom + * pb_extension_type_t with your own callback. + */ +typedef struct pb_extension_type_s pb_extension_type_t; +typedef struct pb_extension_s pb_extension_t; +struct pb_extension_type_s { + /* Called for each unknown field in the message. + * If you handle the field, read off all of its data and return true. + * If you do not handle the field, do not read anything and return true. + * If you run into an error, return false. + * Set to NULL for default handler. + */ + bool (*decode)(pb_istream_t *stream, pb_extension_t *extension, + uint32_t tag, pb_wire_type_t wire_type); + + /* Called once after all regular fields have been encoded. + * If you have something to write, do so and return true. + * If you do not have anything to write, just return true. + * If you run into an error, return false. + * Set to NULL for default handler. + */ + bool (*encode)(pb_ostream_t *stream, const pb_extension_t *extension); + + /* Free field for use by the callback. */ + const void *arg; +}; + +struct pb_extension_s { + /* Type describing the extension field. Usually you'll initialize + * this to a pointer to the automatically generated structure. */ + const pb_extension_type_t *type; + + /* Destination for the decoded data. This must match the datatype + * of the extension field. */ + void *dest; + + /* Pointer to the next extension handler, or NULL. + * If this extension does not match a field, the next handler is + * automatically called. */ + pb_extension_t *next; + + /* The decoder sets this to true if the extension was found. + * Ignored for encoding. */ + bool found; +}; + +#define pb_extension_init_zero {NULL,NULL,NULL,false} + +/* Memory allocation functions to use. You can define pb_realloc and + * pb_free to custom functions if you want. */ +#ifdef PB_ENABLE_MALLOC +# ifndef pb_realloc +# define pb_realloc(ptr, size) realloc(ptr, size) +# endif +# ifndef pb_free +# define pb_free(ptr) free(ptr) +# endif +#endif + +/* This is used to inform about need to regenerate .pb.h/.pb.c files. */ +#define PB_PROTO_HEADER_VERSION 40 + +/* These macros are used to declare pb_field_t's in the constant array. */ +/* Size of a structure member, in bytes. */ +#define pb_membersize(st, m) (sizeof ((st*)0)->m) +/* Number of entries in an array. */ +#define pb_arraysize(st, m) (pb_membersize(st, m) / pb_membersize(st, m[0])) +/* Delta from start of one member to the start of another member. */ +#define pb_delta(st, m1, m2) ((int)offsetof(st, m1) - (int)offsetof(st, m2)) + +/* Force expansion of macro value */ +#define PB_EXPAND(x) x + +/* Binding of a message field set into a specific structure */ +#define PB_BIND(msgname, structname, width) \ + static const uint32_t structname ## _field_info[] PB_PROGMEM = \ + { \ + msgname ## _FIELDLIST(PB_GEN_FIELD_INFO_ ## width, structname) \ + 0 \ + }; \ + static const pb_msgdesc_t* const structname ## _submsg_info[] = \ + { \ + msgname ## _FIELDLIST(PB_GEN_SUBMSG_INFO, structname) \ + NULL \ + }; \ + static const pb_msgdesc_t structname ## _msg = \ + { \ + structname ## _field_info, \ + structname ## _submsg_info, \ + msgname ## _DEFAULT, \ + msgname ## _CALLBACK, \ + 0 msgname ## _FIELDLIST(PB_GEN_FIELD_COUNT, structname), \ + 0 msgname ## _FIELDLIST(PB_GEN_REQ_FIELD_COUNT, structname), \ + 0 msgname ## _FIELDLIST(PB_GEN_LARGEST_TAG, structname), \ + structname::file_descriptor(), \ + structname::msg_name(), \ + }; \ + const pb_msgdesc_t* structname::msg_descriptor(void) noexcept { return &(structname ## _msg); } \ + msgname ## _FIELDLIST(PB_GEN_FIELD_INFO_ASSERT_ ## width, structname) + +#define PB_GEN_FIELD_COUNT(structname, atype, htype, ltype, fieldname, tag) +1 +#define PB_GEN_REQ_FIELD_COUNT(structname, atype, htype, ltype, fieldname, tag) \ + + (PB_HTYPE_ ## htype == PB_HTYPE_REQUIRED) +#define PB_GEN_LARGEST_TAG(structname, atype, htype, ltype, fieldname, tag) \ + * 0 + tag + +/* X-macro for generating the entries in struct_field_info[] array. */ +#define PB_GEN_FIELD_INFO_1(structname, atype, htype, ltype, fieldname, tag) \ + PB_FIELDINFO_1(tag, PB_ATYPE_ ## atype | PB_HTYPE_ ## htype | PB_LTYPE_MAP_ ## ltype, \ + PB_DATA_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_DATA_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_SIZE_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_ARRAY_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname)) + +#define PB_GEN_FIELD_INFO_2(structname, atype, htype, ltype, fieldname, tag) \ + PB_FIELDINFO_2(tag, PB_ATYPE_ ## atype | PB_HTYPE_ ## htype | PB_LTYPE_MAP_ ## ltype, \ + PB_DATA_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_DATA_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_SIZE_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_ARRAY_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname)) + +#define PB_GEN_FIELD_INFO_4(structname, atype, htype, ltype, fieldname, tag) \ + PB_FIELDINFO_4(tag, PB_ATYPE_ ## atype | PB_HTYPE_ ## htype | PB_LTYPE_MAP_ ## ltype, \ + PB_DATA_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_DATA_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_SIZE_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_ARRAY_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname)) + +#define PB_GEN_FIELD_INFO_8(structname, atype, htype, ltype, fieldname, tag) \ + PB_FIELDINFO_8(tag, PB_ATYPE_ ## atype | PB_HTYPE_ ## htype | PB_LTYPE_MAP_ ## ltype, \ + PB_DATA_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_DATA_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_SIZE_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_ARRAY_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname)) + +#define PB_GEN_FIELD_INFO_AUTO(structname, atype, htype, ltype, fieldname, tag) \ + PB_FIELDINFO_AUTO2(PB_FIELDINFO_WIDTH_AUTO(_PB_ATYPE_ ## atype, _PB_HTYPE_ ## htype, _PB_LTYPE_ ## ltype), \ + tag, PB_ATYPE_ ## atype | PB_HTYPE_ ## htype | PB_LTYPE_MAP_ ## ltype, \ + PB_DATA_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_DATA_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_SIZE_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_ARRAY_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname)) + +#define PB_FIELDINFO_AUTO2(width, tag, type, data_offset, data_size, size_offset, array_size) \ + PB_FIELDINFO_AUTO3(width, tag, type, data_offset, data_size, size_offset, array_size) + +#define PB_FIELDINFO_AUTO3(width, tag, type, data_offset, data_size, size_offset, array_size) \ + PB_FIELDINFO_ ## width(tag, type, data_offset, data_size, size_offset, array_size) + +/* X-macro for generating asserts that entries fit in struct_field_info[] array. + * The structure of macros here must match the structure above in PB_GEN_FIELD_INFO_x(), + * but it is not easily reused because of how macro substitutions work. */ +#define PB_GEN_FIELD_INFO_ASSERT_1(structname, atype, htype, ltype, fieldname, tag) \ + PB_FIELDINFO_ASSERT_1(tag, PB_ATYPE_ ## atype | PB_HTYPE_ ## htype | PB_LTYPE_MAP_ ## ltype, \ + PB_DATA_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_DATA_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_SIZE_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_ARRAY_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname)) + +#define PB_GEN_FIELD_INFO_ASSERT_2(structname, atype, htype, ltype, fieldname, tag) \ + PB_FIELDINFO_ASSERT_2(tag, PB_ATYPE_ ## atype | PB_HTYPE_ ## htype | PB_LTYPE_MAP_ ## ltype, \ + PB_DATA_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_DATA_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_SIZE_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_ARRAY_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname)) + +#define PB_GEN_FIELD_INFO_ASSERT_4(structname, atype, htype, ltype, fieldname, tag) \ + PB_FIELDINFO_ASSERT_4(tag, PB_ATYPE_ ## atype | PB_HTYPE_ ## htype | PB_LTYPE_MAP_ ## ltype, \ + PB_DATA_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_DATA_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_SIZE_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_ARRAY_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname)) + +#define PB_GEN_FIELD_INFO_ASSERT_8(structname, atype, htype, ltype, fieldname, tag) \ + PB_FIELDINFO_ASSERT_8(tag, PB_ATYPE_ ## atype | PB_HTYPE_ ## htype | PB_LTYPE_MAP_ ## ltype, \ + PB_DATA_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_DATA_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_SIZE_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_ARRAY_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname)) + +#define PB_GEN_FIELD_INFO_ASSERT_AUTO(structname, atype, htype, ltype, fieldname, tag) \ + PB_FIELDINFO_ASSERT_AUTO2(PB_FIELDINFO_WIDTH_AUTO(_PB_ATYPE_ ## atype, _PB_HTYPE_ ## htype, _PB_LTYPE_ ## ltype), \ + tag, PB_ATYPE_ ## atype | PB_HTYPE_ ## htype | PB_LTYPE_MAP_ ## ltype, \ + PB_DATA_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_DATA_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_SIZE_OFFSET_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname), \ + PB_ARRAY_SIZE_ ## atype(_PB_HTYPE_ ## htype, structname, fieldname)) + +#define PB_FIELDINFO_ASSERT_AUTO2(width, tag, type, data_offset, data_size, size_offset, array_size) \ + PB_FIELDINFO_ASSERT_AUTO3(width, tag, type, data_offset, data_size, size_offset, array_size) + +#define PB_FIELDINFO_ASSERT_AUTO3(width, tag, type, data_offset, data_size, size_offset, array_size) \ + PB_FIELDINFO_ASSERT_ ## width(tag, type, data_offset, data_size, size_offset, array_size) + +#define PB_DATA_OFFSET_STATIC(htype, structname, fieldname) PB_DO ## htype(structname, fieldname) +#define PB_DATA_OFFSET_POINTER(htype, structname, fieldname) PB_DO ## htype(structname, fieldname) +#define PB_DATA_OFFSET_CALLBACK(htype, structname, fieldname) PB_DO ## htype(structname, fieldname) +#define PB_DO_PB_HTYPE_REQUIRED(structname, fieldname) offsetof(structname, fieldname) +#define PB_DO_PB_HTYPE_SINGULAR(structname, fieldname) offsetof(structname, fieldname) +#define PB_DO_PB_HTYPE_ONEOF(structname, fieldname) offsetof(structname, PB_ONEOF_NAME(FULL, fieldname)) +#define PB_DO_PB_HTYPE_OPTIONAL(structname, fieldname) offsetof(structname, fieldname) +#define PB_DO_PB_HTYPE_REPEATED(structname, fieldname) offsetof(structname, fieldname) +#define PB_DO_PB_HTYPE_FIXARRAY(structname, fieldname) offsetof(structname, fieldname) + +#define PB_SIZE_OFFSET_STATIC(htype, structname, fieldname) PB_SO ## htype(structname, fieldname) +#define PB_SIZE_OFFSET_POINTER(htype, structname, fieldname) PB_SO_PTR ## htype(structname, fieldname) +#define PB_SIZE_OFFSET_CALLBACK(htype, structname, fieldname) PB_SO_CB ## htype(structname, fieldname) +#define PB_SO_PB_HTYPE_REQUIRED(structname, fieldname) 0 +#define PB_SO_PB_HTYPE_SINGULAR(structname, fieldname) 0 +#define PB_SO_PB_HTYPE_ONEOF(structname, fieldname) PB_SO_PB_HTYPE_ONEOF2(structname, PB_ONEOF_NAME(FULL, fieldname), PB_ONEOF_NAME(UNION, fieldname)) +#define PB_SO_PB_HTYPE_ONEOF2(structname, fullname, unionname) PB_SO_PB_HTYPE_ONEOF3(structname, fullname, unionname) +#define PB_SO_PB_HTYPE_ONEOF3(structname, fullname, unionname) pb_delta(structname, fullname, which_ ## unionname) +#define PB_SO_PB_HTYPE_OPTIONAL(structname, fieldname) pb_delta(structname, fieldname, has_ ## fieldname) +#define PB_SO_PB_HTYPE_REPEATED(structname, fieldname) pb_delta(structname, fieldname, fieldname ## _count) +#define PB_SO_PB_HTYPE_FIXARRAY(structname, fieldname) 0 +#define PB_SO_PTR_PB_HTYPE_REQUIRED(structname, fieldname) 0 +#define PB_SO_PTR_PB_HTYPE_SINGULAR(structname, fieldname) 0 +#define PB_SO_PTR_PB_HTYPE_ONEOF(structname, fieldname) PB_SO_PB_HTYPE_ONEOF(structname, fieldname) +#define PB_SO_PTR_PB_HTYPE_OPTIONAL(structname, fieldname) 0 +#define PB_SO_PTR_PB_HTYPE_REPEATED(structname, fieldname) PB_SO_PB_HTYPE_REPEATED(structname, fieldname) +#define PB_SO_PTR_PB_HTYPE_FIXARRAY(structname, fieldname) 0 +#define PB_SO_CB_PB_HTYPE_REQUIRED(structname, fieldname) 0 +#define PB_SO_CB_PB_HTYPE_SINGULAR(structname, fieldname) 0 +#define PB_SO_CB_PB_HTYPE_ONEOF(structname, fieldname) PB_SO_PB_HTYPE_ONEOF(structname, fieldname) +#define PB_SO_CB_PB_HTYPE_OPTIONAL(structname, fieldname) 0 +#define PB_SO_CB_PB_HTYPE_REPEATED(structname, fieldname) 0 +#define PB_SO_CB_PB_HTYPE_FIXARRAY(structname, fieldname) 0 + +#define PB_ARRAY_SIZE_STATIC(htype, structname, fieldname) PB_AS ## htype(structname, fieldname) +#define PB_ARRAY_SIZE_POINTER(htype, structname, fieldname) PB_AS_PTR ## htype(structname, fieldname) +#define PB_ARRAY_SIZE_CALLBACK(htype, structname, fieldname) 1 +#define PB_AS_PB_HTYPE_REQUIRED(structname, fieldname) 1 +#define PB_AS_PB_HTYPE_SINGULAR(structname, fieldname) 1 +#define PB_AS_PB_HTYPE_OPTIONAL(structname, fieldname) 1 +#define PB_AS_PB_HTYPE_ONEOF(structname, fieldname) 1 +#define PB_AS_PB_HTYPE_REPEATED(structname, fieldname) pb_arraysize(structname, fieldname) +#define PB_AS_PB_HTYPE_FIXARRAY(structname, fieldname) pb_arraysize(structname, fieldname) +#define PB_AS_PTR_PB_HTYPE_REQUIRED(structname, fieldname) 1 +#define PB_AS_PTR_PB_HTYPE_SINGULAR(structname, fieldname) 1 +#define PB_AS_PTR_PB_HTYPE_OPTIONAL(structname, fieldname) 1 +#define PB_AS_PTR_PB_HTYPE_ONEOF(structname, fieldname) 1 +#define PB_AS_PTR_PB_HTYPE_REPEATED(structname, fieldname) 1 +#define PB_AS_PTR_PB_HTYPE_FIXARRAY(structname, fieldname) pb_arraysize(structname, fieldname[0]) + +#define PB_DATA_SIZE_STATIC(htype, structname, fieldname) PB_DS ## htype(structname, fieldname) +#define PB_DATA_SIZE_POINTER(htype, structname, fieldname) PB_DS_PTR ## htype(structname, fieldname) +#define PB_DATA_SIZE_CALLBACK(htype, structname, fieldname) PB_DS_CB ## htype(structname, fieldname) +#define PB_DS_PB_HTYPE_REQUIRED(structname, fieldname) pb_membersize(structname, fieldname) +#define PB_DS_PB_HTYPE_SINGULAR(structname, fieldname) pb_membersize(structname, fieldname) +#define PB_DS_PB_HTYPE_OPTIONAL(structname, fieldname) pb_membersize(structname, fieldname) +#define PB_DS_PB_HTYPE_ONEOF(structname, fieldname) pb_membersize(structname, PB_ONEOF_NAME(FULL, fieldname)) +#define PB_DS_PB_HTYPE_REPEATED(structname, fieldname) pb_membersize(structname, fieldname[0]) +#define PB_DS_PB_HTYPE_FIXARRAY(structname, fieldname) pb_membersize(structname, fieldname[0]) +#define PB_DS_PTR_PB_HTYPE_REQUIRED(structname, fieldname) pb_membersize(structname, fieldname[0]) +#define PB_DS_PTR_PB_HTYPE_SINGULAR(structname, fieldname) pb_membersize(structname, fieldname[0]) +#define PB_DS_PTR_PB_HTYPE_OPTIONAL(structname, fieldname) pb_membersize(structname, fieldname[0]) +#define PB_DS_PTR_PB_HTYPE_ONEOF(structname, fieldname) pb_membersize(structname, PB_ONEOF_NAME(FULL, fieldname)[0]) +#define PB_DS_PTR_PB_HTYPE_REPEATED(structname, fieldname) pb_membersize(structname, fieldname[0]) +#define PB_DS_PTR_PB_HTYPE_FIXARRAY(structname, fieldname) pb_membersize(structname, fieldname[0][0]) +#define PB_DS_CB_PB_HTYPE_REQUIRED(structname, fieldname) pb_membersize(structname, fieldname) +#define PB_DS_CB_PB_HTYPE_SINGULAR(structname, fieldname) pb_membersize(structname, fieldname) +#define PB_DS_CB_PB_HTYPE_OPTIONAL(structname, fieldname) pb_membersize(structname, fieldname) +#define PB_DS_CB_PB_HTYPE_ONEOF(structname, fieldname) pb_membersize(structname, PB_ONEOF_NAME(FULL, fieldname)) +#define PB_DS_CB_PB_HTYPE_REPEATED(structname, fieldname) pb_membersize(structname, fieldname) +#define PB_DS_CB_PB_HTYPE_FIXARRAY(structname, fieldname) pb_membersize(structname, fieldname) + +#define PB_ONEOF_NAME(type, tuple) PB_EXPAND(PB_ONEOF_NAME_ ## type tuple) +#define PB_ONEOF_NAME_UNION(unionname,membername,fullname) unionname +#define PB_ONEOF_NAME_MEMBER(unionname,membername,fullname) membername +#define PB_ONEOF_NAME_FULL(unionname,membername,fullname) fullname + +#define PB_GEN_SUBMSG_INFO(structname, atype, htype, ltype, fieldname, tag) \ + PB_SUBMSG_INFO_ ## htype(_PB_LTYPE_ ## ltype, structname, fieldname) + +#define PB_SUBMSG_INFO_REQUIRED(ltype, structname, fieldname) PB_SI ## ltype(structname ## _ ## fieldname ## _MSGTYPE) +#define PB_SUBMSG_INFO_SINGULAR(ltype, structname, fieldname) PB_SI ## ltype(structname ## _ ## fieldname ## _MSGTYPE) +#define PB_SUBMSG_INFO_OPTIONAL(ltype, structname, fieldname) PB_SI ## ltype(structname ## _ ## fieldname ## _MSGTYPE) +#define PB_SUBMSG_INFO_ONEOF(ltype, structname, fieldname) PB_SUBMSG_INFO_ONEOF2(ltype, structname, PB_ONEOF_NAME(UNION, fieldname), PB_ONEOF_NAME(MEMBER, fieldname)) +#define PB_SUBMSG_INFO_ONEOF2(ltype, structname, unionname, membername) PB_SUBMSG_INFO_ONEOF3(ltype, structname, unionname, membername) +#define PB_SUBMSG_INFO_ONEOF3(ltype, structname, unionname, membername) PB_SI ## ltype(structname ## _ ## unionname ## _ ## membername ## _MSGTYPE) +#define PB_SUBMSG_INFO_REPEATED(ltype, structname, fieldname) PB_SI ## ltype(structname ## _ ## fieldname ## _MSGTYPE) +#define PB_SUBMSG_INFO_FIXARRAY(ltype, structname, fieldname) PB_SI ## ltype(structname ## _ ## fieldname ## _MSGTYPE) +#define PB_SI_PB_LTYPE_BOOL(t) +#define PB_SI_PB_LTYPE_BYTES(t) +#define PB_SI_PB_LTYPE_DOUBLE(t) +#define PB_SI_PB_LTYPE_ENUM(t) +#define PB_SI_PB_LTYPE_UENUM(t) +#define PB_SI_PB_LTYPE_FIXED32(t) +#define PB_SI_PB_LTYPE_FIXED64(t) +#define PB_SI_PB_LTYPE_FLOAT(t) +#define PB_SI_PB_LTYPE_INT32(t) +#define PB_SI_PB_LTYPE_INT64(t) +#define PB_SI_PB_LTYPE_MESSAGE(t) PB_SUBMSG_DESCRIPTOR(t) +#define PB_SI_PB_LTYPE_MSG_W_CB(t) PB_SUBMSG_DESCRIPTOR(t) +#define PB_SI_PB_LTYPE_SFIXED32(t) +#define PB_SI_PB_LTYPE_SFIXED64(t) +#define PB_SI_PB_LTYPE_SINT32(t) +#define PB_SI_PB_LTYPE_SINT64(t) +#define PB_SI_PB_LTYPE_STRING(t) +#define PB_SI_PB_LTYPE_UINT32(t) +#define PB_SI_PB_LTYPE_UINT64(t) +#define PB_SI_PB_LTYPE_EXTENSION(t) +#define PB_SI_PB_LTYPE_FIXED_LENGTH_BYTES(t) +#define PB_SUBMSG_DESCRIPTOR(t) (t::msg_descriptor()), + +/* The field descriptors use a variable width format, with width of either + * 1, 2, 4 or 8 of 32-bit words. The two lowest bytes of the first byte always + * encode the descriptor size, 6 lowest bits of field tag number, and 8 bits + * of the field type. + * + * Descriptor size is encoded as 0 = 1 word, 1 = 2 words, 2 = 4 words, 3 = 8 words. + * + * Formats, listed starting with the least significant bit of the first word. + * 1 word: [2-bit len] [6-bit tag] [8-bit type] [8-bit data_offset] [4-bit size_offset] [4-bit data_size] + * + * 2 words: [2-bit len] [6-bit tag] [8-bit type] [12-bit array_size] [4-bit size_offset] + * [16-bit data_offset] [12-bit data_size] [4-bit tag>>6] + * + * 4 words: [2-bit len] [6-bit tag] [8-bit type] [16-bit array_size] + * [8-bit size_offset] [24-bit tag>>6] + * [32-bit data_offset] + * [32-bit data_size] + * + * 8 words: [2-bit len] [6-bit tag] [8-bit type] [16-bit reserved] + * [8-bit size_offset] [24-bit tag>>6] + * [32-bit data_offset] + * [32-bit data_size] + * [32-bit array_size] + * [32-bit reserved] + * [32-bit reserved] + * [32-bit reserved] + */ + +#define PB_FIELDINFO_1(tag, type, data_offset, data_size, size_offset, array_size) \ + (0 | (((tag) << 2) & 0xFF) | ((type) << 8) | (((uint32_t)(data_offset) & 0xFF) << 16) | \ + (((uint32_t)(size_offset) & 0x0F) << 24) | (((uint32_t)(data_size) & 0x0F) << 28)), + +#define PB_FIELDINFO_2(tag, type, data_offset, data_size, size_offset, array_size) \ + (1 | (((tag) << 2) & 0xFF) | ((type) << 8) | (((uint32_t)(array_size) & 0xFFF) << 16) | (((uint32_t)(size_offset) & 0x0F) << 28)), \ + (((uint32_t)(data_offset) & 0xFFFF) | (((uint32_t)(data_size) & 0xFFF) << 16) | (((uint32_t)(tag) & 0x3c0) << 22)), + +#define PB_FIELDINFO_4(tag, type, data_offset, data_size, size_offset, array_size) \ + (2 | (((tag) << 2) & 0xFF) | ((type) << 8) | (((uint32_t)(array_size) & 0xFFFF) << 16)), \ + ((uint32_t)(int_least8_t)(size_offset) | (((uint32_t)(tag) << 2) & 0xFFFFFF00)), \ + (data_offset), (data_size), + +#define PB_FIELDINFO_8(tag, type, data_offset, data_size, size_offset, array_size) \ + (3 | (((tag) << 2) & 0xFF) | ((type) << 8)), \ + ((uint32_t)(int_least8_t)(size_offset) | (((uint32_t)(tag) << 2) & 0xFFFFFF00)), \ + (data_offset), (data_size), (array_size), 0, 0, 0, + +/* These assertions verify that the field information fits in the allocated space. + * The generator tries to automatically determine the correct width that can fit all + * data associated with a message. These asserts will fail only if there has been a + * problem in the automatic logic - this may be worth reporting as a bug. As a workaround, + * you can increase the descriptor width by defining PB_FIELDINFO_WIDTH or by setting + * descriptorsize option in .options file. + */ +#define PB_FITS(value,bits) ((uint32_t)(value) < ((uint32_t)1<2GB messages with nanopb anyway. + */ +#define PB_FIELDINFO_ASSERT_4(tag, type, data_offset, data_size, size_offset, array_size) \ + PB_STATIC_ASSERT(PB_FITS(tag,30) && PB_FITS(data_offset,31) && PB_FITS(size_offset,8) && PB_FITS(data_size,31) && PB_FITS(array_size,16), FIELDINFO_DOES_NOT_FIT_width4_field ## tag) + +#define PB_FIELDINFO_ASSERT_8(tag, type, data_offset, data_size, size_offset, array_size) \ + PB_STATIC_ASSERT(PB_FITS(tag,30) && PB_FITS(data_offset,31) && PB_FITS(size_offset,8) && PB_FITS(data_size,31) && PB_FITS(array_size,31), FIELDINFO_DOES_NOT_FIT_width8_field ## tag) +#endif + + +/* Automatic picking of FIELDINFO width: + * Uses width 1 when possible, otherwise resorts to width 2. + * This is used when PB_BIND() is called with "AUTO" as the argument. + * The generator will give explicit size argument when it knows that a message + * structure grows beyond 1-word format limits. + */ +#define PB_FIELDINFO_WIDTH_AUTO(atype, htype, ltype) PB_FI_WIDTH ## atype(htype, ltype) +#define PB_FI_WIDTH_PB_ATYPE_STATIC(htype, ltype) PB_FI_WIDTH ## htype(ltype) +#define PB_FI_WIDTH_PB_ATYPE_POINTER(htype, ltype) PB_FI_WIDTH ## htype(ltype) +#define PB_FI_WIDTH_PB_ATYPE_CALLBACK(htype, ltype) 2 +#define PB_FI_WIDTH_PB_HTYPE_REQUIRED(ltype) PB_FI_WIDTH ## ltype +#define PB_FI_WIDTH_PB_HTYPE_SINGULAR(ltype) PB_FI_WIDTH ## ltype +#define PB_FI_WIDTH_PB_HTYPE_OPTIONAL(ltype) PB_FI_WIDTH ## ltype +#define PB_FI_WIDTH_PB_HTYPE_ONEOF(ltype) PB_FI_WIDTH ## ltype +#define PB_FI_WIDTH_PB_HTYPE_REPEATED(ltype) 2 +#define PB_FI_WIDTH_PB_HTYPE_FIXARRAY(ltype) 2 +#define PB_FI_WIDTH_PB_LTYPE_BOOL 1 +#define PB_FI_WIDTH_PB_LTYPE_BYTES 2 +#define PB_FI_WIDTH_PB_LTYPE_DOUBLE 1 +#define PB_FI_WIDTH_PB_LTYPE_ENUM 1 +#define PB_FI_WIDTH_PB_LTYPE_UENUM 1 +#define PB_FI_WIDTH_PB_LTYPE_FIXED32 1 +#define PB_FI_WIDTH_PB_LTYPE_FIXED64 1 +#define PB_FI_WIDTH_PB_LTYPE_FLOAT 1 +#define PB_FI_WIDTH_PB_LTYPE_INT32 1 +#define PB_FI_WIDTH_PB_LTYPE_INT64 1 +#define PB_FI_WIDTH_PB_LTYPE_MESSAGE 2 +#define PB_FI_WIDTH_PB_LTYPE_MSG_W_CB 2 +#define PB_FI_WIDTH_PB_LTYPE_SFIXED32 1 +#define PB_FI_WIDTH_PB_LTYPE_SFIXED64 1 +#define PB_FI_WIDTH_PB_LTYPE_SINT32 1 +#define PB_FI_WIDTH_PB_LTYPE_SINT64 1 +#define PB_FI_WIDTH_PB_LTYPE_STRING 2 +#define PB_FI_WIDTH_PB_LTYPE_UINT32 1 +#define PB_FI_WIDTH_PB_LTYPE_UINT64 1 +#define PB_FI_WIDTH_PB_LTYPE_EXTENSION 1 +#define PB_FI_WIDTH_PB_LTYPE_FIXED_LENGTH_BYTES 2 + +/* The mapping from protobuf types to LTYPEs is done using these macros. */ +#define PB_LTYPE_MAP_BOOL PB_LTYPE_BOOL +#define PB_LTYPE_MAP_BYTES PB_LTYPE_BYTES +#define PB_LTYPE_MAP_DOUBLE PB_LTYPE_FIXED64 +#define PB_LTYPE_MAP_ENUM PB_LTYPE_VARINT +#define PB_LTYPE_MAP_UENUM PB_LTYPE_UVARINT +#define PB_LTYPE_MAP_FIXED32 PB_LTYPE_FIXED32 +#define PB_LTYPE_MAP_FIXED64 PB_LTYPE_FIXED64 +#define PB_LTYPE_MAP_FLOAT PB_LTYPE_FIXED32 +#define PB_LTYPE_MAP_INT32 PB_LTYPE_VARINT +#define PB_LTYPE_MAP_INT64 PB_LTYPE_VARINT +#define PB_LTYPE_MAP_MESSAGE PB_LTYPE_SUBMESSAGE +#define PB_LTYPE_MAP_MSG_W_CB PB_LTYPE_SUBMSG_W_CB +#define PB_LTYPE_MAP_SFIXED32 PB_LTYPE_FIXED32 +#define PB_LTYPE_MAP_SFIXED64 PB_LTYPE_FIXED64 +#define PB_LTYPE_MAP_SINT32 PB_LTYPE_SVARINT +#define PB_LTYPE_MAP_SINT64 PB_LTYPE_SVARINT +#define PB_LTYPE_MAP_STRING PB_LTYPE_STRING +#define PB_LTYPE_MAP_UINT32 PB_LTYPE_UVARINT +#define PB_LTYPE_MAP_UINT64 PB_LTYPE_UVARINT +#define PB_LTYPE_MAP_EXTENSION PB_LTYPE_EXTENSION +#define PB_LTYPE_MAP_FIXED_LENGTH_BYTES PB_LTYPE_FIXED_LENGTH_BYTES + +/* These macros are used for giving out error messages. + * They are mostly a debugging aid; the main error information + * is the true/false return value from functions. + * Some code space can be saved by disabling the error + * messages if not used. + * + * PB_SET_ERROR() sets the error message if none has been set yet. + * msg must be a constant string literal. + * PB_GET_ERROR() always returns a pointer to a string. + * PB_RETURN_ERROR() sets the error and returns false from current + * function. + */ +#ifdef PB_NO_ERRMSG +#define PB_SET_ERROR(stream, msg) PB_UNUSED(stream) +#define PB_GET_ERROR(stream) "(errmsg disabled)" +#else +#define PB_SET_ERROR(stream, msg) (stream->errmsg = (stream)->errmsg ? (stream)->errmsg : (msg)) +#define PB_GET_ERROR(stream) ((stream)->errmsg ? (stream)->errmsg : "(none)") +#endif + +#define PB_RETURN_ERROR(stream, msg) return PB_SET_ERROR(stream, msg), false + +#ifdef __cplusplus +#if __cplusplus >= 201103L +#define PB_CONSTEXPR constexpr +#else // __cplusplus >= 201103L +#define PB_CONSTEXPR +#endif // __cplusplus >= 201103L + +#if __cplusplus >= 201703L +#define PB_INLINE_CONSTEXPR inline constexpr +#else // __cplusplus >= 201703L +#define PB_INLINE_CONSTEXPR PB_CONSTEXPR +#endif // __cplusplus >= 201703L + +extern "C++" +{ +namespace nanopb { +// Each type will be partially specialized by the generator. +template struct MessageDescriptor; +} // namespace nanopb +} +#endif /* __cplusplus */ + +#endif diff --git a/wpiutil/src/main/native/thirdparty/nanopb/include/pb_common.h b/wpiutil/src/main/native/thirdparty/nanopb/include/pb_common.h new file mode 100644 index 0000000000..f08a87389b --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/include/pb_common.h @@ -0,0 +1,42 @@ +/* pb_common.h: Common support functions for pb_encode.c and pb_decode.c. + * These functions are rarely needed by applications directly. + * + * Modified for WPILib Use + */ + +#ifndef PB_COMMON_H_INCLUDED +#define PB_COMMON_H_INCLUDED + +#include "pb.h" + +/* Initialize the field iterator structure to beginning. + * Returns false if the message type is empty. */ +bool pb_field_iter_begin(pb_field_iter_t *iter, const pb_msgdesc_t *desc, void *message); + +/* Get a field iterator for extension field. */ +bool pb_field_iter_begin_extension(pb_field_iter_t *iter, pb_extension_t *extension); + +/* Same as pb_field_iter_begin(), but for const message pointer. + * Note that the pointers in pb_field_iter_t will be non-const but shouldn't + * be written to when using these functions. */ +bool pb_field_iter_begin_const(pb_field_iter_t *iter, const pb_msgdesc_t *desc, const void *message); +bool pb_field_iter_begin_extension_const(pb_field_iter_t *iter, const pb_extension_t *extension); + +/* Advance the iterator to the next field. + * Returns false when the iterator wraps back to the first field. */ +bool pb_field_iter_next(pb_field_iter_t *iter); + +/* Advance the iterator until it points at a field with the given tag. + * Returns false if no such field exists. */ +bool pb_field_iter_find(pb_field_iter_t *iter, uint32_t tag); + +/* Find a field with type PB_LTYPE_EXTENSION, or return false if not found. + * There can be only one extension range field per message. */ +bool pb_field_iter_find_extension(pb_field_iter_t *iter); + +#ifdef PB_VALIDATE_UTF8 +/* Validate UTF-8 text string */ +bool pb_validate_utf8(const char *s); +#endif + +#endif diff --git a/wpiutil/src/main/native/thirdparty/nanopb/include/pb_decode.h b/wpiutil/src/main/native/thirdparty/nanopb/include/pb_decode.h new file mode 100644 index 0000000000..a96f181691 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/include/pb_decode.h @@ -0,0 +1,198 @@ +/* pb_decode.h: Functions to decode protocol buffers. Depends on pb_decode.c. + * The main function is pb_decode. You also need an input stream, and the + * field descriptions created by nanopb_generator.py. + * + * Modified for WPILib Use + */ + +#ifndef PB_DECODE_H_INCLUDED +#define PB_DECODE_H_INCLUDED + +#include "pb.h" + +/* Structure for defining custom input streams. You will need to provide + * a callback function to read the bytes from your storage, which can be + * for example a file or a network socket. + * + * The callback must conform to these rules: + * + * 1) Return false on IO errors. This will cause decoding to abort. + * 2) You can use state to store your own data (e.g. buffer pointer), + * and rely on pb_read to verify that no-body reads past bytes_left. + * 3) Your callback may be used with substreams, in which case bytes_left + * is different than from the main stream. Don't use bytes_left to compute + * any pointers. + */ +struct pb_istream_s +{ +#ifdef PB_BUFFER_ONLY + /* Callback pointer is not used in buffer-only configuration. + * Having an int pointer here allows binary compatibility but + * gives an error if someone tries to assign callback function. + */ + int *callback; +#else + bool (*callback)(pb_istream_t *stream, pb_byte_t *buf, size_t count); +#endif + + /* state is a free field for use of the callback function defined above. + * Note that when pb_istream_from_buffer() is used, it reserves this field + * for its own use. + */ + void *state; + + /* Maximum number of bytes left in this stream. Callback can report + * EOF before this limit is reached. Setting a limit is recommended + * when decoding directly from file or network streams to avoid + * denial-of-service by excessively long messages. + */ + size_t bytes_left; + +#ifndef PB_NO_ERRMSG + /* Pointer to constant (ROM) string when decoding function returns error */ + const char *errmsg; +#endif +}; + +#ifndef PB_NO_ERRMSG +#define PB_ISTREAM_EMPTY {0,0,0,0} +#else +#define PB_ISTREAM_EMPTY {0,0,0} +#endif + +/*************************** + * Main decoding functions * + ***************************/ + +/* Decode a single protocol buffers message from input stream into a C structure. + * Returns true on success, false on any failure. + * The actual struct pointed to by dest must match the description in fields. + * Callback fields of the destination structure must be initialized by caller. + * All other fields will be initialized by this function. + * + * Example usage: + * MyMessage msg = {}; + * uint8_t buffer[64]; + * pb_istream_t stream; + * + * // ... read some data into buffer ... + * + * stream = pb_istream_from_buffer(buffer, count); + * pb_decode(&stream, MyMessage_fields, &msg); + */ +bool pb_decode(pb_istream_t *stream, const pb_msgdesc_t *fields, void *dest_struct); + +/* Extended version of pb_decode, with several options to control + * the decoding process: + * + * PB_DECODE_NOINIT: Do not initialize the fields to default values. + * This is slightly faster if you do not need the default + * values and instead initialize the structure to 0 using + * e.g. memset(). This can also be used for merging two + * messages, i.e. combine already existing data with new + * values. + * + * PB_DECODE_DELIMITED: Input message starts with the message size as varint. + * Corresponds to parseDelimitedFrom() in Google's + * protobuf API. + * + * PB_DECODE_NULLTERMINATED: Stop reading when field tag is read as 0. This allows + * reading null terminated messages. + * NOTE: Until nanopb-0.4.0, pb_decode() also allows + * null-termination. This behaviour is not supported in + * most other protobuf implementations, so PB_DECODE_DELIMITED + * is a better option for compatibility. + * + * Multiple flags can be combined with bitwise or (| operator) + */ +#define PB_DECODE_NOINIT 0x01U +#define PB_DECODE_DELIMITED 0x02U +#define PB_DECODE_NULLTERMINATED 0x04U +bool pb_decode_ex(pb_istream_t *stream, const pb_msgdesc_t *fields, void *dest_struct, unsigned int flags); + +/* Defines for backwards compatibility with code written before nanopb-0.4.0 */ +#define pb_decode_noinit(s,f,d) pb_decode_ex(s,f,d, PB_DECODE_NOINIT) +#define pb_decode_delimited(s,f,d) pb_decode_ex(s,f,d, PB_DECODE_DELIMITED) +#define pb_decode_delimited_noinit(s,f,d) pb_decode_ex(s,f,d, PB_DECODE_DELIMITED | PB_DECODE_NOINIT) +#define pb_decode_nullterminated(s,f,d) pb_decode_ex(s,f,d, PB_DECODE_NULLTERMINATED) + +/* Release any allocated pointer fields. If you use dynamic allocation, you should + * call this for any successfully decoded message when you are done with it. If + * pb_decode() returns with an error, the message is already released. + */ +void pb_release(const pb_msgdesc_t *fields, void *dest_struct); + +/************************************** + * Functions for manipulating streams * + **************************************/ + +/* Create an input stream for reading from a memory buffer. + * + * msglen should be the actual length of the message, not the full size of + * allocated buffer. + * + * Alternatively, you can use a custom stream that reads directly from e.g. + * a file or a network socket. + */ +pb_istream_t pb_istream_from_buffer(const pb_byte_t *buf, size_t msglen); + +/* Function to read from a pb_istream_t. You can use this if you need to + * read some custom header data, or to read data in field callbacks. + */ +bool pb_read(pb_istream_t *stream, pb_byte_t *buf, size_t count); + + +/************************************************ + * Helper functions for writing field callbacks * + ************************************************/ + +/* Decode the tag for the next field in the stream. Gives the wire type and + * field tag. At end of the message, returns false and sets eof to true. */ +bool pb_decode_tag(pb_istream_t *stream, pb_wire_type_t *wire_type, uint32_t *tag, bool *eof); + +/* Skip the field payload data, given the wire type. */ +bool pb_skip_field(pb_istream_t *stream, pb_wire_type_t wire_type); + +/* Decode an integer in the varint format. This works for enum, int32, + * int64, uint32 and uint64 field types. */ +#ifndef PB_WITHOUT_64BIT +bool pb_decode_varint(pb_istream_t *stream, uint64_t *dest); +#else +#define pb_decode_varint pb_decode_varint32 +#endif + +/* Decode an integer in the varint format. This works for enum, int32, + * and uint32 field types. */ +bool pb_decode_varint32(pb_istream_t *stream, uint32_t *dest); + +/* Decode a bool value in varint format. */ +bool pb_decode_bool(pb_istream_t *stream, bool *dest); + +/* Decode an integer in the zig-zagged svarint format. This works for sint32 + * and sint64. */ +#ifndef PB_WITHOUT_64BIT +bool pb_decode_svarint(pb_istream_t *stream, int64_t *dest); +#else +bool pb_decode_svarint(pb_istream_t *stream, int32_t *dest); +#endif + +/* Decode a fixed32, sfixed32 or float value. You need to pass a pointer to + * a 4-byte wide C variable. */ +bool pb_decode_fixed32(pb_istream_t *stream, void *dest); + +#ifndef PB_WITHOUT_64BIT +/* Decode a fixed64, sfixed64 or double value. You need to pass a pointer to + * a 8-byte wide C variable. */ +bool pb_decode_fixed64(pb_istream_t *stream, void *dest); +#endif + +#ifdef PB_CONVERT_DOUBLE_FLOAT +/* Decode a double value into float variable. */ +bool pb_decode_double_as_float(pb_istream_t *stream, float *dest); +#endif + +/* Make a limited-length substream for reading a PB_WT_STRING field. */ +bool pb_make_string_substream(pb_istream_t *stream, pb_istream_t *substream); +bool pb_close_string_substream(pb_istream_t *stream, pb_istream_t *substream); + +#endif diff --git a/wpiutil/src/main/native/thirdparty/nanopb/include/pb_encode.h b/wpiutil/src/main/native/thirdparty/nanopb/include/pb_encode.h new file mode 100644 index 0000000000..961bde1e35 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/include/pb_encode.h @@ -0,0 +1,189 @@ +/* pb_encode.h: Functions to encode protocol buffers. Depends on pb_encode.c. + * The main function is pb_encode. You also need an output stream, and the + * field descriptions created by nanopb_generator.py. + * + * Modified for WPILib Use + */ + +#ifndef PB_ENCODE_H_INCLUDED +#define PB_ENCODE_H_INCLUDED + +#include "pb.h" + +/* Structure for defining custom output streams. You will need to provide + * a callback function to write the bytes to your storage, which can be + * for example a file or a network socket. + * + * The callback must conform to these rules: + * + * 1) Return false on IO errors. This will cause encoding to abort. + * 2) You can use state to store your own data (e.g. buffer pointer). + * 3) pb_write will update bytes_written after your callback runs. + * 4) Substreams will modify max_size and bytes_written. Don't use them + * to calculate any pointers. + */ +struct pb_ostream_s +{ +#ifdef PB_BUFFER_ONLY + /* Callback pointer is not used in buffer-only configuration. + * Having an int pointer here allows binary compatibility but + * gives an error if someone tries to assign callback function. + * Also, NULL pointer marks a 'sizing stream' that does not + * write anything. + */ + const int *callback; +#else + bool (*callback)(pb_ostream_t *stream, const pb_byte_t *buf, size_t count); +#endif + + /* state is a free field for use of the callback function defined above. + * Note that when pb_ostream_from_buffer() is used, it reserves this field + * for its own use. + */ + void *state; + + /* Limit number of output bytes written. Can be set to SIZE_MAX. */ + size_t max_size; + + /* Number of bytes written so far. */ + size_t bytes_written; + +#ifndef PB_NO_ERRMSG + /* Pointer to constant (ROM) string when decoding function returns error */ + const char *errmsg; +#endif +}; + +/*************************** + * Main encoding functions * + ***************************/ + +/* Encode a single protocol buffers message from C structure into a stream. + * Returns true on success, false on any failure. + * The actual struct pointed to by src_struct must match the description in fields. + * All required fields in the struct are assumed to have been filled in. + * + * Example usage: + * MyMessage msg = {}; + * uint8_t buffer[64]; + * pb_ostream_t stream; + * + * msg.field1 = 42; + * stream = pb_ostream_from_buffer(buffer, sizeof(buffer)); + * pb_encode(&stream, MyMessage_fields, &msg); + */ +bool pb_encode(pb_ostream_t *stream, const pb_msgdesc_t *fields, const void *src_struct); + +/* Extended version of pb_encode, with several options to control the + * encoding process: + * + * PB_ENCODE_DELIMITED: Prepend the length of message as a varint. + * Corresponds to writeDelimitedTo() in Google's + * protobuf API. + * + * PB_ENCODE_NULLTERMINATED: Append a null byte to the message for termination. + * NOTE: This behaviour is not supported in most other + * protobuf implementations, so PB_ENCODE_DELIMITED + * is a better option for compatibility. + */ +#define PB_ENCODE_DELIMITED 0x02U +#define PB_ENCODE_NULLTERMINATED 0x04U +bool pb_encode_ex(pb_ostream_t *stream, const pb_msgdesc_t *fields, const void *src_struct, unsigned int flags); + +/* Defines for backwards compatibility with code written before nanopb-0.4.0 */ +#define pb_encode_delimited(s,f,d) pb_encode_ex(s,f,d, PB_ENCODE_DELIMITED) +#define pb_encode_nullterminated(s,f,d) pb_encode_ex(s,f,d, PB_ENCODE_NULLTERMINATED) + +/* Encode the message to get the size of the encoded data, but do not store + * the data. */ +bool pb_get_encoded_size(size_t *size, const pb_msgdesc_t *fields, const void *src_struct); + +/************************************** + * Functions for manipulating streams * + **************************************/ + +/* Create an output stream for writing into a memory buffer. + * The number of bytes written can be found in stream.bytes_written after + * encoding the message. + * + * Alternatively, you can use a custom stream that writes directly to e.g. + * a file or a network socket. + */ +pb_ostream_t pb_ostream_from_buffer(pb_byte_t *buf, size_t bufsize); + +/* Pseudo-stream for measuring the size of a message without actually storing + * the encoded data. + * + * Example usage: + * MyMessage msg = {}; + * pb_ostream_t stream = PB_OSTREAM_SIZING; + * pb_encode(&stream, MyMessage_fields, &msg); + * printf("Message size is %d\n", stream.bytes_written); + */ +#ifndef PB_NO_ERRMSG +#define PB_OSTREAM_SIZING {0,0,0,0,0} +#else +#define PB_OSTREAM_SIZING {0,0,0,0} +#endif + +/* Function to write into a pb_ostream_t stream. You can use this if you need + * to append or prepend some custom headers to the message. + */ +bool pb_write(pb_ostream_t *stream, const pb_byte_t *buf, size_t count); + + +/************************************************ + * Helper functions for writing field callbacks * + ************************************************/ + +/* Encode field header based on type and field number defined in the field + * structure. Call this from the callback before writing out field contents. */ +bool pb_encode_tag_for_field(pb_ostream_t *stream, const pb_field_iter_t *field); + +/* Encode field header by manually specifying wire type. You need to use this + * if you want to write out packed arrays from a callback field. */ +bool pb_encode_tag(pb_ostream_t *stream, pb_wire_type_t wiretype, uint32_t field_number); + +/* Encode an integer in the varint format. + * This works for bool, enum, int32, int64, uint32 and uint64 field types. */ +#ifndef PB_WITHOUT_64BIT +bool pb_encode_varint(pb_ostream_t *stream, uint64_t value); +#else +bool pb_encode_varint(pb_ostream_t *stream, uint32_t value); +#endif + +/* Encode an integer in the zig-zagged svarint format. + * This works for sint32 and sint64. */ +#ifndef PB_WITHOUT_64BIT +bool pb_encode_svarint(pb_ostream_t *stream, int64_t value); +#else +bool pb_encode_svarint(pb_ostream_t *stream, int32_t value); +#endif + +/* Encode a string or bytes type field. For strings, pass strlen(s) as size. */ +bool pb_encode_string(pb_ostream_t *stream, const pb_byte_t *buffer, size_t size); + +/* Encode a fixed32, sfixed32 or float value. + * You need to pass a pointer to a 4-byte wide C variable. */ +bool pb_encode_fixed32(pb_ostream_t *stream, const void *value); + +#ifndef PB_WITHOUT_64BIT +/* Encode a fixed64, sfixed64 or double value. + * You need to pass a pointer to a 8-byte wide C variable. */ +bool pb_encode_fixed64(pb_ostream_t *stream, const void *value); +#endif + +#ifdef PB_CONVERT_DOUBLE_FLOAT +/* Encode a float value so that it appears like a double in the encoded + * message. */ +bool pb_encode_float_as_double(pb_ostream_t *stream, float value); +#endif + +/* Encode a submessage field. + * You need to pass the pb_field_t array and pointer to struct, just like + * with pb_encode(). This internally encodes the submessage twice, first to + * calculate message size and then to actually write it out. + */ +bool pb_encode_submessage(pb_ostream_t *stream, const pb_msgdesc_t *fields, const void *src_struct); + +#endif diff --git a/wpiutil/src/main/native/thirdparty/nanopb/src/pb_common.cpp b/wpiutil/src/main/native/thirdparty/nanopb/src/pb_common.cpp new file mode 100644 index 0000000000..73698dd7c5 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/src/pb_common.cpp @@ -0,0 +1,389 @@ +/* pb_common.c: Common support functions for pb_encode.c and pb_decode.c. + * + * Modified for WPILib Use + * + * 2014 Petteri Aimonen + */ + +#include "pb_common.h" + +static bool load_descriptor_values(pb_field_iter_t *iter) +{ + uint32_t word0; + uint32_t data_offset; + int_least8_t size_offset; + + if (iter->index >= iter->descriptor->field_count) + return false; + + word0 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index]); + iter->type = (pb_type_t)((word0 >> 8) & 0xFF); + + switch(word0 & 3) + { + case 0: { + /* 1-word format */ + iter->array_size = 1; + iter->tag = (pb_size_t)((word0 >> 2) & 0x3F); + size_offset = (int_least8_t)((word0 >> 24) & 0x0F); + data_offset = (word0 >> 16) & 0xFF; + iter->data_size = (pb_size_t)((word0 >> 28) & 0x0F); + break; + } + + case 1: { + /* 2-word format */ + uint32_t word1 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 1]); + + iter->array_size = (pb_size_t)((word0 >> 16) & 0x0FFF); + iter->tag = (pb_size_t)(((word0 >> 2) & 0x3F) | ((word1 >> 28) << 6)); + size_offset = (int_least8_t)((word0 >> 28) & 0x0F); + data_offset = word1 & 0xFFFF; + iter->data_size = (pb_size_t)((word1 >> 16) & 0x0FFF); + break; + } + + case 2: { + /* 4-word format */ + uint32_t word1 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 1]); + uint32_t word2 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 2]); + uint32_t word3 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 3]); + + iter->array_size = (pb_size_t)(word0 >> 16); + iter->tag = (pb_size_t)(((word0 >> 2) & 0x3F) | ((word1 >> 8) << 6)); + size_offset = (int_least8_t)(word1 & 0xFF); + data_offset = word2; + iter->data_size = (pb_size_t)word3; + break; + } + + default: { + /* 8-word format */ + uint32_t word1 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 1]); + uint32_t word2 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 2]); + uint32_t word3 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 3]); + uint32_t word4 = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index + 4]); + + iter->array_size = (pb_size_t)word4; + iter->tag = (pb_size_t)(((word0 >> 2) & 0x3F) | ((word1 >> 8) << 6)); + size_offset = (int_least8_t)(word1 & 0xFF); + data_offset = word2; + iter->data_size = (pb_size_t)word3; + break; + } + } + + if (!iter->message) + { + /* Avoid doing arithmetic on null pointers, it is undefined */ + iter->pField = NULL; + iter->pSize = NULL; + } + else + { + iter->pField = (char*)iter->message + data_offset; + + if (size_offset) + { + iter->pSize = (char*)iter->pField - size_offset; + } + else if (PB_HTYPE(iter->type) == PB_HTYPE_REPEATED && + (PB_ATYPE(iter->type) == PB_ATYPE_STATIC || + PB_ATYPE(iter->type) == PB_ATYPE_POINTER)) + { + /* Fixed count array */ + iter->pSize = &iter->array_size; + } + else + { + iter->pSize = NULL; + } + + if (PB_ATYPE(iter->type) == PB_ATYPE_POINTER && iter->pField != NULL) + { + iter->pData = *(void**)iter->pField; + } + else + { + iter->pData = iter->pField; + } + } + + if (PB_LTYPE_IS_SUBMSG(iter->type)) + { + iter->submsg_desc = iter->descriptor->submsg_info[iter->submessage_index]; + } + else + { + iter->submsg_desc = NULL; + } + + return true; +} + +static void advance_iterator(pb_field_iter_t *iter) +{ + iter->index++; + + if (iter->index >= iter->descriptor->field_count) + { + /* Restart */ + iter->index = 0; + iter->field_info_index = 0; + iter->submessage_index = 0; + iter->required_field_index = 0; + } + else + { + /* Increment indexes based on previous field type. + * All field info formats have the following fields: + * - lowest 2 bits tell the amount of words in the descriptor (2^n words) + * - bits 2..7 give the lowest bits of tag number. + * - bits 8..15 give the field type. + */ + uint32_t prev_descriptor = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index]); + pb_type_t prev_type = (prev_descriptor >> 8) & 0xFF; + pb_size_t descriptor_len = (pb_size_t)(1 << (prev_descriptor & 3)); + + /* Add to fields. + * The cast to pb_size_t is needed to avoid -Wconversion warning. + * Because the data is is constants from generator, there is no danger of overflow. + */ + iter->field_info_index = (pb_size_t)(iter->field_info_index + descriptor_len); + iter->required_field_index = (pb_size_t)(iter->required_field_index + (PB_HTYPE(prev_type) == PB_HTYPE_REQUIRED)); + iter->submessage_index = (pb_size_t)(iter->submessage_index + PB_LTYPE_IS_SUBMSG(prev_type)); + } +} + +bool pb_field_iter_begin(pb_field_iter_t *iter, const pb_msgdesc_t *desc, void *message) +{ + memset(iter, 0, sizeof(*iter)); + + iter->descriptor = desc; + iter->message = message; + + return load_descriptor_values(iter); +} + +bool pb_field_iter_begin_extension(pb_field_iter_t *iter, pb_extension_t *extension) +{ + const pb_msgdesc_t *msg = (const pb_msgdesc_t*)extension->type->arg; + bool status; + + uint32_t word0 = PB_PROGMEM_READU32(msg->field_info[0]); + if (PB_ATYPE(word0 >> 8) == PB_ATYPE_POINTER) + { + /* For pointer extensions, the pointer is stored directly + * in the extension structure. This avoids having an extra + * indirection. */ + status = pb_field_iter_begin(iter, msg, &extension->dest); + } + else + { + status = pb_field_iter_begin(iter, msg, extension->dest); + } + + iter->pSize = &extension->found; + return status; +} + +bool pb_field_iter_next(pb_field_iter_t *iter) +{ + advance_iterator(iter); + (void)load_descriptor_values(iter); + return iter->index != 0; +} + +bool pb_field_iter_find(pb_field_iter_t *iter, uint32_t tag) +{ + if (iter->tag == tag) + { + return true; /* Nothing to do, correct field already. */ + } + else if (tag > iter->descriptor->largest_tag) + { + return false; + } + else + { + pb_size_t start = iter->index; + uint32_t fieldinfo; + + if (tag < iter->tag) + { + /* Fields are in tag number order, so we know that tag is between + * 0 and our start position. Setting index to end forces + * advance_iterator() call below to restart from beginning. */ + iter->index = iter->descriptor->field_count; + } + + do + { + /* Advance iterator but don't load values yet */ + advance_iterator(iter); + + /* Do fast check for tag number match */ + fieldinfo = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index]); + + if (((fieldinfo >> 2) & 0x3F) == (tag & 0x3F)) + { + /* Good candidate, check further */ + (void)load_descriptor_values(iter); + + if (iter->tag == tag && + PB_LTYPE(iter->type) != PB_LTYPE_EXTENSION) + { + /* Found it */ + return true; + } + } + } while (iter->index != start); + + /* Searched all the way back to start, and found nothing. */ + (void)load_descriptor_values(iter); + return false; + } +} + +bool pb_field_iter_find_extension(pb_field_iter_t *iter) +{ + if (PB_LTYPE(iter->type) == PB_LTYPE_EXTENSION) + { + return true; + } + else + { + pb_size_t start = iter->index; + uint32_t fieldinfo; + + do + { + /* Advance iterator but don't load values yet */ + advance_iterator(iter); + + /* Do fast check for field type */ + fieldinfo = PB_PROGMEM_READU32(iter->descriptor->field_info[iter->field_info_index]); + + if (PB_LTYPE((fieldinfo >> 8) & 0xFF) == PB_LTYPE_EXTENSION) + { + return load_descriptor_values(iter); + } + } while (iter->index != start); + + /* Searched all the way back to start, and found nothing. */ + (void)load_descriptor_values(iter); + return false; + } +} + +static void *pb_const_cast(const void *p) +{ + /* Note: this casts away const, in order to use the common field iterator + * logic for both encoding and decoding. The cast is done using union + * to avoid spurious compiler warnings. */ + union { + void *p1; + const void *p2; + } t; + t.p2 = p; + return t.p1; +} + +bool pb_field_iter_begin_const(pb_field_iter_t *iter, const pb_msgdesc_t *desc, const void *message) +{ + return pb_field_iter_begin(iter, desc, pb_const_cast(message)); +} + +bool pb_field_iter_begin_extension_const(pb_field_iter_t *iter, const pb_extension_t *extension) +{ + return pb_field_iter_begin_extension(iter, (pb_extension_t*)pb_const_cast(extension)); +} + +bool pb_default_field_callback(pb_istream_t *istream, pb_ostream_t *ostream, const pb_field_t *field) +{ + if (field->data_size == sizeof(pb_callback_t)) + { + pb_callback_t *pCallback = (pb_callback_t*)field->pData; + + if (pCallback != NULL) + { + if (istream != NULL && pCallback->funcs.decode != NULL) + { + return pCallback->funcs.decode(istream, field, &pCallback->arg); + } + + if (ostream != NULL && pCallback->funcs.encode != NULL) + { + return pCallback->funcs.encode(ostream, field, &pCallback->arg); + } + } + } + + return true; /* Success, but didn't do anything */ + +} + +#ifdef PB_VALIDATE_UTF8 + +/* This function checks whether a string is valid UTF-8 text. + * + * Algorithm is adapted from https://www.cl.cam.ac.uk/~mgk25/ucs/utf8_check.c + * Original copyright: Markus Kuhn 2005-03-30 + * Licensed under "Short code license", which allows use under MIT license or + * any compatible with it. + */ + +bool pb_validate_utf8(const char *str) +{ + const pb_byte_t *s = (const pb_byte_t*)str; + while (*s) + { + if (*s < 0x80) + { + /* 0xxxxxxx */ + s++; + } + else if ((s[0] & 0xe0) == 0xc0) + { + /* 110XXXXx 10xxxxxx */ + if ((s[1] & 0xc0) != 0x80 || + (s[0] & 0xfe) == 0xc0) /* overlong? */ + return false; + else + s += 2; + } + else if ((s[0] & 0xf0) == 0xe0) + { + /* 1110XXXX 10Xxxxxx 10xxxxxx */ + if ((s[1] & 0xc0) != 0x80 || + (s[2] & 0xc0) != 0x80 || + (s[0] == 0xe0 && (s[1] & 0xe0) == 0x80) || /* overlong? */ + (s[0] == 0xed && (s[1] & 0xe0) == 0xa0) || /* surrogate? */ + (s[0] == 0xef && s[1] == 0xbf && + (s[2] & 0xfe) == 0xbe)) /* U+FFFE or U+FFFF? */ + return false; + else + s += 3; + } + else if ((s[0] & 0xf8) == 0xf0) + { + /* 11110XXX 10XXxxxx 10xxxxxx 10xxxxxx */ + if ((s[1] & 0xc0) != 0x80 || + (s[2] & 0xc0) != 0x80 || + (s[3] & 0xc0) != 0x80 || + (s[0] == 0xf0 && (s[1] & 0xf0) == 0x80) || /* overlong? */ + (s[0] == 0xf4 && s[1] > 0x8f) || s[0] > 0xf4) /* > U+10FFFF? */ + return false; + else + s += 4; + } + else + { + return false; + } + } + + return true; +} + +#endif diff --git a/wpiutil/src/main/native/thirdparty/nanopb/src/pb_decode.cpp b/wpiutil/src/main/native/thirdparty/nanopb/src/pb_decode.cpp new file mode 100644 index 0000000000..03143e02a5 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/src/pb_decode.cpp @@ -0,0 +1,1730 @@ +/* pb_decode.c -- decode a protobuf using minimal resources + * + * Modified for WPILib Use + * + * 2011 Petteri Aimonen + */ + +/* Use the GCC warn_unused_result attribute to check that all return values + * are propagated correctly. On other compilers, gcc before 3.4.0 and iar + * before 9.40.1 just ignore the annotation. + */ +#if (defined(__GNUC__) && ((__GNUC__ > 3) || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4))) || \ + (defined(__IAR_SYSTEMS_ICC__) && (__VER__ >= 9040001)) + #define checkreturn __attribute__((warn_unused_result)) +#else + #define checkreturn +#endif + +#include "pb.h" +#include "pb_decode.h" +#include "pb_common.h" + +/************************************** + * Declarations internal to this file * + **************************************/ + +static bool checkreturn buf_read(pb_istream_t *stream, pb_byte_t *buf, size_t count); +static bool checkreturn pb_decode_varint32_eof(pb_istream_t *stream, uint32_t *dest, bool *eof); +static bool checkreturn read_raw_value(pb_istream_t *stream, pb_wire_type_t wire_type, pb_byte_t *buf, size_t *size); +static bool checkreturn decode_basic_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iter_t *field); +static bool checkreturn decode_static_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iter_t *field); +static bool checkreturn decode_pointer_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iter_t *field); +static bool checkreturn decode_callback_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iter_t *field); +static bool checkreturn decode_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iter_t *field); +static bool checkreturn default_extension_decoder(pb_istream_t *stream, pb_extension_t *extension, uint32_t tag, pb_wire_type_t wire_type); +static bool checkreturn decode_extension(pb_istream_t *stream, uint32_t tag, pb_wire_type_t wire_type, pb_extension_t *extension); +static bool pb_field_set_to_default(pb_field_iter_t *field); +static bool pb_message_set_to_defaults(pb_field_iter_t *iter); +static bool checkreturn pb_dec_bool(pb_istream_t *stream, const pb_field_iter_t *field); +static bool checkreturn pb_dec_varint(pb_istream_t *stream, const pb_field_iter_t *field); +static bool checkreturn pb_dec_bytes(pb_istream_t *stream, const pb_field_iter_t *field); +static bool checkreturn pb_dec_string(pb_istream_t *stream, const pb_field_iter_t *field); +static bool checkreturn pb_dec_submessage(pb_istream_t *stream, const pb_field_iter_t *field); +static bool checkreturn pb_dec_fixed_length_bytes(pb_istream_t *stream, const pb_field_iter_t *field); +static bool checkreturn pb_skip_varint(pb_istream_t *stream); +static bool checkreturn pb_skip_string(pb_istream_t *stream); + +#ifdef PB_ENABLE_MALLOC +static bool checkreturn allocate_field(pb_istream_t *stream, void *pData, size_t data_size, size_t array_size); +static void initialize_pointer_field(void *pItem, pb_field_iter_t *field); +static bool checkreturn pb_release_union_field(pb_istream_t *stream, pb_field_iter_t *field); +static void pb_release_single_field(pb_field_iter_t *field); +#endif + +#ifdef PB_WITHOUT_64BIT +#define pb_int64_t int32_t +#define pb_uint64_t uint32_t +#else +#define pb_int64_t int64_t +#define pb_uint64_t uint64_t +#endif + +typedef struct { + uint32_t bitfield[(PB_MAX_REQUIRED_FIELDS + 31) / 32]; +} pb_fields_seen_t; + +/******************************* + * pb_istream_t implementation * + *******************************/ + +static bool checkreturn buf_read(pb_istream_t *stream, pb_byte_t *buf, size_t count) +{ + const pb_byte_t *source = (const pb_byte_t*)stream->state; + stream->state = (pb_byte_t*)stream->state + count; + + if (buf != NULL) + { + memcpy(buf, source, count * sizeof(pb_byte_t)); + } + + return true; +} + +bool checkreturn pb_read(pb_istream_t *stream, pb_byte_t *buf, size_t count) +{ + if (count == 0) + return true; + +#ifndef PB_BUFFER_ONLY + if (buf == NULL && stream->callback != buf_read) + { + /* Skip input bytes */ + pb_byte_t tmp[16]; + while (count > 16) + { + if (!pb_read(stream, tmp, 16)) + return false; + + count -= 16; + } + + return pb_read(stream, tmp, count); + } +#endif + + if (stream->bytes_left < count) + PB_RETURN_ERROR(stream, "end-of-stream"); + +#ifndef PB_BUFFER_ONLY + if (!stream->callback(stream, buf, count)) + PB_RETURN_ERROR(stream, "io error"); +#else + if (!buf_read(stream, buf, count)) + return false; +#endif + + if (stream->bytes_left < count) + stream->bytes_left = 0; + else + stream->bytes_left -= count; + + return true; +} + +/* Read a single byte from input stream. buf may not be NULL. + * This is an optimization for the varint decoding. */ +static bool checkreturn pb_readbyte(pb_istream_t *stream, pb_byte_t *buf) +{ + if (stream->bytes_left == 0) + PB_RETURN_ERROR(stream, "end-of-stream"); + +#ifndef PB_BUFFER_ONLY + if (!stream->callback(stream, buf, 1)) + PB_RETURN_ERROR(stream, "io error"); +#else + *buf = *(const pb_byte_t*)stream->state; + stream->state = (pb_byte_t*)stream->state + 1; +#endif + + stream->bytes_left--; + + return true; +} + +pb_istream_t pb_istream_from_buffer(const pb_byte_t *buf, size_t msglen) +{ + pb_istream_t stream; + /* Cast away the const from buf without a compiler error. We are + * careful to use it only in a const manner in the callbacks. + */ + union { + void *state; + const void *c_state; + } state; +#ifdef PB_BUFFER_ONLY + stream.callback = NULL; +#else + stream.callback = &buf_read; +#endif + state.c_state = buf; + stream.state = state.state; + stream.bytes_left = msglen; +#ifndef PB_NO_ERRMSG + stream.errmsg = NULL; +#endif + return stream; +} + +/******************** + * Helper functions * + ********************/ + +static bool checkreturn pb_decode_varint32_eof(pb_istream_t *stream, uint32_t *dest, bool *eof) +{ + pb_byte_t byte; + uint32_t result; + + if (!pb_readbyte(stream, &byte)) + { + if (stream->bytes_left == 0) + { + if (eof) + { + *eof = true; + } + } + + return false; + } + + if ((byte & 0x80) == 0) + { + /* Quick case, 1 byte value */ + result = byte; + } + else + { + /* Multibyte case */ + uint_fast8_t bitpos = 7; + result = byte & 0x7F; + + do + { + if (!pb_readbyte(stream, &byte)) + return false; + + if (bitpos >= 32) + { + /* Note: The varint could have trailing 0x80 bytes, or 0xFF for negative. */ + pb_byte_t sign_extension = (bitpos < 63) ? 0xFF : 0x01; + bool valid_extension = ((byte & 0x7F) == 0x00 || + ((result >> 31) != 0 && byte == sign_extension)); + + if (bitpos >= 64 || !valid_extension) + { + PB_RETURN_ERROR(stream, "varint overflow"); + } + } + else if (bitpos == 28) + { + if ((byte & 0x70) != 0 && (byte & 0x78) != 0x78) + { + PB_RETURN_ERROR(stream, "varint overflow"); + } + result |= (uint32_t)(byte & 0x0F) << bitpos; + } + else + { + result |= (uint32_t)(byte & 0x7F) << bitpos; + } + bitpos = (uint_fast8_t)(bitpos + 7); + } while (byte & 0x80); + } + + *dest = result; + return true; +} + +bool checkreturn pb_decode_varint32(pb_istream_t *stream, uint32_t *dest) +{ + return pb_decode_varint32_eof(stream, dest, NULL); +} + +#ifndef PB_WITHOUT_64BIT +bool checkreturn pb_decode_varint(pb_istream_t *stream, uint64_t *dest) +{ + pb_byte_t byte; + uint_fast8_t bitpos = 0; + uint64_t result = 0; + + do + { + if (!pb_readbyte(stream, &byte)) + return false; + + if (bitpos >= 63 && (byte & 0xFE) != 0) + PB_RETURN_ERROR(stream, "varint overflow"); + + result |= (uint64_t)(byte & 0x7F) << bitpos; + bitpos = (uint_fast8_t)(bitpos + 7); + } while (byte & 0x80); + + *dest = result; + return true; +} +#endif + +bool checkreturn pb_skip_varint(pb_istream_t *stream) +{ + pb_byte_t byte; + do + { + if (!pb_read(stream, &byte, 1)) + return false; + } while (byte & 0x80); + return true; +} + +bool checkreturn pb_skip_string(pb_istream_t *stream) +{ + uint32_t length; + if (!pb_decode_varint32(stream, &length)) + return false; + + if ((size_t)length != length) + { + PB_RETURN_ERROR(stream, "size too large"); + } + + return pb_read(stream, NULL, (size_t)length); +} + +bool checkreturn pb_decode_tag(pb_istream_t *stream, pb_wire_type_t *wire_type, uint32_t *tag, bool *eof) +{ + uint32_t temp; + *eof = false; + *wire_type = (pb_wire_type_t) 0; + *tag = 0; + + if (!pb_decode_varint32_eof(stream, &temp, eof)) + { + return false; + } + + *tag = temp >> 3; + *wire_type = (pb_wire_type_t)(temp & 7); + return true; +} + +bool checkreturn pb_skip_field(pb_istream_t *stream, pb_wire_type_t wire_type) +{ + switch (wire_type) + { + case PB_WT_VARINT: return pb_skip_varint(stream); + case PB_WT_64BIT: return pb_read(stream, NULL, 8); + case PB_WT_STRING: return pb_skip_string(stream); + case PB_WT_32BIT: return pb_read(stream, NULL, 4); + default: PB_RETURN_ERROR(stream, "invalid wire_type"); + } +} + +/* Read a raw value to buffer, for the purpose of passing it to callback as + * a substream. Size is maximum size on call, and actual size on return. + */ +static bool checkreturn read_raw_value(pb_istream_t *stream, pb_wire_type_t wire_type, pb_byte_t *buf, size_t *size) +{ + size_t max_size = *size; + switch (wire_type) + { + case PB_WT_VARINT: + *size = 0; + do + { + (*size)++; + if (*size > max_size) + PB_RETURN_ERROR(stream, "varint overflow"); + + if (!pb_read(stream, buf, 1)) + return false; + } while (*buf++ & 0x80); + return true; + + case PB_WT_64BIT: + *size = 8; + return pb_read(stream, buf, 8); + + case PB_WT_32BIT: + *size = 4; + return pb_read(stream, buf, 4); + + case PB_WT_STRING: + /* Calling read_raw_value with a PB_WT_STRING is an error. + * Explicitly handle this case and fallthrough to default to avoid + * compiler warnings. + */ + + default: PB_RETURN_ERROR(stream, "invalid wire_type"); + } +} + +/* Decode string length from stream and return a substream with limited length. + * Remember to close the substream using pb_close_string_substream(). + */ +bool checkreturn pb_make_string_substream(pb_istream_t *stream, pb_istream_t *substream) +{ + uint32_t size; + if (!pb_decode_varint32(stream, &size)) + return false; + + *substream = *stream; + if (substream->bytes_left < size) + PB_RETURN_ERROR(stream, "parent stream too short"); + + substream->bytes_left = (size_t)size; + stream->bytes_left -= (size_t)size; + return true; +} + +bool checkreturn pb_close_string_substream(pb_istream_t *stream, pb_istream_t *substream) +{ + if (substream->bytes_left) { + if (!pb_read(substream, NULL, substream->bytes_left)) + return false; + } + + stream->state = substream->state; + +#ifndef PB_NO_ERRMSG + stream->errmsg = substream->errmsg; +#endif + return true; +} + +/************************* + * Decode a single field * + *************************/ + +static bool checkreturn decode_basic_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iter_t *field) +{ + switch (PB_LTYPE(field->type)) + { + case PB_LTYPE_BOOL: + if (wire_type != PB_WT_VARINT && wire_type != PB_WT_PACKED) + PB_RETURN_ERROR(stream, "wrong wire type"); + + return pb_dec_bool(stream, field); + + case PB_LTYPE_VARINT: + case PB_LTYPE_UVARINT: + case PB_LTYPE_SVARINT: + if (wire_type != PB_WT_VARINT && wire_type != PB_WT_PACKED) + PB_RETURN_ERROR(stream, "wrong wire type"); + + return pb_dec_varint(stream, field); + + case PB_LTYPE_FIXED32: + if (wire_type != PB_WT_32BIT && wire_type != PB_WT_PACKED) + PB_RETURN_ERROR(stream, "wrong wire type"); + + return pb_decode_fixed32(stream, field->pData); + + case PB_LTYPE_FIXED64: + if (wire_type != PB_WT_64BIT && wire_type != PB_WT_PACKED) + PB_RETURN_ERROR(stream, "wrong wire type"); + +#ifdef PB_CONVERT_DOUBLE_FLOAT + if (field->data_size == sizeof(float)) + { + return pb_decode_double_as_float(stream, (float*)field->pData); + } +#endif + +#ifdef PB_WITHOUT_64BIT + PB_RETURN_ERROR(stream, "invalid data_size"); +#else + return pb_decode_fixed64(stream, field->pData); +#endif + + case PB_LTYPE_BYTES: + if (wire_type != PB_WT_STRING) + PB_RETURN_ERROR(stream, "wrong wire type"); + + return pb_dec_bytes(stream, field); + + case PB_LTYPE_STRING: + if (wire_type != PB_WT_STRING) + PB_RETURN_ERROR(stream, "wrong wire type"); + + return pb_dec_string(stream, field); + + case PB_LTYPE_SUBMESSAGE: + case PB_LTYPE_SUBMSG_W_CB: + if (wire_type != PB_WT_STRING) + PB_RETURN_ERROR(stream, "wrong wire type"); + + return pb_dec_submessage(stream, field); + + case PB_LTYPE_FIXED_LENGTH_BYTES: + if (wire_type != PB_WT_STRING) + PB_RETURN_ERROR(stream, "wrong wire type"); + + return pb_dec_fixed_length_bytes(stream, field); + + default: + PB_RETURN_ERROR(stream, "invalid field type"); + } +} + +static bool checkreturn decode_static_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iter_t *field) +{ + switch (PB_HTYPE(field->type)) + { + case PB_HTYPE_REQUIRED: + return decode_basic_field(stream, wire_type, field); + + case PB_HTYPE_OPTIONAL: + if (field->pSize != NULL) + *(bool*)field->pSize = true; + return decode_basic_field(stream, wire_type, field); + + case PB_HTYPE_REPEATED: + if (wire_type == PB_WT_STRING + && PB_LTYPE(field->type) <= PB_LTYPE_LAST_PACKABLE) + { + /* Packed array */ + bool status = true; + pb_istream_t substream; + pb_size_t *size = (pb_size_t*)field->pSize; + field->pData = (char*)field->pField + field->data_size * (*size); + + if (!pb_make_string_substream(stream, &substream)) + return false; + + while (substream.bytes_left > 0 && *size < field->array_size) + { + if (!decode_basic_field(&substream, PB_WT_PACKED, field)) + { + status = false; + break; + } + (*size)++; + field->pData = (char*)field->pData + field->data_size; + } + + if (substream.bytes_left != 0) + PB_RETURN_ERROR(stream, "array overflow"); + if (!pb_close_string_substream(stream, &substream)) + return false; + + return status; + } + else + { + /* Repeated field */ + pb_size_t *size = (pb_size_t*)field->pSize; + field->pData = (char*)field->pField + field->data_size * (*size); + + if ((*size)++ >= field->array_size) + PB_RETURN_ERROR(stream, "array overflow"); + + return decode_basic_field(stream, wire_type, field); + } + + case PB_HTYPE_ONEOF: + if (PB_LTYPE_IS_SUBMSG(field->type) && + *(pb_size_t*)field->pSize != field->tag) + { + /* We memset to zero so that any callbacks are set to NULL. + * This is because the callbacks might otherwise have values + * from some other union field. + * If callbacks are needed inside oneof field, use .proto + * option submsg_callback to have a separate callback function + * that can set the fields before submessage is decoded. + * pb_dec_submessage() will set any default values. */ + memset(field->pData, 0, (size_t)field->data_size); + + /* Set default values for the submessage fields. */ + if (field->submsg_desc->default_value != NULL || + field->submsg_desc->field_callback != NULL || + field->submsg_desc->submsg_info[0] != NULL) + { + pb_field_iter_t submsg_iter; + if (pb_field_iter_begin(&submsg_iter, field->submsg_desc, field->pData)) + { + if (!pb_message_set_to_defaults(&submsg_iter)) + PB_RETURN_ERROR(stream, "failed to set defaults"); + } + } + } + *(pb_size_t*)field->pSize = field->tag; + + return decode_basic_field(stream, wire_type, field); + + default: + PB_RETURN_ERROR(stream, "invalid field type"); + } +} + +#ifdef PB_ENABLE_MALLOC +/* Allocate storage for the field and store the pointer at iter->pData. + * array_size is the number of entries to reserve in an array. + * Zero size is not allowed, use pb_free() for releasing. + */ +static bool checkreturn allocate_field(pb_istream_t *stream, void *pData, size_t data_size, size_t array_size) +{ + void *ptr = *(void**)pData; + + if (data_size == 0 || array_size == 0) + PB_RETURN_ERROR(stream, "invalid size"); + +#ifdef __AVR__ + /* Workaround for AVR libc bug 53284: http://savannah.nongnu.org/bugs/?53284 + * Realloc to size of 1 byte can cause corruption of the malloc structures. + */ + if (data_size == 1 && array_size == 1) + { + data_size = 2; + } +#endif + + /* Check for multiplication overflows. + * This code avoids the costly division if the sizes are small enough. + * Multiplication is safe as long as only half of bits are set + * in either multiplicand. + */ + { + const size_t check_limit = (size_t)1 << (sizeof(size_t) * 4); + if (data_size >= check_limit || array_size >= check_limit) + { + const size_t size_max = (size_t)-1; + if (size_max / array_size < data_size) + { + PB_RETURN_ERROR(stream, "size too large"); + } + } + } + + /* Allocate new or expand previous allocation */ + /* Note: on failure the old pointer will remain in the structure, + * the message must be freed by caller also on error return. */ + ptr = pb_realloc(ptr, array_size * data_size); + if (ptr == NULL) + PB_RETURN_ERROR(stream, "realloc failed"); + + *(void**)pData = ptr; + return true; +} + +/* Clear a newly allocated item in case it contains a pointer, or is a submessage. */ +static void initialize_pointer_field(void *pItem, pb_field_iter_t *field) +{ + if (PB_LTYPE(field->type) == PB_LTYPE_STRING || + PB_LTYPE(field->type) == PB_LTYPE_BYTES) + { + *(void**)pItem = NULL; + } + else if (PB_LTYPE_IS_SUBMSG(field->type)) + { + /* We memset to zero so that any callbacks are set to NULL. + * Default values will be set by pb_dec_submessage(). */ + memset(pItem, 0, field->data_size); + } +} +#endif + +static bool checkreturn decode_pointer_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iter_t *field) +{ +#ifndef PB_ENABLE_MALLOC + PB_UNUSED(wire_type); + PB_UNUSED(field); + PB_RETURN_ERROR(stream, "no malloc support"); +#else + switch (PB_HTYPE(field->type)) + { + case PB_HTYPE_REQUIRED: + case PB_HTYPE_OPTIONAL: + case PB_HTYPE_ONEOF: + if (PB_LTYPE_IS_SUBMSG(field->type) && *(void**)field->pField != NULL) + { + /* Duplicate field, have to release the old allocation first. */ + /* FIXME: Does this work correctly for oneofs? */ + pb_release_single_field(field); + } + + if (PB_HTYPE(field->type) == PB_HTYPE_ONEOF) + { + *(pb_size_t*)field->pSize = field->tag; + } + + if (PB_LTYPE(field->type) == PB_LTYPE_STRING || + PB_LTYPE(field->type) == PB_LTYPE_BYTES) + { + /* pb_dec_string and pb_dec_bytes handle allocation themselves */ + field->pData = field->pField; + return decode_basic_field(stream, wire_type, field); + } + else + { + if (!allocate_field(stream, field->pField, field->data_size, 1)) + return false; + + field->pData = *(void**)field->pField; + initialize_pointer_field(field->pData, field); + return decode_basic_field(stream, wire_type, field); + } + + case PB_HTYPE_REPEATED: + if (wire_type == PB_WT_STRING + && PB_LTYPE(field->type) <= PB_LTYPE_LAST_PACKABLE) + { + /* Packed array, multiple items come in at once. */ + bool status = true; + pb_size_t *size = (pb_size_t*)field->pSize; + size_t allocated_size = *size; + pb_istream_t substream; + + if (!pb_make_string_substream(stream, &substream)) + return false; + + while (substream.bytes_left) + { + if (*size == PB_SIZE_MAX) + { +#ifndef PB_NO_ERRMSG + stream->errmsg = "too many array entries"; +#endif + status = false; + break; + } + + if ((size_t)*size + 1 > allocated_size) + { + /* Allocate more storage. This tries to guess the + * number of remaining entries. Round the division + * upwards. */ + size_t remain = (substream.bytes_left - 1) / field->data_size + 1; + if (remain < PB_SIZE_MAX - allocated_size) + allocated_size += remain; + else + allocated_size += 1; + + if (!allocate_field(&substream, field->pField, field->data_size, allocated_size)) + { + status = false; + break; + } + } + + /* Decode the array entry */ + field->pData = *(char**)field->pField + field->data_size * (*size); + if (field->pData == NULL) + { + /* Shouldn't happen, but satisfies static analyzers */ + status = false; + break; + } + initialize_pointer_field(field->pData, field); + if (!decode_basic_field(&substream, PB_WT_PACKED, field)) + { + status = false; + break; + } + + (*size)++; + } + if (!pb_close_string_substream(stream, &substream)) + return false; + + return status; + } + else + { + /* Normal repeated field, i.e. only one item at a time. */ + pb_size_t *size = (pb_size_t*)field->pSize; + + if (*size == PB_SIZE_MAX) + PB_RETURN_ERROR(stream, "too many array entries"); + + if (!allocate_field(stream, field->pField, field->data_size, (size_t)(*size + 1))) + return false; + + field->pData = *(char**)field->pField + field->data_size * (*size); + (*size)++; + initialize_pointer_field(field->pData, field); + return decode_basic_field(stream, wire_type, field); + } + + default: + PB_RETURN_ERROR(stream, "invalid field type"); + } +#endif +} + +static bool checkreturn decode_callback_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iter_t *field) +{ + if (!field->descriptor->field_callback) + return pb_skip_field(stream, wire_type); + + if (wire_type == PB_WT_STRING) + { + pb_istream_t substream; + size_t prev_bytes_left; + + if (!pb_make_string_substream(stream, &substream)) + return false; + + do + { + prev_bytes_left = substream.bytes_left; + if (!field->descriptor->field_callback(&substream, NULL, field)) + { + PB_SET_ERROR(stream, substream.errmsg ? substream.errmsg : "callback failed"); + return false; + } + } while (substream.bytes_left > 0 && substream.bytes_left < prev_bytes_left); + + if (!pb_close_string_substream(stream, &substream)) + return false; + + return true; + } + else + { + /* Copy the single scalar value to stack. + * This is required so that we can limit the stream length, + * which in turn allows to use same callback for packed and + * not-packed fields. */ + pb_istream_t substream; + pb_byte_t buffer[10]; + size_t size = sizeof(buffer); + + if (!read_raw_value(stream, wire_type, buffer, &size)) + return false; + substream = pb_istream_from_buffer(buffer, size); + + return field->descriptor->field_callback(&substream, NULL, field); + } +} + +static bool checkreturn decode_field(pb_istream_t *stream, pb_wire_type_t wire_type, pb_field_iter_t *field) +{ +#ifdef PB_ENABLE_MALLOC + /* When decoding an oneof field, check if there is old data that must be + * released first. */ + if (PB_HTYPE(field->type) == PB_HTYPE_ONEOF) + { + if (!pb_release_union_field(stream, field)) + return false; + } +#endif + + switch (PB_ATYPE(field->type)) + { + case PB_ATYPE_STATIC: + return decode_static_field(stream, wire_type, field); + + case PB_ATYPE_POINTER: + return decode_pointer_field(stream, wire_type, field); + + case PB_ATYPE_CALLBACK: + return decode_callback_field(stream, wire_type, field); + + default: + PB_RETURN_ERROR(stream, "invalid field type"); + } +} + +/* Default handler for extension fields. Expects to have a pb_msgdesc_t + * pointer in the extension->type->arg field, pointing to a message with + * only one field in it. */ +static bool checkreturn default_extension_decoder(pb_istream_t *stream, + pb_extension_t *extension, uint32_t tag, pb_wire_type_t wire_type) +{ + pb_field_iter_t iter; + + if (!pb_field_iter_begin_extension(&iter, extension)) + PB_RETURN_ERROR(stream, "invalid extension"); + + if (iter.tag != tag || !iter.message) + return true; + + extension->found = true; + return decode_field(stream, wire_type, &iter); +} + +/* Try to decode an unknown field as an extension field. Tries each extension + * decoder in turn, until one of them handles the field or loop ends. */ +static bool checkreturn decode_extension(pb_istream_t *stream, + uint32_t tag, pb_wire_type_t wire_type, pb_extension_t *extension) +{ + size_t pos = stream->bytes_left; + + while (extension != NULL && pos == stream->bytes_left) + { + bool status; + if (extension->type->decode) + status = extension->type->decode(stream, extension, tag, wire_type); + else + status = default_extension_decoder(stream, extension, tag, wire_type); + + if (!status) + return false; + + extension = extension->next; + } + + return true; +} + +/* Initialize message fields to default values, recursively */ +static bool pb_field_set_to_default(pb_field_iter_t *field) +{ + pb_type_t type; + type = field->type; + + if (PB_LTYPE(type) == PB_LTYPE_EXTENSION) + { + pb_extension_t *ext = *(pb_extension_t* const *)field->pData; + while (ext != NULL) + { + pb_field_iter_t ext_iter; + if (pb_field_iter_begin_extension(&ext_iter, ext)) + { + ext->found = false; + if (!pb_message_set_to_defaults(&ext_iter)) + return false; + } + ext = ext->next; + } + } + else if (PB_ATYPE(type) == PB_ATYPE_STATIC) + { + bool init_data = true; + if (PB_HTYPE(type) == PB_HTYPE_OPTIONAL && field->pSize != NULL) + { + /* Set has_field to false. Still initialize the optional field + * itself also. */ + *(bool*)field->pSize = false; + } + else if (PB_HTYPE(type) == PB_HTYPE_REPEATED || + PB_HTYPE(type) == PB_HTYPE_ONEOF) + { + /* REPEATED: Set array count to 0, no need to initialize contents. + ONEOF: Set which_field to 0. */ + *(pb_size_t*)field->pSize = 0; + init_data = false; + } + + if (init_data) + { + if (PB_LTYPE_IS_SUBMSG(field->type) && + (field->submsg_desc->default_value != NULL || + field->submsg_desc->field_callback != NULL || + field->submsg_desc->submsg_info[0] != NULL)) + { + /* Initialize submessage to defaults. + * Only needed if it has default values + * or callback/submessage fields. */ + pb_field_iter_t submsg_iter; + if (pb_field_iter_begin(&submsg_iter, field->submsg_desc, field->pData)) + { + if (!pb_message_set_to_defaults(&submsg_iter)) + return false; + } + } + else + { + /* Initialize to zeros */ + memset(field->pData, 0, (size_t)field->data_size); + } + } + } + else if (PB_ATYPE(type) == PB_ATYPE_POINTER) + { + /* Initialize the pointer to NULL. */ + *(void**)field->pField = NULL; + + /* Initialize array count to 0. */ + if (PB_HTYPE(type) == PB_HTYPE_REPEATED || + PB_HTYPE(type) == PB_HTYPE_ONEOF) + { + *(pb_size_t*)field->pSize = 0; + } + } + else if (PB_ATYPE(type) == PB_ATYPE_CALLBACK) + { + /* Don't overwrite callback */ + } + + return true; +} + +static bool pb_message_set_to_defaults(pb_field_iter_t *iter) +{ + pb_istream_t defstream = PB_ISTREAM_EMPTY; + uint32_t tag = 0; + pb_wire_type_t wire_type = PB_WT_VARINT; + bool eof; + + if (iter->descriptor->default_value) + { + defstream = pb_istream_from_buffer(iter->descriptor->default_value, (size_t)-1); + if (!pb_decode_tag(&defstream, &wire_type, &tag, &eof)) + return false; + } + + do + { + if (!pb_field_set_to_default(iter)) + return false; + + if (tag != 0 && iter->tag == tag) + { + /* We have a default value for this field in the defstream */ + if (!decode_field(&defstream, wire_type, iter)) + return false; + if (!pb_decode_tag(&defstream, &wire_type, &tag, &eof)) + return false; + + if (iter->pSize) + *(bool*)iter->pSize = false; + } + } while (pb_field_iter_next(iter)); + + return true; +} + +/********************* + * Decode all fields * + *********************/ + +static bool checkreturn pb_decode_inner(pb_istream_t *stream, const pb_msgdesc_t *fields, void *dest_struct, unsigned int flags) +{ + uint32_t extension_range_start = 0; + pb_extension_t *extensions = NULL; + + /* 'fixed_count_field' and 'fixed_count_size' track position of a repeated fixed + * count field. This can only handle _one_ repeated fixed count field that + * is unpacked and unordered among other (non repeated fixed count) fields. + */ + pb_size_t fixed_count_field = PB_SIZE_MAX; + pb_size_t fixed_count_size = 0; + pb_size_t fixed_count_total_size = 0; + + pb_fields_seen_t fields_seen = {{0, 0}}; + const uint32_t allbits = ~(uint32_t)0; + pb_field_iter_t iter; + + if (pb_field_iter_begin(&iter, fields, dest_struct)) + { + if ((flags & PB_DECODE_NOINIT) == 0) + { + if (!pb_message_set_to_defaults(&iter)) + PB_RETURN_ERROR(stream, "failed to set defaults"); + } + } + + while (stream->bytes_left) + { + uint32_t tag; + pb_wire_type_t wire_type; + bool eof; + + if (!pb_decode_tag(stream, &wire_type, &tag, &eof)) + { + if (eof) + break; + else + return false; + } + + if (tag == 0) + { + if (flags & PB_DECODE_NULLTERMINATED) + { + break; + } + else + { + PB_RETURN_ERROR(stream, "zero tag"); + } + } + + if (!pb_field_iter_find(&iter, tag) || PB_LTYPE(iter.type) == PB_LTYPE_EXTENSION) + { + /* No match found, check if it matches an extension. */ + if (extension_range_start == 0) + { + if (pb_field_iter_find_extension(&iter)) + { + extensions = *(pb_extension_t* const *)iter.pData; + extension_range_start = iter.tag; + } + + if (!extensions) + { + extension_range_start = (uint32_t)-1; + } + } + + if (tag >= extension_range_start) + { + size_t pos = stream->bytes_left; + + if (!decode_extension(stream, tag, wire_type, extensions)) + return false; + + if (pos != stream->bytes_left) + { + /* The field was handled */ + continue; + } + } + + /* No match found, skip data */ + if (!pb_skip_field(stream, wire_type)) + return false; + continue; + } + + /* If a repeated fixed count field was found, get size from + * 'fixed_count_field' as there is no counter contained in the struct. + */ + if (PB_HTYPE(iter.type) == PB_HTYPE_REPEATED && iter.pSize == &iter.array_size) + { + if (fixed_count_field != iter.index) { + /* If the new fixed count field does not match the previous one, + * check that the previous one is NULL or that it finished + * receiving all the expected data. + */ + if (fixed_count_field != PB_SIZE_MAX && + fixed_count_size != fixed_count_total_size) + { + PB_RETURN_ERROR(stream, "wrong size for fixed count field"); + } + + fixed_count_field = iter.index; + fixed_count_size = 0; + fixed_count_total_size = iter.array_size; + } + + iter.pSize = &fixed_count_size; + } + + if (PB_HTYPE(iter.type) == PB_HTYPE_REQUIRED + && iter.required_field_index < PB_MAX_REQUIRED_FIELDS) + { + uint32_t tmp = ((uint32_t)1 << (iter.required_field_index & 31)); + fields_seen.bitfield[iter.required_field_index >> 5] |= tmp; + } + + if (!decode_field(stream, wire_type, &iter)) + return false; + } + + /* Check that all elements of the last decoded fixed count field were present. */ + if (fixed_count_field != PB_SIZE_MAX && + fixed_count_size != fixed_count_total_size) + { + PB_RETURN_ERROR(stream, "wrong size for fixed count field"); + } + + /* Check that all required fields were present. */ + { + pb_size_t req_field_count = iter.descriptor->required_field_count; + + if (req_field_count > 0) + { + pb_size_t i; + + if (req_field_count > PB_MAX_REQUIRED_FIELDS) + req_field_count = PB_MAX_REQUIRED_FIELDS; + + /* Check the whole words */ + for (i = 0; i < (req_field_count >> 5); i++) + { + if (fields_seen.bitfield[i] != allbits) + PB_RETURN_ERROR(stream, "missing required field"); + } + + /* Check the remaining bits (if any) */ + if ((req_field_count & 31) != 0) + { + if (fields_seen.bitfield[req_field_count >> 5] != + (allbits >> (uint_least8_t)(32 - (req_field_count & 31)))) + { + PB_RETURN_ERROR(stream, "missing required field"); + } + } + } + } + + return true; +} + +bool checkreturn pb_decode_ex(pb_istream_t *stream, const pb_msgdesc_t *fields, void *dest_struct, unsigned int flags) +{ + bool status; + + if ((flags & PB_DECODE_DELIMITED) == 0) + { + status = pb_decode_inner(stream, fields, dest_struct, flags); + } + else + { + pb_istream_t substream; + if (!pb_make_string_substream(stream, &substream)) + return false; + + status = pb_decode_inner(&substream, fields, dest_struct, flags); + + if (!pb_close_string_substream(stream, &substream)) + return false; + } + +#ifdef PB_ENABLE_MALLOC + if (!status) + pb_release(fields, dest_struct); +#endif + + return status; +} + +bool checkreturn pb_decode(pb_istream_t *stream, const pb_msgdesc_t *fields, void *dest_struct) +{ + bool status; + + status = pb_decode_inner(stream, fields, dest_struct, 0); + +#ifdef PB_ENABLE_MALLOC + if (!status) + pb_release(fields, dest_struct); +#endif + + return status; +} + +#ifdef PB_ENABLE_MALLOC +/* Given an oneof field, if there has already been a field inside this oneof, + * release it before overwriting with a different one. */ +static bool pb_release_union_field(pb_istream_t *stream, pb_field_iter_t *field) +{ + pb_field_iter_t old_field = *field; + pb_size_t old_tag = *(pb_size_t*)field->pSize; /* Previous which_ value */ + pb_size_t new_tag = field->tag; /* New which_ value */ + + if (old_tag == 0) + return true; /* Ok, no old data in union */ + + if (old_tag == new_tag) + return true; /* Ok, old data is of same type => merge */ + + /* Release old data. The find can fail if the message struct contains + * invalid data. */ + if (!pb_field_iter_find(&old_field, old_tag)) + PB_RETURN_ERROR(stream, "invalid union tag"); + + pb_release_single_field(&old_field); + + if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) + { + /* Initialize the pointer to NULL to make sure it is valid + * even in case of error return. */ + *(void**)field->pField = NULL; + field->pData = NULL; + } + + return true; +} + +static void pb_release_single_field(pb_field_iter_t *field) +{ + pb_type_t type; + type = field->type; + + if (PB_HTYPE(type) == PB_HTYPE_ONEOF) + { + if (*(pb_size_t*)field->pSize != field->tag) + return; /* This is not the current field in the union */ + } + + /* Release anything contained inside an extension or submsg. + * This has to be done even if the submsg itself is statically + * allocated. */ + if (PB_LTYPE(type) == PB_LTYPE_EXTENSION) + { + /* Release fields from all extensions in the linked list */ + pb_extension_t *ext = *(pb_extension_t**)field->pData; + while (ext != NULL) + { + pb_field_iter_t ext_iter; + if (pb_field_iter_begin_extension(&ext_iter, ext)) + { + pb_release_single_field(&ext_iter); + } + ext = ext->next; + } + } + else if (PB_LTYPE_IS_SUBMSG(type) && PB_ATYPE(type) != PB_ATYPE_CALLBACK) + { + /* Release fields in submessage or submsg array */ + pb_size_t count = 1; + + if (PB_ATYPE(type) == PB_ATYPE_POINTER) + { + field->pData = *(void**)field->pField; + } + else + { + field->pData = field->pField; + } + + if (PB_HTYPE(type) == PB_HTYPE_REPEATED) + { + count = *(pb_size_t*)field->pSize; + + if (PB_ATYPE(type) == PB_ATYPE_STATIC && count > field->array_size) + { + /* Protect against corrupted _count fields */ + count = field->array_size; + } + } + + if (field->pData) + { + for (; count > 0; count--) + { + pb_release(field->submsg_desc, field->pData); + field->pData = (char*)field->pData + field->data_size; + } + } + } + + if (PB_ATYPE(type) == PB_ATYPE_POINTER) + { + if (PB_HTYPE(type) == PB_HTYPE_REPEATED && + (PB_LTYPE(type) == PB_LTYPE_STRING || + PB_LTYPE(type) == PB_LTYPE_BYTES)) + { + /* Release entries in repeated string or bytes array */ + void **pItem = *(void***)field->pField; + pb_size_t count = *(pb_size_t*)field->pSize; + for (; count > 0; count--) + { + pb_free(*pItem); + *pItem++ = NULL; + } + } + + if (PB_HTYPE(type) == PB_HTYPE_REPEATED) + { + /* We are going to release the array, so set the size to 0 */ + *(pb_size_t*)field->pSize = 0; + } + + /* Release main pointer */ + pb_free(*(void**)field->pField); + *(void**)field->pField = NULL; + } +} + +void pb_release(const pb_msgdesc_t *fields, void *dest_struct) +{ + pb_field_iter_t iter; + + if (!dest_struct) + return; /* Ignore NULL pointers, similar to free() */ + + if (!pb_field_iter_begin(&iter, fields, dest_struct)) + return; /* Empty message type */ + + do + { + pb_release_single_field(&iter); + } while (pb_field_iter_next(&iter)); +} +#else +void pb_release(const pb_msgdesc_t *fields, void *dest_struct) +{ + /* Nothing to release without PB_ENABLE_MALLOC. */ + PB_UNUSED(fields); + PB_UNUSED(dest_struct); +} +#endif + +/* Field decoders */ + +bool pb_decode_bool(pb_istream_t *stream, bool *dest) +{ + uint32_t value; + if (!pb_decode_varint32(stream, &value)) + return false; + + *(bool*)dest = (value != 0); + return true; +} + +bool pb_decode_svarint(pb_istream_t *stream, pb_int64_t *dest) +{ + pb_uint64_t value; + if (!pb_decode_varint(stream, &value)) + return false; + + if (value & 1) + *dest = (pb_int64_t)(~(value >> 1)); + else + *dest = (pb_int64_t)(value >> 1); + + return true; +} + +bool pb_decode_fixed32(pb_istream_t *stream, void *dest) +{ + union { + uint32_t fixed32; + pb_byte_t bytes[4]; + } u; + + if (!pb_read(stream, u.bytes, 4)) + return false; + +#if defined(PB_LITTLE_ENDIAN_8BIT) && PB_LITTLE_ENDIAN_8BIT == 1 + /* fast path - if we know that we're on little endian, assign directly */ + *(uint32_t*)dest = u.fixed32; +#else + *(uint32_t*)dest = ((uint32_t)u.bytes[0] << 0) | + ((uint32_t)u.bytes[1] << 8) | + ((uint32_t)u.bytes[2] << 16) | + ((uint32_t)u.bytes[3] << 24); +#endif + return true; +} + +#ifndef PB_WITHOUT_64BIT +bool pb_decode_fixed64(pb_istream_t *stream, void *dest) +{ + union { + uint64_t fixed64; + pb_byte_t bytes[8]; + } u; + + if (!pb_read(stream, u.bytes, 8)) + return false; + +#if defined(PB_LITTLE_ENDIAN_8BIT) && PB_LITTLE_ENDIAN_8BIT == 1 + /* fast path - if we know that we're on little endian, assign directly */ + *(uint64_t*)dest = u.fixed64; +#else + *(uint64_t*)dest = ((uint64_t)u.bytes[0] << 0) | + ((uint64_t)u.bytes[1] << 8) | + ((uint64_t)u.bytes[2] << 16) | + ((uint64_t)u.bytes[3] << 24) | + ((uint64_t)u.bytes[4] << 32) | + ((uint64_t)u.bytes[5] << 40) | + ((uint64_t)u.bytes[6] << 48) | + ((uint64_t)u.bytes[7] << 56); +#endif + return true; +} +#endif + +static bool checkreturn pb_dec_bool(pb_istream_t *stream, const pb_field_iter_t *field) +{ + return pb_decode_bool(stream, (bool*)field->pData); +} + +static bool checkreturn pb_dec_varint(pb_istream_t *stream, const pb_field_iter_t *field) +{ + if (PB_LTYPE(field->type) == PB_LTYPE_UVARINT) + { + pb_uint64_t value, clamped; + if (!pb_decode_varint(stream, &value)) + return false; + + /* Cast to the proper field size, while checking for overflows */ + if (field->data_size == sizeof(pb_uint64_t)) + clamped = *(pb_uint64_t*)field->pData = value; + else if (field->data_size == sizeof(uint32_t)) + clamped = *(uint32_t*)field->pData = (uint32_t)value; + else if (field->data_size == sizeof(uint_least16_t)) + clamped = *(uint_least16_t*)field->pData = (uint_least16_t)value; + else if (field->data_size == sizeof(uint_least8_t)) + clamped = *(uint_least8_t*)field->pData = (uint_least8_t)value; + else + PB_RETURN_ERROR(stream, "invalid data_size"); + + if (clamped != value) + PB_RETURN_ERROR(stream, "integer too large"); + + return true; + } + else + { + pb_uint64_t value; + pb_int64_t svalue; + pb_int64_t clamped; + + if (PB_LTYPE(field->type) == PB_LTYPE_SVARINT) + { + if (!pb_decode_svarint(stream, &svalue)) + return false; + } + else + { + if (!pb_decode_varint(stream, &value)) + return false; + + /* See issue 97: Google's C++ protobuf allows negative varint values to + * be cast as int32_t, instead of the int64_t that should be used when + * encoding. Nanopb versions before 0.2.5 had a bug in encoding. In order to + * not break decoding of such messages, we cast <=32 bit fields to + * int32_t first to get the sign correct. + */ + if (field->data_size == sizeof(pb_int64_t)) + svalue = (pb_int64_t)value; + else + svalue = (int32_t)value; + } + + /* Cast to the proper field size, while checking for overflows */ + if (field->data_size == sizeof(pb_int64_t)) + clamped = *(pb_int64_t*)field->pData = svalue; + else if (field->data_size == sizeof(int32_t)) + clamped = *(int32_t*)field->pData = (int32_t)svalue; + else if (field->data_size == sizeof(int_least16_t)) + clamped = *(int_least16_t*)field->pData = (int_least16_t)svalue; + else if (field->data_size == sizeof(int_least8_t)) + clamped = *(int_least8_t*)field->pData = (int_least8_t)svalue; + else + PB_RETURN_ERROR(stream, "invalid data_size"); + + if (clamped != svalue) + PB_RETURN_ERROR(stream, "integer too large"); + + return true; + } +} + +static bool checkreturn pb_dec_bytes(pb_istream_t *stream, const pb_field_iter_t *field) +{ + uint32_t size; + size_t alloc_size; + pb_bytes_array_t *dest; + + if (!pb_decode_varint32(stream, &size)) + return false; + + if (size > PB_SIZE_MAX) + PB_RETURN_ERROR(stream, "bytes overflow"); + + alloc_size = PB_BYTES_ARRAY_T_ALLOCSIZE(size); + if (size > alloc_size) + PB_RETURN_ERROR(stream, "size too large"); + + if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) + { +#ifndef PB_ENABLE_MALLOC + PB_RETURN_ERROR(stream, "no malloc support"); +#else + if (stream->bytes_left < size) + PB_RETURN_ERROR(stream, "end-of-stream"); + + if (!allocate_field(stream, field->pData, alloc_size, 1)) + return false; + dest = *(pb_bytes_array_t**)field->pData; +#endif + } + else + { + if (alloc_size > field->data_size) + PB_RETURN_ERROR(stream, "bytes overflow"); + dest = (pb_bytes_array_t*)field->pData; + } + + dest->size = (pb_size_t)size; + return pb_read(stream, dest->bytes, (size_t)size); +} + +static bool checkreturn pb_dec_string(pb_istream_t *stream, const pb_field_iter_t *field) +{ + uint32_t size; + size_t alloc_size; + pb_byte_t *dest = (pb_byte_t*)field->pData; + + if (!pb_decode_varint32(stream, &size)) + return false; + + if (size == (uint32_t)-1) + PB_RETURN_ERROR(stream, "size too large"); + + /* Space for null terminator */ + alloc_size = (size_t)(size + 1); + + if (alloc_size < size) + PB_RETURN_ERROR(stream, "size too large"); + + if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) + { +#ifndef PB_ENABLE_MALLOC + PB_RETURN_ERROR(stream, "no malloc support"); +#else + if (stream->bytes_left < size) + PB_RETURN_ERROR(stream, "end-of-stream"); + + if (!allocate_field(stream, field->pData, alloc_size, 1)) + return false; + dest = *(pb_byte_t**)field->pData; +#endif + } + else + { + if (alloc_size > field->data_size) + PB_RETURN_ERROR(stream, "string overflow"); + } + + dest[size] = 0; + + if (!pb_read(stream, dest, (size_t)size)) + return false; + +#ifdef PB_VALIDATE_UTF8 + if (!pb_validate_utf8((const char*)dest)) + PB_RETURN_ERROR(stream, "invalid utf8"); +#endif + + return true; +} + +static bool checkreturn pb_dec_submessage(pb_istream_t *stream, const pb_field_iter_t *field) +{ + bool status = true; + bool submsg_consumed = false; + pb_istream_t substream; + + if (!pb_make_string_substream(stream, &substream)) + return false; + + if (field->submsg_desc == NULL) + PB_RETURN_ERROR(stream, "invalid field descriptor"); + + /* Submessages can have a separate message-level callback that is called + * before decoding the message. Typically it is used to set callback fields + * inside oneofs. */ + if (PB_LTYPE(field->type) == PB_LTYPE_SUBMSG_W_CB && field->pSize != NULL) + { + /* Message callback is stored right before pSize. */ + pb_callback_t *callback = (pb_callback_t*)field->pSize - 1; + if (callback->funcs.decode) + { + status = callback->funcs.decode(&substream, field, &callback->arg); + + if (substream.bytes_left == 0) + { + submsg_consumed = true; + } + } + } + + /* Now decode the submessage contents */ + if (status && !submsg_consumed) + { + unsigned int flags = 0; + + /* Static required/optional fields are already initialized by top-level + * pb_decode(), no need to initialize them again. */ + if (PB_ATYPE(field->type) == PB_ATYPE_STATIC && + PB_HTYPE(field->type) != PB_HTYPE_REPEATED) + { + flags = PB_DECODE_NOINIT; + } + + status = pb_decode_inner(&substream, field->submsg_desc, field->pData, flags); + } + + if (!pb_close_string_substream(stream, &substream)) + return false; + + return status; +} + +static bool checkreturn pb_dec_fixed_length_bytes(pb_istream_t *stream, const pb_field_iter_t *field) +{ + uint32_t size; + + if (!pb_decode_varint32(stream, &size)) + return false; + + if (size > PB_SIZE_MAX) + PB_RETURN_ERROR(stream, "bytes overflow"); + + if (size == 0) + { + /* As a special case, treat empty bytes string as all zeros for fixed_length_bytes. */ + memset(field->pData, 0, (size_t)field->data_size); + return true; + } + + if (size != field->data_size) + PB_RETURN_ERROR(stream, "incorrect fixed length bytes size"); + + return pb_read(stream, (pb_byte_t*)field->pData, (size_t)field->data_size); +} + +#ifdef PB_CONVERT_DOUBLE_FLOAT +bool pb_decode_double_as_float(pb_istream_t *stream, float *dest) +{ + uint_least8_t sign; + int exponent; + uint32_t mantissa; + uint64_t value; + union { float f; uint32_t i; } out; + + if (!pb_decode_fixed64(stream, &value)) + return false; + + /* Decompose input value */ + sign = (uint_least8_t)((value >> 63) & 1); + exponent = (int)((value >> 52) & 0x7FF) - 1023; + mantissa = (value >> 28) & 0xFFFFFF; /* Highest 24 bits */ + + /* Figure if value is in range representable by floats. */ + if (exponent == 1024) + { + /* Special value */ + exponent = 128; + mantissa >>= 1; + } + else + { + if (exponent > 127) + { + /* Too large, convert to infinity */ + exponent = 128; + mantissa = 0; + } + else if (exponent < -150) + { + /* Too small, convert to zero */ + exponent = -127; + mantissa = 0; + } + else if (exponent < -126) + { + /* Denormalized */ + mantissa |= 0x1000000; + mantissa >>= (-126 - exponent); + exponent = -127; + } + + /* Round off mantissa */ + mantissa = (mantissa + 1) >> 1; + + /* Check if mantissa went over 2.0 */ + if (mantissa & 0x800000) + { + exponent += 1; + mantissa &= 0x7FFFFF; + mantissa >>= 1; + } + } + + /* Combine fields */ + out.i = mantissa; + out.i |= (uint32_t)(exponent + 127) << 23; + out.i |= (uint32_t)sign << 31; + + *dest = out.f; + return true; +} +#endif diff --git a/wpiutil/src/main/native/thirdparty/nanopb/src/pb_encode.cpp b/wpiutil/src/main/native/thirdparty/nanopb/src/pb_encode.cpp new file mode 100644 index 0000000000..270a721863 --- /dev/null +++ b/wpiutil/src/main/native/thirdparty/nanopb/src/pb_encode.cpp @@ -0,0 +1,1003 @@ +/* pb_encode.c -- encode a protobuf using minimal resources + * + * Modified for WPILib Use + * + * 2011 Petteri Aimonen + */ + +#include "pb.h" +#include "pb_encode.h" +#include "pb_common.h" + +/* Use the GCC warn_unused_result attribute to check that all return values + * are propagated correctly. On other compilers, gcc before 3.4.0 and iar + * before 9.40.1 just ignore the annotation. + */ +#if (defined(__GNUC__) && ((__GNUC__ > 3) || (__GNUC__ == 3 && __GNUC_MINOR__ >= 4))) || \ + (defined(__IAR_SYSTEMS_ICC__) && (__VER__ >= 9040001)) + #define checkreturn __attribute__((warn_unused_result)) +#else + #define checkreturn +#endif + +/************************************** + * Declarations internal to this file * + **************************************/ +static bool checkreturn buf_write(pb_ostream_t *stream, const pb_byte_t *buf, size_t count); +static bool checkreturn encode_array(pb_ostream_t *stream, pb_field_iter_t *field); +static bool checkreturn pb_check_proto3_default_value(const pb_field_iter_t *field); +static bool checkreturn encode_basic_field(pb_ostream_t *stream, const pb_field_iter_t *field); +static bool checkreturn encode_callback_field(pb_ostream_t *stream, const pb_field_iter_t *field); +static bool checkreturn encode_field(pb_ostream_t *stream, pb_field_iter_t *field); +static bool checkreturn encode_extension_field(pb_ostream_t *stream, const pb_field_iter_t *field); +static bool checkreturn default_extension_encoder(pb_ostream_t *stream, const pb_extension_t *extension); +static bool checkreturn pb_encode_varint_32(pb_ostream_t *stream, uint32_t low, uint32_t high); +static bool checkreturn pb_enc_bool(pb_ostream_t *stream, const pb_field_iter_t *field); +static bool checkreturn pb_enc_varint(pb_ostream_t *stream, const pb_field_iter_t *field); +static bool checkreturn pb_enc_fixed(pb_ostream_t *stream, const pb_field_iter_t *field); +static bool checkreturn pb_enc_bytes(pb_ostream_t *stream, const pb_field_iter_t *field); +static bool checkreturn pb_enc_string(pb_ostream_t *stream, const pb_field_iter_t *field); +static bool checkreturn pb_enc_submessage(pb_ostream_t *stream, const pb_field_iter_t *field); +static bool checkreturn pb_enc_fixed_length_bytes(pb_ostream_t *stream, const pb_field_iter_t *field); + +#ifdef PB_WITHOUT_64BIT +#define pb_int64_t int32_t +#define pb_uint64_t uint32_t +#else +#define pb_int64_t int64_t +#define pb_uint64_t uint64_t +#endif + +/******************************* + * pb_ostream_t implementation * + *******************************/ + +static bool checkreturn buf_write(pb_ostream_t *stream, const pb_byte_t *buf, size_t count) +{ + pb_byte_t *dest = (pb_byte_t*)stream->state; + stream->state = dest + count; + + memcpy(dest, buf, count * sizeof(pb_byte_t)); + + return true; +} + +pb_ostream_t pb_ostream_from_buffer(pb_byte_t *buf, size_t bufsize) +{ + pb_ostream_t stream; +#ifdef PB_BUFFER_ONLY + /* In PB_BUFFER_ONLY configuration the callback pointer is just int*. + * NULL pointer marks a sizing field, so put a non-NULL value to mark a buffer stream. + */ + static const int marker = 0; + stream.callback = ▮ +#else + stream.callback = &buf_write; +#endif + stream.state = buf; + stream.max_size = bufsize; + stream.bytes_written = 0; +#ifndef PB_NO_ERRMSG + stream.errmsg = NULL; +#endif + return stream; +} + +bool checkreturn pb_write(pb_ostream_t *stream, const pb_byte_t *buf, size_t count) +{ + if (count > 0 && stream->callback != NULL) + { + if (stream->bytes_written + count < stream->bytes_written || + stream->bytes_written + count > stream->max_size) + { + PB_RETURN_ERROR(stream, "stream full"); + } + +#ifdef PB_BUFFER_ONLY + if (!buf_write(stream, buf, count)) + PB_RETURN_ERROR(stream, "io error"); +#else + if (!stream->callback(stream, buf, count)) + PB_RETURN_ERROR(stream, "io error"); +#endif + } + + stream->bytes_written += count; + return true; +} + +/************************* + * Encode a single field * + *************************/ + +/* Read a bool value without causing undefined behavior even if the value + * is invalid. See issue #434 and + * https://stackoverflow.com/questions/27661768/weird-results-for-conditional + */ +static bool safe_read_bool(const void *pSize) +{ + const char *p = (const char *)pSize; + size_t i; + for (i = 0; i < sizeof(bool); i++) + { + if (p[i] != 0) + return true; + } + return false; +} + +/* Encode a static array. Handles the size calculations and possible packing. */ +static bool checkreturn encode_array(pb_ostream_t *stream, pb_field_iter_t *field) +{ + pb_size_t i; + pb_size_t count; +#ifndef PB_ENCODE_ARRAYS_UNPACKED + size_t size; +#endif + + count = *(pb_size_t*)field->pSize; + + if (count == 0) + return true; + + if (PB_ATYPE(field->type) != PB_ATYPE_POINTER && count > field->array_size) + PB_RETURN_ERROR(stream, "array max size exceeded"); + +#ifndef PB_ENCODE_ARRAYS_UNPACKED + /* We always pack arrays if the datatype allows it. */ + if (PB_LTYPE(field->type) <= PB_LTYPE_LAST_PACKABLE) + { + if (!pb_encode_tag(stream, PB_WT_STRING, field->tag)) + return false; + + /* Determine the total size of packed array. */ + if (PB_LTYPE(field->type) == PB_LTYPE_FIXED32) + { + size = 4 * (size_t)count; + } + else if (PB_LTYPE(field->type) == PB_LTYPE_FIXED64) + { + size = 8 * (size_t)count; + } + else + { + pb_ostream_t sizestream = PB_OSTREAM_SIZING; + void *pData_orig = field->pData; + for (i = 0; i < count; i++) + { + if (!pb_enc_varint(&sizestream, field)) + PB_RETURN_ERROR(stream, PB_GET_ERROR(&sizestream)); + field->pData = (char*)field->pData + field->data_size; + } + field->pData = pData_orig; + size = sizestream.bytes_written; + } + + if (!pb_encode_varint(stream, (pb_uint64_t)size)) + return false; + + if (stream->callback == NULL) + return pb_write(stream, NULL, size); /* Just sizing.. */ + + /* Write the data */ + for (i = 0; i < count; i++) + { + if (PB_LTYPE(field->type) == PB_LTYPE_FIXED32 || PB_LTYPE(field->type) == PB_LTYPE_FIXED64) + { + if (!pb_enc_fixed(stream, field)) + return false; + } + else + { + if (!pb_enc_varint(stream, field)) + return false; + } + + field->pData = (char*)field->pData + field->data_size; + } + } + else /* Unpacked fields */ +#endif + { + for (i = 0; i < count; i++) + { + /* Normally the data is stored directly in the array entries, but + * for pointer-type string and bytes fields, the array entries are + * actually pointers themselves also. So we have to dereference once + * more to get to the actual data. */ + if (PB_ATYPE(field->type) == PB_ATYPE_POINTER && + (PB_LTYPE(field->type) == PB_LTYPE_STRING || + PB_LTYPE(field->type) == PB_LTYPE_BYTES)) + { + bool status; + void *pData_orig = field->pData; + field->pData = *(void* const*)field->pData; + + if (!field->pData) + { + /* Null pointer in array is treated as empty string / bytes */ + status = pb_encode_tag_for_field(stream, field) && + pb_encode_varint(stream, 0); + } + else + { + status = encode_basic_field(stream, field); + } + + field->pData = pData_orig; + + if (!status) + return false; + } + else + { + if (!encode_basic_field(stream, field)) + return false; + } + field->pData = (char*)field->pData + field->data_size; + } + } + + return true; +} + +/* In proto3, all fields are optional and are only encoded if their value is "non-zero". + * This function implements the check for the zero value. */ +static bool checkreturn pb_check_proto3_default_value(const pb_field_iter_t *field) +{ + pb_type_t type = field->type; + + if (PB_ATYPE(type) == PB_ATYPE_STATIC) + { + if (PB_HTYPE(type) == PB_HTYPE_REQUIRED) + { + /* Required proto2 fields inside proto3 submessage, pretty rare case */ + return false; + } + else if (PB_HTYPE(type) == PB_HTYPE_REPEATED) + { + /* Repeated fields inside proto3 submessage: present if count != 0 */ + return *(const pb_size_t*)field->pSize == 0; + } + else if (PB_HTYPE(type) == PB_HTYPE_ONEOF) + { + /* Oneof fields */ + return *(const pb_size_t*)field->pSize == 0; + } + else if (PB_HTYPE(type) == PB_HTYPE_OPTIONAL && field->pSize != NULL) + { + /* Proto2 optional fields inside proto3 message, or proto3 + * submessage fields. */ + return safe_read_bool(field->pSize) == false; + } + else if (field->descriptor->default_value) + { + /* Proto3 messages do not have default values, but proto2 messages + * can contain optional fields without has_fields (generator option 'proto3'). + * In this case they must always be encoded, to make sure that the + * non-zero default value is overwritten. + */ + return false; + } + + /* Rest is proto3 singular fields */ + if (PB_LTYPE(type) <= PB_LTYPE_LAST_PACKABLE) + { + /* Simple integer / float fields */ + pb_size_t i; + const char *p = (const char*)field->pData; + for (i = 0; i < field->data_size; i++) + { + if (p[i] != 0) + { + return false; + } + } + + return true; + } + else if (PB_LTYPE(type) == PB_LTYPE_BYTES) + { + const pb_bytes_array_t *bytes = (const pb_bytes_array_t*)field->pData; + return bytes->size == 0; + } + else if (PB_LTYPE(type) == PB_LTYPE_STRING) + { + return *(const char*)field->pData == '\0'; + } + else if (PB_LTYPE(type) == PB_LTYPE_FIXED_LENGTH_BYTES) + { + /* Fixed length bytes is only empty if its length is fixed + * as 0. Which would be pretty strange, but we can check + * it anyway. */ + return field->data_size == 0; + } + else if (PB_LTYPE_IS_SUBMSG(type)) + { + /* Check all fields in the submessage to find if any of them + * are non-zero. The comparison cannot be done byte-per-byte + * because the C struct may contain padding bytes that must + * be skipped. Note that usually proto3 submessages have + * a separate has_field that is checked earlier in this if. + */ + pb_field_iter_t iter; + if (pb_field_iter_begin(&iter, field->submsg_desc, field->pData)) + { + do + { + if (!pb_check_proto3_default_value(&iter)) + { + return false; + } + } while (pb_field_iter_next(&iter)); + } + return true; + } + } + else if (PB_ATYPE(type) == PB_ATYPE_POINTER) + { + return field->pData == NULL; + } + else if (PB_ATYPE(type) == PB_ATYPE_CALLBACK) + { + if (PB_LTYPE(type) == PB_LTYPE_EXTENSION) + { + const pb_extension_t *extension = *(const pb_extension_t* const *)field->pData; + return extension == NULL; + } + else if (field->descriptor->field_callback == pb_default_field_callback) + { + pb_callback_t *pCallback = (pb_callback_t*)field->pData; + return pCallback->funcs.encode == NULL; + } + else + { + return field->descriptor->field_callback == NULL; + } + } + + return false; /* Not typically reached, safe default for weird special cases. */ +} + +/* Encode a field with static or pointer allocation, i.e. one whose data + * is available to the encoder directly. */ +static bool checkreturn encode_basic_field(pb_ostream_t *stream, const pb_field_iter_t *field) +{ + if (!field->pData) + { + /* Missing pointer field */ + return true; + } + + if (!pb_encode_tag_for_field(stream, field)) + return false; + + switch (PB_LTYPE(field->type)) + { + case PB_LTYPE_BOOL: + return pb_enc_bool(stream, field); + + case PB_LTYPE_VARINT: + case PB_LTYPE_UVARINT: + case PB_LTYPE_SVARINT: + return pb_enc_varint(stream, field); + + case PB_LTYPE_FIXED32: + case PB_LTYPE_FIXED64: + return pb_enc_fixed(stream, field); + + case PB_LTYPE_BYTES: + return pb_enc_bytes(stream, field); + + case PB_LTYPE_STRING: + return pb_enc_string(stream, field); + + case PB_LTYPE_SUBMESSAGE: + case PB_LTYPE_SUBMSG_W_CB: + return pb_enc_submessage(stream, field); + + case PB_LTYPE_FIXED_LENGTH_BYTES: + return pb_enc_fixed_length_bytes(stream, field); + + default: + PB_RETURN_ERROR(stream, "invalid field type"); + } +} + +/* Encode a field with callback semantics. This means that a user function is + * called to provide and encode the actual data. */ +static bool checkreturn encode_callback_field(pb_ostream_t *stream, const pb_field_iter_t *field) +{ + if (field->descriptor->field_callback != NULL) + { + if (!field->descriptor->field_callback(NULL, stream, field)) + PB_RETURN_ERROR(stream, "callback error"); + } + return true; +} + +/* Encode a single field of any callback, pointer or static type. */ +static bool checkreturn encode_field(pb_ostream_t *stream, pb_field_iter_t *field) +{ + /* Check field presence */ + if (PB_HTYPE(field->type) == PB_HTYPE_ONEOF) + { + if (*(const pb_size_t*)field->pSize != field->tag) + { + /* Different type oneof field */ + return true; + } + } + else if (PB_HTYPE(field->type) == PB_HTYPE_OPTIONAL) + { + if (field->pSize) + { + if (safe_read_bool(field->pSize) == false) + { + /* Missing optional field */ + return true; + } + } + else if (PB_ATYPE(field->type) == PB_ATYPE_STATIC) + { + /* Proto3 singular field */ + if (pb_check_proto3_default_value(field)) + return true; + } + } + + if (!field->pData) + { + if (PB_HTYPE(field->type) == PB_HTYPE_REQUIRED) + PB_RETURN_ERROR(stream, "missing required field"); + + /* Pointer field set to NULL */ + return true; + } + + /* Then encode field contents */ + if (PB_ATYPE(field->type) == PB_ATYPE_CALLBACK) + { + return encode_callback_field(stream, field); + } + else if (PB_HTYPE(field->type) == PB_HTYPE_REPEATED) + { + return encode_array(stream, field); + } + else + { + return encode_basic_field(stream, field); + } +} + +/* Default handler for extension fields. Expects to have a pb_msgdesc_t + * pointer in the extension->type->arg field, pointing to a message with + * only one field in it. */ +static bool checkreturn default_extension_encoder(pb_ostream_t *stream, const pb_extension_t *extension) +{ + pb_field_iter_t iter; + + if (!pb_field_iter_begin_extension_const(&iter, extension)) + PB_RETURN_ERROR(stream, "invalid extension"); + + return encode_field(stream, &iter); +} + + +/* Walk through all the registered extensions and give them a chance + * to encode themselves. */ +static bool checkreturn encode_extension_field(pb_ostream_t *stream, const pb_field_iter_t *field) +{ + const pb_extension_t *extension = *(const pb_extension_t* const *)field->pData; + + while (extension) + { + bool status; + if (extension->type->encode) + status = extension->type->encode(stream, extension); + else + status = default_extension_encoder(stream, extension); + + if (!status) + return false; + + extension = extension->next; + } + + return true; +} + +/********************* + * Encode all fields * + *********************/ + +bool checkreturn pb_encode(pb_ostream_t *stream, const pb_msgdesc_t *fields, const void *src_struct) +{ + pb_field_iter_t iter; + if (!pb_field_iter_begin_const(&iter, fields, src_struct)) + return true; /* Empty message type */ + + do { + if (PB_LTYPE(iter.type) == PB_LTYPE_EXTENSION) + { + /* Special case for the extension field placeholder */ + if (!encode_extension_field(stream, &iter)) + return false; + } + else + { + /* Regular field */ + if (!encode_field(stream, &iter)) + return false; + } + } while (pb_field_iter_next(&iter)); + + return true; +} + +bool checkreturn pb_encode_ex(pb_ostream_t *stream, const pb_msgdesc_t *fields, const void *src_struct, unsigned int flags) +{ + if ((flags & PB_ENCODE_DELIMITED) != 0) + { + return pb_encode_submessage(stream, fields, src_struct); + } + else if ((flags & PB_ENCODE_NULLTERMINATED) != 0) + { + const pb_byte_t zero = 0; + + if (!pb_encode(stream, fields, src_struct)) + return false; + + return pb_write(stream, &zero, 1); + } + else + { + return pb_encode(stream, fields, src_struct); + } +} + +bool pb_get_encoded_size(size_t *size, const pb_msgdesc_t *fields, const void *src_struct) +{ + pb_ostream_t stream = PB_OSTREAM_SIZING; + + if (!pb_encode(&stream, fields, src_struct)) + return false; + + *size = stream.bytes_written; + return true; +} + +/******************** + * Helper functions * + ********************/ + +/* This function avoids 64-bit shifts as they are quite slow on many platforms. */ +static bool checkreturn pb_encode_varint_32(pb_ostream_t *stream, uint32_t low, uint32_t high) +{ + size_t i = 0; + pb_byte_t buffer[10]; + pb_byte_t byte = (pb_byte_t)(low & 0x7F); + low >>= 7; + + while (i < 4 && (low != 0 || high != 0)) + { + byte |= 0x80; + buffer[i++] = byte; + byte = (pb_byte_t)(low & 0x7F); + low >>= 7; + } + + if (high) + { + byte = (pb_byte_t)(byte | ((high & 0x07) << 4)); + high >>= 3; + + while (high) + { + byte |= 0x80; + buffer[i++] = byte; + byte = (pb_byte_t)(high & 0x7F); + high >>= 7; + } + } + + buffer[i++] = byte; + + return pb_write(stream, buffer, i); +} + +bool checkreturn pb_encode_varint(pb_ostream_t *stream, pb_uint64_t value) +{ + if (value <= 0x7F) + { + /* Fast path: single byte */ + pb_byte_t byte = (pb_byte_t)value; + return pb_write(stream, &byte, 1); + } + else + { +#ifdef PB_WITHOUT_64BIT + return pb_encode_varint_32(stream, value, 0); +#else + return pb_encode_varint_32(stream, (uint32_t)value, (uint32_t)(value >> 32)); +#endif + } +} + +bool checkreturn pb_encode_svarint(pb_ostream_t *stream, pb_int64_t value) +{ + pb_uint64_t zigzagged; + pb_uint64_t mask = ((pb_uint64_t)-1) >> 1; /* Satisfy clang -fsanitize=integer */ + if (value < 0) + zigzagged = ~(((pb_uint64_t)value & mask) << 1); + else + zigzagged = (pb_uint64_t)value << 1; + + return pb_encode_varint(stream, zigzagged); +} + +bool checkreturn pb_encode_fixed32(pb_ostream_t *stream, const void *value) +{ +#if defined(PB_LITTLE_ENDIAN_8BIT) && PB_LITTLE_ENDIAN_8BIT == 1 + /* Fast path if we know that we're on little endian */ + return pb_write(stream, (const pb_byte_t*)value, 4); +#else + uint32_t val = *(const uint32_t*)value; + pb_byte_t bytes[4]; + bytes[0] = (pb_byte_t)(val & 0xFF); + bytes[1] = (pb_byte_t)((val >> 8) & 0xFF); + bytes[2] = (pb_byte_t)((val >> 16) & 0xFF); + bytes[3] = (pb_byte_t)((val >> 24) & 0xFF); + return pb_write(stream, bytes, 4); +#endif +} + +#ifndef PB_WITHOUT_64BIT +bool checkreturn pb_encode_fixed64(pb_ostream_t *stream, const void *value) +{ +#if defined(PB_LITTLE_ENDIAN_8BIT) && PB_LITTLE_ENDIAN_8BIT == 1 + /* Fast path if we know that we're on little endian */ + return pb_write(stream, (const pb_byte_t*)value, 8); +#else + uint64_t val = *(const uint64_t*)value; + pb_byte_t bytes[8]; + bytes[0] = (pb_byte_t)(val & 0xFF); + bytes[1] = (pb_byte_t)((val >> 8) & 0xFF); + bytes[2] = (pb_byte_t)((val >> 16) & 0xFF); + bytes[3] = (pb_byte_t)((val >> 24) & 0xFF); + bytes[4] = (pb_byte_t)((val >> 32) & 0xFF); + bytes[5] = (pb_byte_t)((val >> 40) & 0xFF); + bytes[6] = (pb_byte_t)((val >> 48) & 0xFF); + bytes[7] = (pb_byte_t)((val >> 56) & 0xFF); + return pb_write(stream, bytes, 8); +#endif +} +#endif + +bool checkreturn pb_encode_tag(pb_ostream_t *stream, pb_wire_type_t wiretype, uint32_t field_number) +{ + pb_uint64_t tag = ((pb_uint64_t)field_number << 3) | wiretype; + return pb_encode_varint(stream, tag); +} + +bool pb_encode_tag_for_field ( pb_ostream_t* stream, const pb_field_iter_t* field ) +{ + pb_wire_type_t wiretype; + switch (PB_LTYPE(field->type)) + { + case PB_LTYPE_BOOL: + case PB_LTYPE_VARINT: + case PB_LTYPE_UVARINT: + case PB_LTYPE_SVARINT: + wiretype = PB_WT_VARINT; + break; + + case PB_LTYPE_FIXED32: + wiretype = PB_WT_32BIT; + break; + + case PB_LTYPE_FIXED64: + wiretype = PB_WT_64BIT; + break; + + case PB_LTYPE_BYTES: + case PB_LTYPE_STRING: + case PB_LTYPE_SUBMESSAGE: + case PB_LTYPE_SUBMSG_W_CB: + case PB_LTYPE_FIXED_LENGTH_BYTES: + wiretype = PB_WT_STRING; + break; + + default: + PB_RETURN_ERROR(stream, "invalid field type"); + } + + return pb_encode_tag(stream, wiretype, field->tag); +} + +bool checkreturn pb_encode_string(pb_ostream_t *stream, const pb_byte_t *buffer, size_t size) +{ + if (!pb_encode_varint(stream, (pb_uint64_t)size)) + return false; + + return pb_write(stream, buffer, size); +} + +bool checkreturn pb_encode_submessage(pb_ostream_t *stream, const pb_msgdesc_t *fields, const void *src_struct) +{ + /* First calculate the message size using a non-writing substream. */ + pb_ostream_t substream = PB_OSTREAM_SIZING; + size_t size; + bool status; + + if (!pb_encode(&substream, fields, src_struct)) + { +#ifndef PB_NO_ERRMSG + stream->errmsg = substream.errmsg; +#endif + return false; + } + + size = substream.bytes_written; + + if (!pb_encode_varint(stream, (pb_uint64_t)size)) + return false; + + if (stream->callback == NULL) + return pb_write(stream, NULL, size); /* Just sizing */ + + if (stream->bytes_written + size > stream->max_size) + PB_RETURN_ERROR(stream, "stream full"); + + /* Use a substream to verify that a callback doesn't write more than + * what it did the first time. */ + substream.callback = stream->callback; + substream.state = stream->state; + substream.max_size = size; + substream.bytes_written = 0; +#ifndef PB_NO_ERRMSG + substream.errmsg = NULL; +#endif + + status = pb_encode(&substream, fields, src_struct); + + stream->bytes_written += substream.bytes_written; + stream->state = substream.state; +#ifndef PB_NO_ERRMSG + stream->errmsg = substream.errmsg; +#endif + + if (substream.bytes_written != size) + PB_RETURN_ERROR(stream, "submsg size changed"); + + return status; +} + +/* Field encoders */ + +static bool checkreturn pb_enc_bool(pb_ostream_t *stream, const pb_field_iter_t *field) +{ + uint32_t value = safe_read_bool(field->pData) ? 1 : 0; + PB_UNUSED(field); + return pb_encode_varint(stream, value); +} + +static bool checkreturn pb_enc_varint(pb_ostream_t *stream, const pb_field_iter_t *field) +{ + if (PB_LTYPE(field->type) == PB_LTYPE_UVARINT) + { + /* Perform unsigned integer extension */ + pb_uint64_t value = 0; + + if (field->data_size == sizeof(uint_least8_t)) + value = *(const uint_least8_t*)field->pData; + else if (field->data_size == sizeof(uint_least16_t)) + value = *(const uint_least16_t*)field->pData; + else if (field->data_size == sizeof(uint32_t)) + value = *(const uint32_t*)field->pData; + else if (field->data_size == sizeof(pb_uint64_t)) + value = *(const pb_uint64_t*)field->pData; + else + PB_RETURN_ERROR(stream, "invalid data_size"); + + return pb_encode_varint(stream, value); + } + else + { + /* Perform signed integer extension */ + pb_int64_t value = 0; + + if (field->data_size == sizeof(int_least8_t)) + value = *(const int_least8_t*)field->pData; + else if (field->data_size == sizeof(int_least16_t)) + value = *(const int_least16_t*)field->pData; + else if (field->data_size == sizeof(int32_t)) + value = *(const int32_t*)field->pData; + else if (field->data_size == sizeof(pb_int64_t)) + value = *(const pb_int64_t*)field->pData; + else + PB_RETURN_ERROR(stream, "invalid data_size"); + + if (PB_LTYPE(field->type) == PB_LTYPE_SVARINT) + return pb_encode_svarint(stream, value); +#ifdef PB_WITHOUT_64BIT + else if (value < 0) + return pb_encode_varint_32(stream, (uint32_t)value, (uint32_t)-1); +#endif + else + return pb_encode_varint(stream, (pb_uint64_t)value); + + } +} + +static bool checkreturn pb_enc_fixed(pb_ostream_t *stream, const pb_field_iter_t *field) +{ +#ifdef PB_CONVERT_DOUBLE_FLOAT + if (field->data_size == sizeof(float) && PB_LTYPE(field->type) == PB_LTYPE_FIXED64) + { + return pb_encode_float_as_double(stream, *(float*)field->pData); + } +#endif + + if (field->data_size == sizeof(uint32_t)) + { + return pb_encode_fixed32(stream, field->pData); + } +#ifndef PB_WITHOUT_64BIT + else if (field->data_size == sizeof(uint64_t)) + { + return pb_encode_fixed64(stream, field->pData); + } +#endif + else + { + PB_RETURN_ERROR(stream, "invalid data_size"); + } +} + +static bool checkreturn pb_enc_bytes(pb_ostream_t *stream, const pb_field_iter_t *field) +{ + const pb_bytes_array_t *bytes = NULL; + + bytes = (const pb_bytes_array_t*)field->pData; + + if (bytes == NULL) + { + /* Treat null pointer as an empty bytes field */ + return pb_encode_string(stream, NULL, 0); + } + + if (PB_ATYPE(field->type) == PB_ATYPE_STATIC && + bytes->size > field->data_size - offsetof(pb_bytes_array_t, bytes)) + { + PB_RETURN_ERROR(stream, "bytes size exceeded"); + } + + return pb_encode_string(stream, bytes->bytes, (size_t)bytes->size); +} + +static bool checkreturn pb_enc_string(pb_ostream_t *stream, const pb_field_iter_t *field) +{ + size_t size = 0; + size_t max_size = (size_t)field->data_size; + const char *str = (const char*)field->pData; + + if (PB_ATYPE(field->type) == PB_ATYPE_POINTER) + { + max_size = (size_t)-1; + } + else + { + /* pb_dec_string() assumes string fields end with a null + * terminator when the type isn't PB_ATYPE_POINTER, so we + * shouldn't allow more than max-1 bytes to be written to + * allow space for the null terminator. + */ + if (max_size == 0) + PB_RETURN_ERROR(stream, "zero-length string"); + + max_size -= 1; + } + + + if (str == NULL) + { + size = 0; /* Treat null pointer as an empty string */ + } + else + { + const char *p = str; + + /* strnlen() is not always available, so just use a loop */ + while (size < max_size && *p != '\0') + { + size++; + p++; + } + + if (*p != '\0') + { + PB_RETURN_ERROR(stream, "unterminated string"); + } + } + +#ifdef PB_VALIDATE_UTF8 + if (!pb_validate_utf8(str)) + PB_RETURN_ERROR(stream, "invalid utf8"); +#endif + + return pb_encode_string(stream, (const pb_byte_t*)str, size); +} + +static bool checkreturn pb_enc_submessage(pb_ostream_t *stream, const pb_field_iter_t *field) +{ + if (field->submsg_desc == NULL) + PB_RETURN_ERROR(stream, "invalid field descriptor"); + + if (PB_LTYPE(field->type) == PB_LTYPE_SUBMSG_W_CB && field->pSize != NULL) + { + /* Message callback is stored right before pSize. */ + pb_callback_t *callback = (pb_callback_t*)field->pSize - 1; + if (callback->funcs.encode) + { + if (!callback->funcs.encode(stream, field, &callback->arg)) + return false; + } + } + + return pb_encode_submessage(stream, field->submsg_desc, field->pData); +} + +static bool checkreturn pb_enc_fixed_length_bytes(pb_ostream_t *stream, const pb_field_iter_t *field) +{ + return pb_encode_string(stream, (const pb_byte_t*)field->pData, (size_t)field->data_size); +} + +#ifdef PB_CONVERT_DOUBLE_FLOAT +bool pb_encode_float_as_double(pb_ostream_t *stream, float value) +{ + union { float f; uint32_t i; } in; + uint_least8_t sign; + int exponent; + uint64_t mantissa; + + in.f = value; + + /* Decompose input value */ + sign = (uint_least8_t)((in.i >> 31) & 1); + exponent = (int)((in.i >> 23) & 0xFF) - 127; + mantissa = in.i & 0x7FFFFF; + + if (exponent == 128) + { + /* Special value (NaN etc.) */ + exponent = 1024; + } + else if (exponent == -127) + { + if (!mantissa) + { + /* Zero */ + exponent = -1023; + } + else + { + /* Denormalized */ + mantissa <<= 1; + while (!(mantissa & 0x800000)) + { + mantissa <<= 1; + exponent--; + } + mantissa &= 0x7FFFFF; + } + } + + /* Combine fields */ + mantissa <<= 29; + mantissa |= (uint64_t)(exponent + 1023) << 52; + mantissa |= (uint64_t)sign << 63; + + return pb_encode_fixed64(stream, &mantissa); +} +#endif diff --git a/wpiutil/src/test/native/cpp/proto/TestProto.cpp b/wpiutil/src/test/native/cpp/proto/TestProto.cpp new file mode 100644 index 0000000000..40e31da0db --- /dev/null +++ b/wpiutil/src/test/native/cpp/proto/TestProto.cpp @@ -0,0 +1,125 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include + +#include +#include +#include + +#include + +#include "TestProtoInner.h" +#include "wpi/protobuf/ProtobufCallbacks.h" +#include "wpiutil.npb.h" + +struct TestProto { + double double_msg{1}; + float float_msg{2}; + int32_t int32_msg{3}; + int64_t int64_msg{4}; + uint32_t uint32_msg{5}; + uint64_t uint64_msg{6}; + int32_t sint32_msg{7}; + int64_t sint64_msg{8}; + uint32_t fixed32_msg{9}; + uint64_t fixed64_msg{10}; + int32_t sfixed32_msg{11}; + int64_t sfixed64_msg{12}; + bool bool_msg{true}; + std::string string_msg; + std::vector bytes_msg; + TestProtoInner TestProtoInner_msg; +}; + +template <> +struct wpi::Protobuf { + using MessageStruct = wpi_proto_TestProto; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const TestProto& value); +}; + +std::optional wpi::Protobuf::Unpack(InputStream& stream) { + wpi::UnpackCallback str; + wpi::UnpackCallback> bytes; + wpi::UnpackCallback inner; + wpi_proto_TestProto msg; + msg.string_msg = str.Callback(); + msg.bytes_msg = bytes.Callback(); + msg.TestProtoInner_msg = inner.Callback(); + if (!stream.Decode(msg)) { + return {}; + } + + auto istr = str.Items(); + auto ibytes = bytes.Items(); + auto iinner = inner.Items(); + + if (istr.empty() || ibytes.empty() || iinner.empty()) { + return {}; + } + + return TestProto{ + .double_msg = msg.double_msg, + .float_msg = msg.float_msg, + .int32_msg = msg.int32_msg, + .int64_msg = msg.int64_msg, + .uint32_msg = msg.uint32_msg, + .uint64_msg = msg.uint64_msg, + .sint32_msg = msg.sint32_msg, + .sint64_msg = msg.sint64_msg, + .fixed32_msg = msg.fixed32_msg, + .fixed64_msg = msg.fixed64_msg, + .sfixed32_msg = msg.sfixed32_msg, + .sfixed64_msg = msg.sfixed64_msg, + .bool_msg = msg.bool_msg, + .string_msg = std::move(istr[0]), + .bytes_msg = std::move(ibytes[0]), + .TestProtoInner_msg = std::move(iinner[0]), + }; +} + +bool wpi::Protobuf::Pack(OutputStream& stream, + const TestProto& value) { + wpi::PackCallback str{&value.string_msg}; + wpi::PackCallback bytes{&value.bytes_msg}; + wpi::PackCallback inner{&value.TestProtoInner_msg}; + wpi_proto_TestProto msg{ + .double_msg = value.double_msg, + .float_msg = value.float_msg, + .int32_msg = value.int32_msg, + .int64_msg = value.int64_msg, + .uint32_msg = value.uint32_msg, + .uint64_msg = value.uint64_msg, + .sint32_msg = value.sint32_msg, + .sint64_msg = value.sint64_msg, + .fixed32_msg = value.fixed32_msg, + .fixed64_msg = value.fixed64_msg, + .sfixed32_msg = value.sfixed32_msg, + .sfixed64_msg = value.sfixed64_msg, + .bool_msg = value.bool_msg, + .string_msg = str.Callback(), + .bytes_msg = bytes.Callback(), + .TestProtoInner_msg = inner.Callback(), + }; + return stream.Encode(msg); +} + +namespace { +using ProtoType = wpi::Protobuf; +} // namespace + +TEST(TestProtoTest, RoundtripNanopb) { + const TestProto kExpectedData = TestProto{}; + + wpi::ProtobufMessage message; + wpi::SmallVector buf; + + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + std::optional unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + ASSERT_TRUE(unpacked_data.has_value()); +} diff --git a/wpiutil/src/test/native/cpp/proto/TestProtoInner.cpp b/wpiutil/src/test/native/cpp/proto/TestProtoInner.cpp new file mode 100644 index 0000000000..9fb12d8f2f --- /dev/null +++ b/wpiutil/src/test/native/cpp/proto/TestProtoInner.cpp @@ -0,0 +1,70 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include "TestProtoInner.h" + +#include +#include + +#include + +#include "wpi/protobuf/ProtobufCallbacks.h" +#include "wpiutil.npb.h" + +std::optional wpi::Protobuf::Unpack( + wpi::ProtoInputStream& stream) { + wpi::UnpackCallback str; + wpi_proto_TestProtoInner msg{ + .msg = str.Callback(), + }; + if (!stream.Decode(msg)) { + return {}; + } + + auto istr = str.Items(); + + if (istr.empty()) { + return {}; + } + + return TestProtoInner{std::move(istr[0])}; +} + +bool wpi::Protobuf::Pack( + wpi::ProtoOutputStream& stream, + const TestProtoInner& value) { + wpi::PackCallback str{&value.msg}; + wpi_proto_TestProtoInner msg{ + .msg = str.Callback(), + }; + return stream.Encode(msg); +} + +namespace { +using ProtoType = wpi::Protobuf; +} // namespace + +TEST(TestProtoInnerTest, RoundtripNanopb) { + const TestProtoInner kExpectedData = TestProtoInner{"Hello!"}; + + wpi::ProtobufMessage message; + wpi::SmallVector buf; + + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + std::optional unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + EXPECT_EQ(kExpectedData.msg, unpacked_data->msg); +} + +TEST(TestProtoInnerTest, RoundtripNanopbEmpty) { + const TestProtoInner kExpectedData = TestProtoInner{"Hello!"}; + + wpi::ProtobufMessage message; + wpi::SmallVector buf; + + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + EXPECT_EQ(kExpectedData.msg, unpacked_data->msg); +} diff --git a/wpiutil/src/test/native/cpp/proto/TestProtoInner.h b/wpiutil/src/test/native/cpp/proto/TestProtoInner.h new file mode 100644 index 0000000000..37a88e71c5 --- /dev/null +++ b/wpiutil/src/test/native/cpp/proto/TestProtoInner.h @@ -0,0 +1,24 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#pragma once + +#include + +#include + +#include "wpiutil.npb.h" + +struct TestProtoInner { + std::string msg; +}; + +template <> +struct wpi::Protobuf { + using MessageStruct = wpi_proto_TestProtoInner; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const TestProtoInner& value); +}; diff --git a/wpiutil/src/test/native/cpp/proto/TestProtoRepeated.cpp b/wpiutil/src/test/native/cpp/proto/TestProtoRepeated.cpp new file mode 100644 index 0000000000..b4e1107eba --- /dev/null +++ b/wpiutil/src/test/native/cpp/proto/TestProtoRepeated.cpp @@ -0,0 +1,186 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +#include +#include +#include + +#include + +#include "TestProtoInner.h" +#include "wpi/protobuf/ProtobufCallbacks.h" +#include "wpiutil.npb.h" + +struct RepeatedTestProto { + std::vector double_msg; + std::vector float_msg; + std::vector int32_msg; + std::vector int64_msg; + std::vector uint32_msg; + std::vector uint64_msg; + std::vector sint32_msg; + std::vector sint64_msg; + std::vector fixed32_msg; + std::vector fixed64_msg; + std::vector sfixed32_msg; + std::vector sfixed64_msg; + wpi::SmallVector bool_msg; + std::vector string_msg; + std::vector> bytes_msg; + std::vector TestProtoInner_msg; +}; + +template <> +struct wpi::Protobuf { + using MessageStruct = wpi_proto_RepeatedTestProto; + using InputStream = wpi::ProtoInputStream; + using OutputStream = wpi::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const RepeatedTestProto& value); +}; + +std::optional wpi::Protobuf::Unpack( + InputStream& stream) { + RepeatedTestProto toRet; + + wpi::DirectUnpackCallback> double_msg{ + toRet.double_msg}; + wpi::DirectUnpackCallback> float_msg{ + toRet.float_msg}; + wpi::DirectUnpackCallback> int32_msg{ + toRet.int32_msg}; + wpi::DirectUnpackCallback> int64_msg{ + toRet.int64_msg}; + wpi::DirectUnpackCallback> uint32_msg{ + toRet.uint32_msg}; + wpi::DirectUnpackCallback> uint64_msg{ + toRet.uint64_msg}; + wpi::DirectUnpackCallback> sint32_msg{ + toRet.sint32_msg}; + wpi::DirectUnpackCallback> sint64_msg{ + toRet.sint64_msg}; + wpi::DirectUnpackCallback> fixed32_msg{ + toRet.fixed32_msg}; + wpi::DirectUnpackCallback> fixed64_msg{ + toRet.fixed64_msg}; + wpi::DirectUnpackCallback> sfixed32_msg{ + toRet.sfixed32_msg}; + wpi::DirectUnpackCallback> sfixed64_msg{ + toRet.sfixed64_msg}; + wpi::DirectUnpackCallback> bool_msg{ + toRet.bool_msg}; + wpi::DirectUnpackCallback> string_msg{ + toRet.string_msg}; + wpi::DirectUnpackCallback, + std::vector>> + bytes_msg{toRet.bytes_msg}; + wpi::DirectUnpackCallback> + TestProtoInner_msg{toRet.TestProtoInner_msg}; + + wpi_proto_RepeatedTestProto msg{ + .double_msg = double_msg.Callback(), + .float_msg = float_msg.Callback(), + .int32_msg = int32_msg.Callback(), + .int64_msg = int64_msg.Callback(), + .uint32_msg = uint32_msg.Callback(), + .uint64_msg = uint64_msg.Callback(), + .sint32_msg = sint32_msg.Callback(), + .sint64_msg = sint64_msg.Callback(), + .fixed32_msg = fixed32_msg.Callback(), + .fixed64_msg = fixed64_msg.Callback(), + .sfixed32_msg = sfixed32_msg.Callback(), + .sfixed64_msg = sfixed64_msg.Callback(), + .bool_msg = bool_msg.Callback(), + .string_msg = string_msg.Callback(), + .bytes_msg = bytes_msg.Callback(), + .TestProtoInner_msg = TestProtoInner_msg.Callback(), + }; + + if (!stream.Decode(msg)) { + return {}; + } + + return toRet; +} + +bool wpi::Protobuf::Pack(OutputStream& stream, + const RepeatedTestProto& value) { + wpi::PackCallback double_msg{value.double_msg}; + wpi::PackCallback float_msg{value.float_msg}; + wpi::PackCallback int32_msg{value.int32_msg}; + wpi::PackCallback int64_msg{value.int64_msg}; + wpi::PackCallback uint32_msg{value.uint32_msg}; + wpi::PackCallback uint64_msg{value.uint64_msg}; + wpi::PackCallback sint32_msg{value.sint32_msg}; + wpi::PackCallback sint64_msg{value.sint64_msg}; + wpi::PackCallback fixed32_msg{value.fixed32_msg}; + wpi::PackCallback fixed64_msg{value.fixed64_msg}; + wpi::PackCallback sfixed32_msg{value.sfixed32_msg}; + wpi::PackCallback sfixed64_msg{value.sfixed64_msg}; + wpi::PackCallback bool_msg{value.bool_msg}; + wpi::PackCallback string_msg{value.string_msg}; + wpi::PackCallback> bytes_msg{value.bytes_msg}; + wpi::PackCallback TestProtoInner_msg{ + value.TestProtoInner_msg}; + wpi_proto_RepeatedTestProto msg{ + .double_msg = double_msg.Callback(), + .float_msg = float_msg.Callback(), + .int32_msg = int32_msg.Callback(), + .int64_msg = int64_msg.Callback(), + .uint32_msg = uint32_msg.Callback(), + .uint64_msg = uint64_msg.Callback(), + .sint32_msg = sint32_msg.Callback(), + .sint64_msg = sint64_msg.Callback(), + .fixed32_msg = fixed32_msg.Callback(), + .fixed64_msg = fixed64_msg.Callback(), + .sfixed32_msg = sfixed32_msg.Callback(), + .sfixed64_msg = sfixed64_msg.Callback(), + .bool_msg = bool_msg.Callback(), + .string_msg = string_msg.Callback(), + .bytes_msg = bytes_msg.Callback(), + .TestProtoInner_msg = TestProtoInner_msg.Callback(), + }; + return stream.Encode(msg); +} + +namespace { +using ProtoType = wpi::Protobuf; +} // namespace + +TEST(RepeatedTestProtoTest, RoundtripNanopb) { + RepeatedTestProto kExpectedData = RepeatedTestProto{}; + kExpectedData.bool_msg.emplace_back(true); + kExpectedData.bool_msg.emplace_back(false); + + kExpectedData.double_msg.emplace_back(5.05); + + wpi::ProtobufMessage message; + wpi::SmallVector buf; + + ASSERT_TRUE(message.Pack(buf, kExpectedData)); + auto unpacked_data = message.Unpack(buf); + ASSERT_TRUE(unpacked_data.has_value()); + + ASSERT_EQ(kExpectedData.double_msg.size(), unpacked_data->double_msg.size()); + ASSERT_EQ(kExpectedData.float_msg.size(), unpacked_data->float_msg.size()); + ASSERT_EQ(kExpectedData.int32_msg.size(), unpacked_data->int32_msg.size()); + ASSERT_EQ(kExpectedData.int64_msg.size(), unpacked_data->int64_msg.size()); + ASSERT_EQ(kExpectedData.uint32_msg.size(), unpacked_data->uint32_msg.size()); + ASSERT_EQ(kExpectedData.uint64_msg.size(), unpacked_data->uint64_msg.size()); + ASSERT_EQ(kExpectedData.sint32_msg.size(), unpacked_data->sint32_msg.size()); + ASSERT_EQ(kExpectedData.sint64_msg.size(), unpacked_data->sint64_msg.size()); + ASSERT_EQ(kExpectedData.fixed32_msg.size(), + unpacked_data->fixed32_msg.size()); + ASSERT_EQ(kExpectedData.fixed64_msg.size(), + unpacked_data->fixed64_msg.size()); + ASSERT_EQ(kExpectedData.sfixed32_msg.size(), + unpacked_data->sfixed32_msg.size()); + ASSERT_EQ(kExpectedData.sfixed64_msg.size(), + unpacked_data->sfixed64_msg.size()); + ASSERT_EQ(kExpectedData.bool_msg.size(), unpacked_data->bool_msg.size()); + ASSERT_EQ(kExpectedData.string_msg.size(), unpacked_data->string_msg.size()); + ASSERT_EQ(kExpectedData.bytes_msg.size(), unpacked_data->bytes_msg.size()); + ASSERT_EQ(kExpectedData.TestProtoInner_msg.size(), + unpacked_data->TestProtoInner_msg.size()); +} diff --git a/wpiutil/src/test/proto/wpiutil.proto b/wpiutil/src/test/proto/wpiutil.proto new file mode 100644 index 0000000000..2c5b99586b --- /dev/null +++ b/wpiutil/src/test/proto/wpiutil.proto @@ -0,0 +1,64 @@ +syntax = "proto3"; + +package wpi.proto; + +message TestProtoInner { + string msg = 1; +} + +message TestProto { + double double_msg = 1; + float float_msg = 2; + int32 int32_msg = 3; + int64 int64_msg = 4; + uint32 uint32_msg = 5; + uint64 uint64_msg = 6; + sint32 sint32_msg = 7; + sint64 sint64_msg = 8; + fixed32 fixed32_msg = 9; + fixed64 fixed64_msg = 10; + sfixed32 sfixed32_msg = 11; + sfixed64 sfixed64_msg = 12; + bool bool_msg = 13; + string string_msg = 14; + bytes bytes_msg = 15; + TestProtoInner TestProtoInner_msg = 16; +} + +message OptionalTestProto { + optional double double_msg = 1; + optional float float_msg = 2; + optional int32 int32_msg = 3; + optional int64 int64_msg = 4; + optional uint32 uint32_msg = 5; + optional uint64 uint64_msg = 6; + optional sint32 sint32_msg = 7; + optional sint64 sint64_msg = 8; + optional fixed32 fixed32_msg = 9; + optional fixed64 fixed64_msg = 10; + optional sfixed32 sfixed32_msg = 11; + optional sfixed64 sfixed64_msg = 12; + optional bool bool_msg = 13; + optional string string_msg = 14; + optional bytes bytes_msg = 15; + optional TestProtoInner TestProtoInner_msg = 16; +} + +message RepeatedTestProto { + repeated double double_msg = 1; + repeated float float_msg = 2; + repeated int32 int32_msg = 3; + repeated int64 int64_msg = 4; + repeated uint32 uint32_msg = 5; + repeated uint64 uint64_msg = 6; + repeated sint32 sint32_msg = 7; + repeated sint64 sint64_msg = 8; + repeated fixed32 fixed32_msg = 9; + repeated fixed64 fixed64_msg = 10; + repeated sfixed32 sfixed32_msg = 11; + repeated sfixed64 sfixed64_msg = 12; + repeated bool bool_msg = 13; + repeated string string_msg = 14; + repeated bytes bytes_msg = 15; + repeated TestProtoInner TestProtoInner_msg = 16; +}