From 2676b7787305acc57ca8ea3f75fb085a5f14f063 Mon Sep 17 00:00:00 2001 From: PJ Reiniger Date: Tue, 5 Dec 2023 00:18:26 -0500 Subject: [PATCH 1/9] Fix compilation issues that occur when building with bazel (#6008) --- hal/src/main/native/sim/HAL.cpp | 4 ++-- ntcore/src/main/native/cpp/net/ClientImpl.cpp | 1 - .../java/edu/wpi/first/wpilibj/examples/eventloop/Main.java | 1 - .../examples/rapidreactcommandbot/subsystems/Shooter.java | 2 +- wpiunits/src/test/java/edu/wpi/first/units/MeasureTest.java | 1 + 5 files changed, 4 insertions(+), 5 deletions(-) diff --git a/hal/src/main/native/sim/HAL.cpp b/hal/src/main/native/sim/HAL.cpp index ce8b6dde5ff..c7b632c1b61 100644 --- a/hal/src/main/native/sim/HAL.cpp +++ b/hal/src/main/native/sim/HAL.cpp @@ -367,12 +367,12 @@ HAL_Bool HAL_Initialize(int32_t timeout, int32_t mode) { #ifdef _WIN32 TIMECAPS tc; if (timeGetDevCaps(&tc, sizeof(tc)) == TIMERR_NOERROR) { - UINT target = min(1, tc.wPeriodMin); + UINT target = (std::min)(static_cast(1), tc.wPeriodMin); timeBeginPeriod(target); std::atexit([]() { TIMECAPS tc; if (timeGetDevCaps(&tc, sizeof(tc)) == TIMERR_NOERROR) { - UINT target = min(1, tc.wPeriodMin); + UINT target = (std::min)(static_cast(1), tc.wPeriodMin); timeEndPeriod(target); } }); diff --git a/ntcore/src/main/native/cpp/net/ClientImpl.cpp b/ntcore/src/main/native/cpp/net/ClientImpl.cpp index 309b01a0d05..4f7e9cb7a96 100644 --- a/ntcore/src/main/native/cpp/net/ClientImpl.cpp +++ b/ntcore/src/main/native/cpp/net/ClientImpl.cpp @@ -20,7 +20,6 @@ #include "NetworkInterface.h" #include "WireConnection.h" #include "WireEncoder.h" -#include "net/NetworkOutgoingQueue.h" #include "networktables/NetworkTableValue.h" using namespace nt; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Main.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Main.java index d6f3150a6c0..23a49cb2e13 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Main.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/eventloop/Main.java @@ -5,7 +5,6 @@ package edu.wpi.first.wpilibj.examples.eventloop; import edu.wpi.first.wpilibj.RobotBase; -import edu.wpi.first.wpilibj.examples.encoder.Robot; /** * Do NOT add any static variables to this class, or any initialization at all. Unless you know what diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java index 0e7f9b56cef..d282c2062cf 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java @@ -10,7 +10,7 @@ import edu.wpi.first.math.controller.PIDController; import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.wpilibj.Encoder; -import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants; +import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.ShooterConstants; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.SubsystemBase; diff --git a/wpiunits/src/test/java/edu/wpi/first/units/MeasureTest.java b/wpiunits/src/test/java/edu/wpi/first/units/MeasureTest.java index 6bc867d41d5..53f950ddec5 100644 --- a/wpiunits/src/test/java/edu/wpi/first/units/MeasureTest.java +++ b/wpiunits/src/test/java/edu/wpi/first/units/MeasureTest.java @@ -176,6 +176,7 @@ void testOfBaseUnits() { } @Test + @SuppressWarnings("SelfComparison") void testCompare() { var unit = new ExampleUnit(7); var base = unit.of(1); From 90757b9e90a2acd8b4a9679ffe777863b7db7cca Mon Sep 17 00:00:00 2001 From: Tyler Veness Date: Mon, 4 Dec 2023 21:20:49 -0800 Subject: [PATCH 2/9] [wpilib] Make Color::HexString() constexpr (#5985) Related improvements to wpi::ct_string: * Implicitly convert to std::string * Add operator== for std::string, std::string_view, and const Char* --- wpilibc/src/main/native/cpp/util/Color.cpp | 13 ---- .../src/main/native/cpp/util/Color8Bit.cpp | 11 --- .../src/main/native/include/frc/util/Color.h | 12 ++- .../main/native/include/frc/util/Color8Bit.h | 8 +- .../test/native/cpp/util/Color8BitTest.cpp | 11 ++- .../src/test/native/cpp/util/ColorTest.cpp | 11 ++- .../src/main/native/include/wpi/ct_string.h | 75 +++++++++++++++++-- 7 files changed, 105 insertions(+), 36 deletions(-) delete mode 100644 wpilibc/src/main/native/cpp/util/Color.cpp delete mode 100644 wpilibc/src/main/native/cpp/util/Color8Bit.cpp diff --git a/wpilibc/src/main/native/cpp/util/Color.cpp b/wpilibc/src/main/native/cpp/util/Color.cpp deleted file mode 100644 index 6923c9cbec1..00000000000 --- a/wpilibc/src/main/native/cpp/util/Color.cpp +++ /dev/null @@ -1,13 +0,0 @@ -// 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 "frc/util/Color.h" - -using namespace frc; - -std::string Color::HexString() const { - return fmt::format("#{:02X}{:02X}{:02X}", static_cast(255.0 * red), - static_cast(255.0 * green), - static_cast(255.0 * blue)); -} diff --git a/wpilibc/src/main/native/cpp/util/Color8Bit.cpp b/wpilibc/src/main/native/cpp/util/Color8Bit.cpp deleted file mode 100644 index e8e46567d70..00000000000 --- a/wpilibc/src/main/native/cpp/util/Color8Bit.cpp +++ /dev/null @@ -1,11 +0,0 @@ -// 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 "frc/util/Color8Bit.h" - -using namespace frc; - -std::string Color8Bit::HexString() const { - return fmt::format("#{:02X}{:02X}{:02X}", red, green, blue); -} diff --git a/wpilibc/src/main/native/include/frc/util/Color.h b/wpilibc/src/main/native/include/frc/util/Color.h index b5855e23ce8..868e577e3ce 100644 --- a/wpilibc/src/main/native/include/frc/util/Color.h +++ b/wpilibc/src/main/native/include/frc/util/Color.h @@ -11,6 +11,7 @@ #include #include +#include namespace frc { @@ -851,7 +852,16 @@ class Color { * * @return a string of the format \#RRGGBB */ - std::string HexString() const; + constexpr auto HexString() const { + const int r = 255.0 * red; + const int g = 255.0 * green; + const int b = 255.0 * blue; + + return wpi::ct_string, 7>{ + {'#', wpi::hexdigit(r / 16), wpi::hexdigit(r % 16), + wpi::hexdigit(g / 16), wpi::hexdigit(g % 16), wpi::hexdigit(b / 16), + wpi::hexdigit(b % 16)}}; + } double red = 0.0; double green = 0.0; diff --git a/wpilibc/src/main/native/include/frc/util/Color8Bit.h b/wpilibc/src/main/native/include/frc/util/Color8Bit.h index 77bdc9f0ee5..ce7915a5fd4 100644 --- a/wpilibc/src/main/native/include/frc/util/Color8Bit.h +++ b/wpilibc/src/main/native/include/frc/util/Color8Bit.h @@ -11,6 +11,7 @@ #include #include +#include #include "Color.h" @@ -107,7 +108,12 @@ class Color8Bit { * * @return a string of the format \#RRGGBB */ - std::string HexString() const; + constexpr auto HexString() const { + return wpi::ct_string, 7>{ + {'#', wpi::hexdigit(red / 16), wpi::hexdigit(red % 16), + wpi::hexdigit(green / 16), wpi::hexdigit(green % 16), + wpi::hexdigit(blue / 16), wpi::hexdigit(blue % 16)}}; + } int red = 0; int green = 0; diff --git a/wpilibc/src/test/native/cpp/util/Color8BitTest.cpp b/wpilibc/src/test/native/cpp/util/Color8BitTest.cpp index e0b26dd5790..d9027be2445 100644 --- a/wpilibc/src/test/native/cpp/util/Color8BitTest.cpp +++ b/wpilibc/src/test/native/cpp/util/Color8BitTest.cpp @@ -2,6 +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 "frc/util/Color8Bit.h" @@ -56,7 +58,12 @@ TEST(Color8BitTest, ImplicitConversionToColor) { } TEST(Color8BitTest, ToHexString) { - constexpr frc::Color8Bit color{255, 128, 64}; + constexpr frc::Color8Bit color1{255, 128, 64}; + EXPECT_EQ("#FF8040", color1.HexString()); + + // Ensure conversion to std::string works + [[maybe_unused]] std::string str = color1.HexString(); - EXPECT_EQ("#FF8040", color.HexString()); + frc::Color8Bit color2{255, 128, 64}; + EXPECT_EQ("#FF8040", color2.HexString()); } diff --git a/wpilibc/src/test/native/cpp/util/ColorTest.cpp b/wpilibc/src/test/native/cpp/util/ColorTest.cpp index c76c7f1da29..8b71d4634c1 100644 --- a/wpilibc/src/test/native/cpp/util/ColorTest.cpp +++ b/wpilibc/src/test/native/cpp/util/ColorTest.cpp @@ -2,6 +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 "frc/util/Color.h" @@ -56,7 +58,12 @@ TEST(ColorTest, FromHSV) { } TEST(ColorTest, ToHexString) { - constexpr frc::Color color{255, 128, 64}; + constexpr frc::Color color1{255, 128, 64}; + EXPECT_EQ("#FF8040", color1.HexString()); + + // Ensure conversion to std::string works + [[maybe_unused]] std::string str = color1.HexString(); - EXPECT_EQ("#FF8040", color.HexString()); + frc::Color color2{255, 128, 64}; + EXPECT_EQ("#FF8040", color2.HexString()); } diff --git a/wpiutil/src/main/native/include/wpi/ct_string.h b/wpiutil/src/main/native/include/wpi/ct_string.h index 9f0ef907508..2c7796b4f63 100644 --- a/wpiutil/src/main/native/include/wpi/ct_string.h +++ b/wpiutil/src/main/native/include/wpi/ct_string.h @@ -31,7 +31,7 @@ struct ct_string { template requires(M <= (N + 1)) - consteval ct_string(Char const (&s)[M]) { // NOLINT + constexpr ct_string(Char const (&s)[M]) { // NOLINT if constexpr (M == (N + 1)) { if (s[N] != Char{}) { throw std::logic_error{"char array not null terminated"}; @@ -50,7 +50,7 @@ struct ct_string { } } - explicit consteval ct_string(std::basic_string_view s) { + explicit constexpr ct_string(std::basic_string_view s) { // avoid dependency on // auto p = std::ranges::copy(s, chars.begin()).out; auto p = chars.begin(); @@ -63,6 +63,64 @@ struct ct_string { } } + constexpr bool operator==(const ct_string&) const = default; + + constexpr bool operator==(const std::basic_string& rhs) const { + if (size() != rhs.size()) { + return false; + } + + for (size_t i = 0; i < size(); ++i) { + if (chars[i] != rhs[i]) { + return false; + } + } + + return true; + } + + constexpr bool operator==(std::basic_string_view rhs) const { + if (size() != rhs.size()) { + return false; + } + + for (size_t i = 0; i < size(); ++i) { + if (chars[i] != rhs[i]) { + return false; + } + } + + return true; + } + + template + requires(N + 1 == M) + constexpr bool operator==(Char const (&rhs)[M]) const { + for (size_t i = 0; i < M; ++i) { + if (chars[i] != rhs[i]) { + return false; + } + } + + return true; + } + + constexpr bool operator==(const Char* rhs) const { + for (size_t i = 0; i < N + 1; ++i) { + if (chars[i] != rhs[i]) { + return false; + } + + // If index of rhs's null terminator is less than lhs's size - 1, rhs is + // shorter than lhs + if (rhs[i] == '\0' && i < N) { + return false; + } + } + + return true; + } + constexpr auto size() const noexcept { return N; } constexpr auto begin() const noexcept { return chars.begin(); } @@ -71,6 +129,11 @@ struct ct_string { constexpr auto data() const noexcept { return chars.data(); } constexpr auto c_str() const noexcept { return chars.data(); } + constexpr operator std::basic_string() // NOLINT + const noexcept { + return std::basic_string{chars.data(), N}; + } + constexpr operator std::basic_string_view() // NOLINT const noexcept { return std::basic_string_view{chars.data(), N}; @@ -82,13 +145,13 @@ ct_string(Char const (&s)[M]) -> ct_string, M - 1>; inline namespace literals { template -consteval auto operator""_ct_string() { +constexpr auto operator""_ct_string() { return S; } } // namespace literals template -consteval auto operator+(ct_string const& s1, +constexpr auto operator+(ct_string const& s1, ct_string const& s2) noexcept { return Concat(s1, s2); } @@ -102,7 +165,7 @@ consteval auto operator+(ct_string const& s1, * @return concatenated string */ template -consteval auto Concat(ct_string const& s1, +constexpr auto Concat(ct_string const& s1, ct_string const&... s) { // Need a dummy array to instantiate a ct_string. constexpr Char dummy[1] = {}; @@ -136,7 +199,7 @@ consteval auto Concat(ct_string const& s1, template > requires(Base >= 2 && Base <= 36) -consteval auto NumToCtString() { +constexpr auto NumToCtString() { constexpr char digits[] = "0123456789ABCDEFGHIJKLMNOPQRSTUVWXYZ"; auto buflen = [] { From 14c3ade155080ee7d4ae1467e3e0c54e4b561337 Mon Sep 17 00:00:00 2001 From: Joseph Eng <91924258+KangarooKoala@users.noreply.github.com> Date: Mon, 4 Dec 2023 22:40:18 -0800 Subject: [PATCH 3/9] [wpimath] Struct cleanup (#6011) --- .../controller/struct/ArmFeedforwardStruct.cpp | 4 ++-- .../DifferentialDriveWheelVoltagesStruct.cpp | 4 ++-- .../struct/ElevatorFeedforwardStruct.cpp | 5 ++--- .../cpp/system/plant/struct/DCMotorStruct.cpp | 5 ++--- .../controller/struct/ArmFeedforwardStruct.h | 18 +++++++++++------- .../DifferentialDriveWheelVoltagesStruct.h | 17 +++++++++++------ .../struct/ElevatorFeedforwardStruct.h | 17 +++++++++++------ .../include/frc/geometry/struct/Pose2dStruct.h | 1 + .../include/frc/geometry/struct/Pose3dStruct.h | 1 + .../frc/geometry/struct/QuaternionStruct.h | 2 ++ .../frc/geometry/struct/Rotation2dStruct.h | 2 ++ .../frc/geometry/struct/Rotation3dStruct.h | 1 + .../frc/geometry/struct/Transform2dStruct.h | 1 + .../frc/geometry/struct/Transform3dStruct.h | 1 + .../frc/geometry/struct/Translation2dStruct.h | 2 ++ .../frc/geometry/struct/Translation3dStruct.h | 2 ++ .../frc/geometry/struct/Twist2dStruct.h | 2 ++ .../frc/geometry/struct/Twist3dStruct.h | 2 ++ .../kinematics/struct/ChassisSpeedsStruct.h | 2 ++ .../struct/DifferentialDriveKinematicsStruct.h | 2 ++ .../DifferentialDriveWheelSpeedsStruct.h | 2 ++ .../struct/MecanumDriveKinematicsStruct.h | 1 + .../struct/MecanumDriveWheelPositionsStruct.h | 2 ++ .../struct/MecanumDriveWheelSpeedsStruct.h | 2 ++ .../struct/SwerveModulePositionStruct.h | 1 + .../struct/SwerveModuleStateStruct.h | 1 + .../frc/system/plant/struct/DCMotorStruct.h | 18 +++++++++++------- .../struct/ArmFeedforwardStructTest.cpp | 4 ++-- ...ifferentialDriveWheelVoltagesStructTest.cpp | 4 ++-- .../struct/ElevatorFeedforwardStructTest.cpp | 4 ++-- .../system/plant/struct/DCMotorStructTest.cpp | 4 ++-- .../main/native/include/wpi/struct/Struct.h | 10 +++++----- 32 files changed, 95 insertions(+), 49 deletions(-) diff --git a/wpimath/src/main/native/cpp/controller/struct/ArmFeedforwardStruct.cpp b/wpimath/src/main/native/cpp/controller/struct/ArmFeedforwardStruct.cpp index 0e6e8165ca4..6b0070cb1e1 100644 --- a/wpimath/src/main/native/cpp/controller/struct/ArmFeedforwardStruct.cpp +++ b/wpimath/src/main/native/cpp/controller/struct/ArmFeedforwardStruct.cpp @@ -13,7 +13,7 @@ constexpr size_t kKaOff = kKvOff + 8; using StructType = wpi::Struct; -frc::ArmFeedforward StructType::Unpack(std::span data) { +frc::ArmFeedforward StructType::Unpack(std::span data) { return frc::ArmFeedforward{ units::volt_t{wpi::UnpackStruct(data)}, units::volt_t{wpi::UnpackStruct(data)}, @@ -24,7 +24,7 @@ frc::ArmFeedforward StructType::Unpack(std::span data) { }; } -void StructType::Pack(std::span data, +void StructType::Pack(std::span data, const frc::ArmFeedforward& value) { wpi::PackStruct(data, value.kS()); wpi::PackStruct(data, value.kG()); diff --git a/wpimath/src/main/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStruct.cpp b/wpimath/src/main/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStruct.cpp index c056638eaf3..22a79302b6a 100644 --- a/wpimath/src/main/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStruct.cpp +++ b/wpimath/src/main/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStruct.cpp @@ -12,14 +12,14 @@ constexpr size_t kRightOff = kLeftOff + 8; using StructType = wpi::Struct; frc::DifferentialDriveWheelVoltages StructType::Unpack( - std::span data) { + std::span data) { return frc::DifferentialDriveWheelVoltages{ units::volt_t{wpi::UnpackStruct(data)}, units::volt_t{wpi::UnpackStruct(data)}, }; } -void StructType::Pack(std::span data, +void StructType::Pack(std::span data, const frc::DifferentialDriveWheelVoltages& value) { wpi::PackStruct(data, value.left.value()); wpi::PackStruct(data, value.right.value()); diff --git a/wpimath/src/main/native/cpp/controller/struct/ElevatorFeedforwardStruct.cpp b/wpimath/src/main/native/cpp/controller/struct/ElevatorFeedforwardStruct.cpp index 0572181c7f5..ff28357bbba 100644 --- a/wpimath/src/main/native/cpp/controller/struct/ElevatorFeedforwardStruct.cpp +++ b/wpimath/src/main/native/cpp/controller/struct/ElevatorFeedforwardStruct.cpp @@ -13,8 +13,7 @@ constexpr size_t kKaOff = kKvOff + 8; using StructType = wpi::Struct; -frc::ElevatorFeedforward StructType::Unpack( - std::span data) { +frc::ElevatorFeedforward StructType::Unpack(std::span data) { return frc::ElevatorFeedforward{ units::volt_t{wpi::UnpackStruct(data)}, units::volt_t{wpi::UnpackStruct(data)}, @@ -25,7 +24,7 @@ frc::ElevatorFeedforward StructType::Unpack( }; } -void StructType::Pack(std::span data, +void StructType::Pack(std::span data, const frc::ElevatorFeedforward& value) { wpi::PackStruct(data, value.kS()); wpi::PackStruct(data, value.kG()); diff --git a/wpimath/src/main/native/cpp/system/plant/struct/DCMotorStruct.cpp b/wpimath/src/main/native/cpp/system/plant/struct/DCMotorStruct.cpp index 91438ca2c1f..e7389a17efb 100644 --- a/wpimath/src/main/native/cpp/system/plant/struct/DCMotorStruct.cpp +++ b/wpimath/src/main/native/cpp/system/plant/struct/DCMotorStruct.cpp @@ -14,7 +14,7 @@ constexpr size_t kFreeSpeedOff = kFreeCurrentOff + 8; using StructType = wpi::Struct; -frc::DCMotor StructType::Unpack(std::span data) { +frc::DCMotor StructType::Unpack(std::span data) { return frc::DCMotor{ units::volt_t{wpi::UnpackStruct(data)}, units::newton_meter_t{wpi::UnpackStruct(data)}, @@ -25,8 +25,7 @@ frc::DCMotor StructType::Unpack(std::span data) { }; } -void StructType::Pack(std::span data, - const frc::DCMotor& value) { +void StructType::Pack(std::span data, const frc::DCMotor& value) { wpi::PackStruct(data, value.nominalVoltage.value()); wpi::PackStruct(data, value.stallTorque.value()); wpi::PackStruct(data, value.stallCurrent.value()); diff --git a/wpimath/src/main/native/include/frc/controller/struct/ArmFeedforwardStruct.h b/wpimath/src/main/native/include/frc/controller/struct/ArmFeedforwardStruct.h index 3f427da9d87..cfc585cb320 100644 --- a/wpimath/src/main/native/include/frc/controller/struct/ArmFeedforwardStruct.h +++ b/wpimath/src/main/native/include/frc/controller/struct/ArmFeedforwardStruct.h @@ -11,12 +11,16 @@ template <> struct WPILIB_DLLEXPORT wpi::Struct { - static constexpr std::string_view kTypeString = "struct:ArmFeedforward"; - static constexpr size_t kSize = 32; - static constexpr std::string_view kSchema = - "double ks;double kg;double kv;double ka"; + static constexpr std::string_view GetTypeString() { + return "struct:ArmFeedforward"; + } + static constexpr size_t GetSize() { return 32; } + static constexpr std::string_view GetSchema() { + return "double ks;double kg;double kv;double ka"; + } - static frc::ArmFeedforward Unpack(std::span data); - static void Pack(std::span data, - const frc::ArmFeedforward& value); + static frc::ArmFeedforward Unpack(std::span data); + static void Pack(std::span data, const frc::ArmFeedforward& value); }; + +static_assert(wpi::StructSerializable); diff --git a/wpimath/src/main/native/include/frc/controller/struct/DifferentialDriveWheelVoltagesStruct.h b/wpimath/src/main/native/include/frc/controller/struct/DifferentialDriveWheelVoltagesStruct.h index dae20ed4893..cb5311f691c 100644 --- a/wpimath/src/main/native/include/frc/controller/struct/DifferentialDriveWheelVoltagesStruct.h +++ b/wpimath/src/main/native/include/frc/controller/struct/DifferentialDriveWheelVoltagesStruct.h @@ -11,13 +11,18 @@ template <> struct WPILIB_DLLEXPORT wpi::Struct { - static constexpr std::string_view kTypeString = - "struct:DifferentialDriveWheelVoltages"; - static constexpr size_t kSize = 16; - static constexpr std::string_view kSchema = "double left;double right"; + static constexpr std::string_view GetTypeString() { + return "struct:DifferentialDriveWheelVoltages"; + } + static constexpr size_t GetSize() { return 16; } + static constexpr std::string_view GetSchema() { + return "double left;double right"; + } static frc::DifferentialDriveWheelVoltages Unpack( - std::span data); - static void Pack(std::span data, + std::span data); + static void Pack(std::span data, const frc::DifferentialDriveWheelVoltages& value); }; + +static_assert(wpi::StructSerializable); diff --git a/wpimath/src/main/native/include/frc/controller/struct/ElevatorFeedforwardStruct.h b/wpimath/src/main/native/include/frc/controller/struct/ElevatorFeedforwardStruct.h index 89c03f8fea9..fafb7d73ecc 100644 --- a/wpimath/src/main/native/include/frc/controller/struct/ElevatorFeedforwardStruct.h +++ b/wpimath/src/main/native/include/frc/controller/struct/ElevatorFeedforwardStruct.h @@ -11,12 +11,17 @@ template <> struct WPILIB_DLLEXPORT wpi::Struct { - static constexpr std::string_view kTypeString = "struct:ElevatorFeedforward"; - static constexpr size_t kSize = 32; - static constexpr std::string_view kSchema = - "double ks;double kg;double kv;double ka"; + static constexpr std::string_view GetTypeString() { + return "struct:ElevatorFeedforward"; + } + static constexpr size_t GetSize() { return 32; } + static constexpr std::string_view GetSchema() { + return "double ks;double kg;double kv;double ka"; + } - static frc::ElevatorFeedforward Unpack(std::span data); - static void Pack(std::span data, + static frc::ElevatorFeedforward Unpack(std::span data); + static void Pack(std::span data, const frc::ElevatorFeedforward& value); }; + +static_assert(wpi::StructSerializable); diff --git a/wpimath/src/main/native/include/frc/geometry/struct/Pose2dStruct.h b/wpimath/src/main/native/include/frc/geometry/struct/Pose2dStruct.h index a76eed546de..66e3295f918 100644 --- a/wpimath/src/main/native/include/frc/geometry/struct/Pose2dStruct.h +++ b/wpimath/src/main/native/include/frc/geometry/struct/Pose2dStruct.h @@ -29,4 +29,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { } }; +static_assert(wpi::StructSerializable); static_assert(wpi::HasNestedStruct); diff --git a/wpimath/src/main/native/include/frc/geometry/struct/Pose3dStruct.h b/wpimath/src/main/native/include/frc/geometry/struct/Pose3dStruct.h index e3c2eb489e4..f47ffec964c 100644 --- a/wpimath/src/main/native/include/frc/geometry/struct/Pose3dStruct.h +++ b/wpimath/src/main/native/include/frc/geometry/struct/Pose3dStruct.h @@ -29,4 +29,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { } }; +static_assert(wpi::StructSerializable); static_assert(wpi::HasNestedStruct); diff --git a/wpimath/src/main/native/include/frc/geometry/struct/QuaternionStruct.h b/wpimath/src/main/native/include/frc/geometry/struct/QuaternionStruct.h index 06410325fb5..80420c0774d 100644 --- a/wpimath/src/main/native/include/frc/geometry/struct/QuaternionStruct.h +++ b/wpimath/src/main/native/include/frc/geometry/struct/QuaternionStruct.h @@ -22,3 +22,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { static frc::Quaternion Unpack(std::span data); static void Pack(std::span data, const frc::Quaternion& value); }; + +static_assert(wpi::StructSerializable); diff --git a/wpimath/src/main/native/include/frc/geometry/struct/Rotation2dStruct.h b/wpimath/src/main/native/include/frc/geometry/struct/Rotation2dStruct.h index 127a2027af4..85b6ae51782 100644 --- a/wpimath/src/main/native/include/frc/geometry/struct/Rotation2dStruct.h +++ b/wpimath/src/main/native/include/frc/geometry/struct/Rotation2dStruct.h @@ -20,3 +20,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { static frc::Rotation2d Unpack(std::span data); static void Pack(std::span data, const frc::Rotation2d& value); }; + +static_assert(wpi::StructSerializable); diff --git a/wpimath/src/main/native/include/frc/geometry/struct/Rotation3dStruct.h b/wpimath/src/main/native/include/frc/geometry/struct/Rotation3dStruct.h index d1cc1f0ca85..e94b75ee4be 100644 --- a/wpimath/src/main/native/include/frc/geometry/struct/Rotation3dStruct.h +++ b/wpimath/src/main/native/include/frc/geometry/struct/Rotation3dStruct.h @@ -27,4 +27,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { } }; +static_assert(wpi::StructSerializable); static_assert(wpi::HasNestedStruct); diff --git a/wpimath/src/main/native/include/frc/geometry/struct/Transform2dStruct.h b/wpimath/src/main/native/include/frc/geometry/struct/Transform2dStruct.h index 36438b577b6..28ef463ab14 100644 --- a/wpimath/src/main/native/include/frc/geometry/struct/Transform2dStruct.h +++ b/wpimath/src/main/native/include/frc/geometry/struct/Transform2dStruct.h @@ -31,4 +31,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { } }; +static_assert(wpi::StructSerializable); static_assert(wpi::HasNestedStruct); diff --git a/wpimath/src/main/native/include/frc/geometry/struct/Transform3dStruct.h b/wpimath/src/main/native/include/frc/geometry/struct/Transform3dStruct.h index f4de9cafadf..e4e88bcf498 100644 --- a/wpimath/src/main/native/include/frc/geometry/struct/Transform3dStruct.h +++ b/wpimath/src/main/native/include/frc/geometry/struct/Transform3dStruct.h @@ -31,4 +31,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { } }; +static_assert(wpi::StructSerializable); static_assert(wpi::HasNestedStruct); diff --git a/wpimath/src/main/native/include/frc/geometry/struct/Translation2dStruct.h b/wpimath/src/main/native/include/frc/geometry/struct/Translation2dStruct.h index a1c77e90036..df12760f855 100644 --- a/wpimath/src/main/native/include/frc/geometry/struct/Translation2dStruct.h +++ b/wpimath/src/main/native/include/frc/geometry/struct/Translation2dStruct.h @@ -20,3 +20,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { static frc::Translation2d Unpack(std::span data); static void Pack(std::span data, const frc::Translation2d& value); }; + +static_assert(wpi::StructSerializable); diff --git a/wpimath/src/main/native/include/frc/geometry/struct/Translation3dStruct.h b/wpimath/src/main/native/include/frc/geometry/struct/Translation3dStruct.h index 255e9ac900d..b61a8758c62 100644 --- a/wpimath/src/main/native/include/frc/geometry/struct/Translation3dStruct.h +++ b/wpimath/src/main/native/include/frc/geometry/struct/Translation3dStruct.h @@ -22,3 +22,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { static frc::Translation3d Unpack(std::span data); static void Pack(std::span data, const frc::Translation3d& value); }; + +static_assert(wpi::StructSerializable); diff --git a/wpimath/src/main/native/include/frc/geometry/struct/Twist2dStruct.h b/wpimath/src/main/native/include/frc/geometry/struct/Twist2dStruct.h index adff1294b23..86bb4ada36c 100644 --- a/wpimath/src/main/native/include/frc/geometry/struct/Twist2dStruct.h +++ b/wpimath/src/main/native/include/frc/geometry/struct/Twist2dStruct.h @@ -20,3 +20,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { static frc::Twist2d Unpack(std::span data); static void Pack(std::span data, const frc::Twist2d& value); }; + +static_assert(wpi::StructSerializable); diff --git a/wpimath/src/main/native/include/frc/geometry/struct/Twist3dStruct.h b/wpimath/src/main/native/include/frc/geometry/struct/Twist3dStruct.h index 64ca8abd3d6..a346a1ad801 100644 --- a/wpimath/src/main/native/include/frc/geometry/struct/Twist3dStruct.h +++ b/wpimath/src/main/native/include/frc/geometry/struct/Twist3dStruct.h @@ -20,3 +20,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { static frc::Twist3d Unpack(std::span data); static void Pack(std::span data, const frc::Twist3d& value); }; + +static_assert(wpi::StructSerializable); diff --git a/wpimath/src/main/native/include/frc/kinematics/struct/ChassisSpeedsStruct.h b/wpimath/src/main/native/include/frc/kinematics/struct/ChassisSpeedsStruct.h index e8b6395910a..8c65057da93 100644 --- a/wpimath/src/main/native/include/frc/kinematics/struct/ChassisSpeedsStruct.h +++ b/wpimath/src/main/native/include/frc/kinematics/struct/ChassisSpeedsStruct.h @@ -22,3 +22,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { static frc::ChassisSpeeds Unpack(std::span data); static void Pack(std::span data, const frc::ChassisSpeeds& value); }; + +static_assert(wpi::StructSerializable); diff --git a/wpimath/src/main/native/include/frc/kinematics/struct/DifferentialDriveKinematicsStruct.h b/wpimath/src/main/native/include/frc/kinematics/struct/DifferentialDriveKinematicsStruct.h index 79b44f65fb4..0acbc76e47c 100644 --- a/wpimath/src/main/native/include/frc/kinematics/struct/DifferentialDriveKinematicsStruct.h +++ b/wpimath/src/main/native/include/frc/kinematics/struct/DifferentialDriveKinematicsStruct.h @@ -21,3 +21,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { static void Pack(std::span data, const frc::DifferentialDriveKinematics& value); }; + +static_assert(wpi::StructSerializable); diff --git a/wpimath/src/main/native/include/frc/kinematics/struct/DifferentialDriveWheelSpeedsStruct.h b/wpimath/src/main/native/include/frc/kinematics/struct/DifferentialDriveWheelSpeedsStruct.h index 06800206049..12dc8431eb0 100644 --- a/wpimath/src/main/native/include/frc/kinematics/struct/DifferentialDriveWheelSpeedsStruct.h +++ b/wpimath/src/main/native/include/frc/kinematics/struct/DifferentialDriveWheelSpeedsStruct.h @@ -24,3 +24,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { static void Pack(std::span data, const frc::DifferentialDriveWheelSpeeds& value); }; + +static_assert(wpi::StructSerializable); diff --git a/wpimath/src/main/native/include/frc/kinematics/struct/MecanumDriveKinematicsStruct.h b/wpimath/src/main/native/include/frc/kinematics/struct/MecanumDriveKinematicsStruct.h index 4dde54b1a20..a4fe3bddca0 100644 --- a/wpimath/src/main/native/include/frc/kinematics/struct/MecanumDriveKinematicsStruct.h +++ b/wpimath/src/main/native/include/frc/kinematics/struct/MecanumDriveKinematicsStruct.h @@ -31,4 +31,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { } }; +static_assert(wpi::StructSerializable); static_assert(wpi::HasNestedStruct); diff --git a/wpimath/src/main/native/include/frc/kinematics/struct/MecanumDriveWheelPositionsStruct.h b/wpimath/src/main/native/include/frc/kinematics/struct/MecanumDriveWheelPositionsStruct.h index f14c3749b88..87b5f386246 100644 --- a/wpimath/src/main/native/include/frc/kinematics/struct/MecanumDriveWheelPositionsStruct.h +++ b/wpimath/src/main/native/include/frc/kinematics/struct/MecanumDriveWheelPositionsStruct.h @@ -24,3 +24,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { static void Pack(std::span data, const frc::MecanumDriveWheelPositions& value); }; + +static_assert(wpi::StructSerializable); diff --git a/wpimath/src/main/native/include/frc/kinematics/struct/MecanumDriveWheelSpeedsStruct.h b/wpimath/src/main/native/include/frc/kinematics/struct/MecanumDriveWheelSpeedsStruct.h index b0b0608c19b..28f28e8c229 100644 --- a/wpimath/src/main/native/include/frc/kinematics/struct/MecanumDriveWheelSpeedsStruct.h +++ b/wpimath/src/main/native/include/frc/kinematics/struct/MecanumDriveWheelSpeedsStruct.h @@ -24,3 +24,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { static void Pack(std::span data, const frc::MecanumDriveWheelSpeeds& value); }; + +static_assert(wpi::StructSerializable); diff --git a/wpimath/src/main/native/include/frc/kinematics/struct/SwerveModulePositionStruct.h b/wpimath/src/main/native/include/frc/kinematics/struct/SwerveModulePositionStruct.h index ac0f852bf93..ee58a2c7cdb 100644 --- a/wpimath/src/main/native/include/frc/kinematics/struct/SwerveModulePositionStruct.h +++ b/wpimath/src/main/native/include/frc/kinematics/struct/SwerveModulePositionStruct.h @@ -30,4 +30,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { } }; +static_assert(wpi::StructSerializable); static_assert(wpi::HasNestedStruct); diff --git a/wpimath/src/main/native/include/frc/kinematics/struct/SwerveModuleStateStruct.h b/wpimath/src/main/native/include/frc/kinematics/struct/SwerveModuleStateStruct.h index 589eb2a60db..06885fed518 100644 --- a/wpimath/src/main/native/include/frc/kinematics/struct/SwerveModuleStateStruct.h +++ b/wpimath/src/main/native/include/frc/kinematics/struct/SwerveModuleStateStruct.h @@ -30,4 +30,5 @@ struct WPILIB_DLLEXPORT wpi::Struct { } }; +static_assert(wpi::StructSerializable); static_assert(wpi::HasNestedStruct); diff --git a/wpimath/src/main/native/include/frc/system/plant/struct/DCMotorStruct.h b/wpimath/src/main/native/include/frc/system/plant/struct/DCMotorStruct.h index c16b65b4d6d..22a6405d9a6 100644 --- a/wpimath/src/main/native/include/frc/system/plant/struct/DCMotorStruct.h +++ b/wpimath/src/main/native/include/frc/system/plant/struct/DCMotorStruct.h @@ -11,12 +11,16 @@ template <> struct WPILIB_DLLEXPORT wpi::Struct { - static constexpr std::string_view kTypeString = "struct:DCMotor"; - static constexpr size_t kSize = 40; - static constexpr std::string_view kSchema = - "double nominal_voltage;double stall_torque;double stall_current;double " - "free_current;double free_speed"; + static constexpr std::string_view GetTypeString() { return "struct:DCMotor"; } + static constexpr size_t GetSize() { return 40; } + static constexpr std::string_view GetSchema() { + return "double nominal_voltage;double stall_torque;double " + "stall_current;double " + "free_current;double free_speed"; + } - static frc::DCMotor Unpack(std::span data); - static void Pack(std::span data, const frc::DCMotor& value); + static frc::DCMotor Unpack(std::span data); + static void Pack(std::span data, const frc::DCMotor& value); }; + +static_assert(wpi::StructSerializable); diff --git a/wpimath/src/test/native/cpp/controller/struct/ArmFeedforwardStructTest.cpp b/wpimath/src/test/native/cpp/controller/struct/ArmFeedforwardStructTest.cpp index 453061c56e3..a76f52585a8 100644 --- a/wpimath/src/test/native/cpp/controller/struct/ArmFeedforwardStructTest.cpp +++ b/wpimath/src/test/native/cpp/controller/struct/ArmFeedforwardStructTest.cpp @@ -20,8 +20,8 @@ const ArmFeedforward kExpectedData{Ks, Kg, Kv, Ka}; } // namespace TEST(ArmFeedforwardStructTest, Roundtrip) { - uint8_t buffer[StructType::kSize]; - std::memset(buffer, 0, StructType::kSize); + uint8_t buffer[StructType::GetSize()]; + std::memset(buffer, 0, StructType::GetSize()); StructType::Pack(buffer, kExpectedData); ArmFeedforward unpacked_data = StructType::Unpack(buffer); diff --git a/wpimath/src/test/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStructTest.cpp b/wpimath/src/test/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStructTest.cpp index 2b47e5a5383..c72ac4aac97 100644 --- a/wpimath/src/test/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStructTest.cpp +++ b/wpimath/src/test/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStructTest.cpp @@ -16,8 +16,8 @@ const DifferentialDriveWheelVoltages kExpectedData{ } // namespace TEST(DifferentialDriveWheelVoltagesStructTest, Roundtrip) { - uint8_t buffer[StructType::kSize]; - std::memset(buffer, 0, StructType::kSize); + uint8_t buffer[StructType::GetSize()]; + std::memset(buffer, 0, StructType::GetSize()); StructType::Pack(buffer, kExpectedData); DifferentialDriveWheelVoltages unpacked_data = StructType::Unpack(buffer); diff --git a/wpimath/src/test/native/cpp/controller/struct/ElevatorFeedforwardStructTest.cpp b/wpimath/src/test/native/cpp/controller/struct/ElevatorFeedforwardStructTest.cpp index 299d39a34be..2e5c43a2310 100644 --- a/wpimath/src/test/native/cpp/controller/struct/ElevatorFeedforwardStructTest.cpp +++ b/wpimath/src/test/native/cpp/controller/struct/ElevatorFeedforwardStructTest.cpp @@ -21,8 +21,8 @@ constexpr ElevatorFeedforward kExpectedData{Ks, Kg, Kv, Ka}; } // namespace TEST(ElevatorFeedforwardStructTest, Roundtrip) { - uint8_t buffer[StructType::kSize]; - std::memset(buffer, 0, StructType::kSize); + uint8_t buffer[StructType::GetSize()]; + std::memset(buffer, 0, StructType::GetSize()); StructType::Pack(buffer, kExpectedData); ElevatorFeedforward unpacked_data = StructType::Unpack(buffer); diff --git a/wpimath/src/test/native/cpp/system/plant/struct/DCMotorStructTest.cpp b/wpimath/src/test/native/cpp/system/plant/struct/DCMotorStructTest.cpp index 30306d2d5f5..50d5c8b5607 100644 --- a/wpimath/src/test/native/cpp/system/plant/struct/DCMotorStructTest.cpp +++ b/wpimath/src/test/native/cpp/system/plant/struct/DCMotorStructTest.cpp @@ -20,8 +20,8 @@ const DCMotor kExpectedData = DCMotor{units::volt_t{1.91}, } // namespace TEST(DCMotorStructTest, Roundtrip) { - uint8_t buffer[StructType::kSize]; - std::memset(buffer, 0, StructType::kSize); + uint8_t buffer[StructType::GetSize()]; + std::memset(buffer, 0, StructType::GetSize()); StructType::Pack(buffer, kExpectedData); DCMotor unpacked_data = StructType::Unpack(buffer); diff --git a/wpiutil/src/main/native/include/wpi/struct/Struct.h b/wpiutil/src/main/native/include/wpi/struct/Struct.h index 530607acda6..58aca475d9e 100644 --- a/wpiutil/src/main/native/include/wpi/struct/Struct.h +++ b/wpiutil/src/main/native/include/wpi/struct/Struct.h @@ -51,8 +51,8 @@ struct Struct {}; * - std::string_view GetTypeString(): function that returns the type string * - size_t GetSize(): function that returns the structure size in bytes * - std::string_view GetSchema(): function that returns the struct schema - * - T Unpack(std::span): function for deserialization - * - void Pack(std::span, T&& value): function for + * - T Unpack(std::span): function for deserialization + * - void Pack(std::span, T&& value): function for * serialization * * If possible, the GetTypeString(), GetSize(), and GetSchema() functions should @@ -411,9 +411,9 @@ struct Struct { */ template <> struct Struct { - static constexpr std::string_view kTypeString = "struct:int8"; - static constexpr size_t kSize = 1; - static constexpr std::string_view kSchema = "int8 value"; + static constexpr std::string_view GetTypeString() { return "struct:int8"; } + static constexpr size_t GetSize() { return 1; } + static constexpr std::string_view GetSchema() { return "int8 value"; } static int8_t Unpack(std::span data) { return data[0]; } static void Pack(std::span data, int8_t value) { data[0] = value; From 41cfc961e4976818178d75c8c495e930bdbff680 Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Tue, 5 Dec 2023 13:30:54 -0800 Subject: [PATCH 4/9] gitattributes: Add linguist-generated locations (#6004) --- .gitattributes | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/.gitattributes b/.gitattributes index ae2ea0e0571..483e5c1a916 100644 --- a/.gitattributes +++ b/.gitattributes @@ -3,3 +3,8 @@ *.json text eol=lf *.md text eol=lf *.xml text eol=lf + +# Generated files +hal/src/generated/** linguist-generated +ntcore/src/generated/** linguist-generated +wpimath/src/generated/** linguist-generated From c2971c0bb36b58618803a6b32e3eb1b395b226af Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Tue, 5 Dec 2023 16:31:27 -0500 Subject: [PATCH 5/9] [build] cmake: Export apriltag and wpimath (#6012) --- CMakeLists.txt | 12 ++++++------ wpilib-config.cmake.in | 11 +++++++---- 2 files changed, 13 insertions(+), 10 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index d0af74c68fd..249b542681c 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -213,16 +213,16 @@ find_package(LIBSSH 0.7.1) find_package(Protobuf REQUIRED) find_program(Quickbuf_EXECUTABLE NAMES protoc-gen-quickbuf DOC "The Quickbuf protoc plugin") -set(WPIUTIL_DEP_REPLACE "find_dependency(wpiutil)") -set(WPINET_DEP_REPLACE "find_dependency(wpinet)") -set(NTCORE_DEP_REPLACE "find_dependency(ntcore)") -set(CSCORE_DEP_REPLACE_IMPL "find_dependency(cscore)") +set(APRILTAG_DEP_REPLACE "find_dependency(apriltag)") set(CAMERASERVER_DEP_REPLACE_IMPL "find_dependency(cameraserver)") +set(CSCORE_DEP_REPLACE_IMPL "find_dependency(cscore)") set(HAL_DEP_REPLACE_IMPL "find_dependency(hal)") -set(WPIMATH_DEP_REPLACE "find_dependency(wpimath)") -set(WPIUNITS_DEP_REPLACE "find_dependency(wpiunits)") +set(NTCORE_DEP_REPLACE "find_dependency(ntcore)") set(WPILIBC_DEP_REPLACE_IMPL "find_dependency(wpilibc)") set(WPILIBNEWCOMMANDS_DEP_REPLACE "find_dependency(wpilibNewCommands)") +set(WPIMATH_DEP_REPLACE "find_dependency(wpimath)") +set(WPINET_DEP_REPLACE "find_dependency(wpinet)") +set(WPIUTIL_DEP_REPLACE "find_dependency(wpiutil)") set(FILENAME_DEP_REPLACE "get_filename_component(SELF_DIR \"$\{CMAKE_CURRENT_LIST_FILE\}\" PATH)") set(SELF_DIR "$\{SELF_DIR\}") diff --git a/wpilib-config.cmake.in b/wpilib-config.cmake.in index aaf4bb84f85..018c39ce933 100644 --- a/wpilib-config.cmake.in +++ b/wpilib-config.cmake.in @@ -4,11 +4,14 @@ set(THREADS_PREFER_PTHREAD_FLAG ON) find_dependency(Threads) @LIBUV_SYSTEM_REPLACE@ @EIGEN_SYSTEM_REPLACE@ -@WPIUTIL_DEP_REPLACE@ -@WPINET_DEP_REPLACE@ -@NTCORE_DEP_REPLACE@ -@CSCORE_DEP_REPLACE@ + +@APRILTAG_DEP_REPLACE@ @CAMERASERVER_DEP_REPLACE@ +@CSCORE_DEP_REPLACE@ @HAL_DEP_REPLACE@ +@NTCORE_DEP_REPLACE@ @WPILIBC_DEP_REPLACE@ @WPILIBNEWCOMMANDS_DEP_REPLACE@ +@WPIMATH_DEP_REPLACE@ +@WPINET_DEP_REPLACE@ +@WPIUTIL_DEP_REPLACE@ From 28deba20f54cbac99020975d29e2dad6d9d26305 Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Tue, 5 Dec 2023 20:02:29 -0500 Subject: [PATCH 6/9] [wpimath] Commit generated quickbuf Java files (#5994) This removes a build dependency on the quickbuf generator being available for the build platform. It's safe to generate Java because the quickbuf version is defined by the project. C++ protobufs can't be committed because the protoc version must match the library version (this is a particular issue for cmake builds). --- .github/workflows/pregenerate.yml | 96 +- shared/java/javacommon.gradle | 10 - styleguide/checkstyle-suppressions.xml | 2 +- styleguide/pmd-ruleset.xml | 2 +- wpimath/.styleguide | 1 + wpimath/CMakeLists.txt | 49 - wpimath/generate_quickbuf.py | 33 + .../edu/wpi/first/math/proto/Controller.java | 2309 +++++++++ .../edu/wpi/first/math/proto/Geometry2D.java | 1806 +++++++ .../edu/wpi/first/math/proto/Geometry3D.java | 2652 +++++++++++ .../edu/wpi/first/math/proto/Kinematics.java | 4196 +++++++++++++++++ .../java/edu/wpi/first/math/proto/Plant.java | 621 +++ .../java/edu/wpi/first/math/proto/Spline.java | 1367 ++++++ .../java/edu/wpi/first/math/proto/System.java | 866 ++++ .../edu/wpi/first/math/proto/Trajectory.java | 928 ++++ .../edu/wpi/first/math/proto/Wpimath.java | 791 ++++ 16 files changed, 15621 insertions(+), 108 deletions(-) create mode 100755 wpimath/generate_quickbuf.py create mode 100644 wpimath/src/generated/main/java/edu/wpi/first/math/proto/Controller.java create mode 100644 wpimath/src/generated/main/java/edu/wpi/first/math/proto/Geometry2D.java create mode 100644 wpimath/src/generated/main/java/edu/wpi/first/math/proto/Geometry3D.java create mode 100644 wpimath/src/generated/main/java/edu/wpi/first/math/proto/Kinematics.java create mode 100644 wpimath/src/generated/main/java/edu/wpi/first/math/proto/Plant.java create mode 100644 wpimath/src/generated/main/java/edu/wpi/first/math/proto/Spline.java create mode 100644 wpimath/src/generated/main/java/edu/wpi/first/math/proto/System.java create mode 100644 wpimath/src/generated/main/java/edu/wpi/first/math/proto/Trajectory.java create mode 100644 wpimath/src/generated/main/java/edu/wpi/first/math/proto/Wpimath.java diff --git a/.github/workflows/pregenerate.yml b/.github/workflows/pregenerate.yml index f7c96489861..b730264c4c6 100644 --- a/.github/workflows/pregenerate.yml +++ b/.github/workflows/pregenerate.yml @@ -1,47 +1,49 @@ -name: Check Pregenerated Files - -on: - pull_request: - push: - branches-ignore: - - main - -concurrency: - group: ${{ github.workflow }}-${{ github.head_ref || github.ref }} - cancel-in-progress: true - -jobs: - update: - name: "Update" - runs-on: ubuntu-22.04 - steps: - - uses: actions/checkout@v3 - - name: Fetch all history and metadata - run: | - git fetch --prune --unshallow - git checkout -b pr - git branch -f main origin/main - - name: Set up Python 3.9 - uses: actions/setup-python@v4 - with: - python-version: 3.9 - - name: Install jinja - run: python -m pip install jinja2 - - name: Run hal - run: ./hal/generate_usage_reporting.py - - name: Run ntcore - run: ./ntcore/generate_topics.py - - name: Run wpimath - run: ./wpimath/generate_numbers.py - - name: Add untracked files to index so they count as changes - run: git add -A - - name: Check output - run: git --no-pager diff --exit-code HEAD - - name: Generate diff - run: git diff HEAD > pregenerated-files-fixes.patch - if: ${{ failure() }} - - uses: actions/upload-artifact@v3 - with: - name: pregenerated-files-fixes - path: pregenerated-files-fixes.patch - if: ${{ failure() }} +name: Check Pregenerated Files + +on: + pull_request: + push: + branches-ignore: + - main + +concurrency: + group: ${{ github.workflow }}-${{ github.head_ref || github.ref }} + cancel-in-progress: true + +jobs: + update: + name: "Update" + runs-on: ubuntu-22.04 + steps: + - uses: actions/checkout@v3 + - name: Fetch all history and metadata + run: | + git fetch --prune --unshallow + git checkout -b pr + git branch -f main origin/main + - name: Set up Python 3.9 + uses: actions/setup-python@v4 + with: + python-version: 3.9 + - name: Install jinja + run: python -m pip install jinja2 + - 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.2/protoc-gen-quickbuf-1.3.2-linux-x86_64.exe && chmod +x protoc-gen-quickbuf-1.3.2-linux-x86_64.exe + - name: Run hal + run: ./hal/generate_usage_reporting.py + - name: Run ntcore + run: ./ntcore/generate_topics.py + - name: Run wpimath + run: ./wpimath/generate_numbers.py && ./wpimath/generate_quickbuf.py protoc protoc-gen-quickbuf-1.3.2-linux-x86_64.exe + - name: Add untracked files to index so they count as changes + run: git add -A + - name: Check output + run: git --no-pager diff --exit-code HEAD + - name: Generate diff + run: git diff HEAD > pregenerated-files-fixes.patch + if: ${{ failure() }} + - uses: actions/upload-artifact@v3 + with: + name: pregenerated-files-fixes + path: pregenerated-files-fixes.patch + if: ${{ failure() }} diff --git a/shared/java/javacommon.gradle b/shared/java/javacommon.gradle index f5813328cd7..48a506293b0 100644 --- a/shared/java/javacommon.gradle +++ b/shared/java/javacommon.gradle @@ -146,22 +146,12 @@ protobuf { protoc { artifact = 'com.google.protobuf:protoc:3.21.12' } - plugins { - quickbuf { - artifact = 'us.hebi.quickbuf:protoc-gen-quickbuf:1.3.2' - } - } generateProtoTasks { all().configureEach { task -> task.builtins { cpp {} remove java } - task.plugins { - quickbuf { - option "gen_descriptors=true" - } - } } } } diff --git a/styleguide/checkstyle-suppressions.xml b/styleguide/checkstyle-suppressions.xml index 2197fe27ba4..f42b176a636 100644 --- a/styleguide/checkstyle-suppressions.xml +++ b/styleguide/checkstyle-suppressions.xml @@ -10,6 +10,6 @@ suppressions PUBLIC "-//Puppy Crawl//DTD Suppressions 1.1//EN" checks="(LocalVariableName|MemberName|MethodName|MethodTypeParameterName|ParameterName)" /> - diff --git a/styleguide/pmd-ruleset.xml b/styleguide/pmd-ruleset.xml index f2ef2bc8dbe..1f6577e6f18 100644 --- a/styleguide/pmd-ruleset.xml +++ b/styleguide/pmd-ruleset.xml @@ -8,7 +8,7 @@ .*/*JNI.* .*/*IntegrationTests.* - .*/quickbuf/.* + .*/math/proto.* diff --git a/wpimath/.styleguide b/wpimath/.styleguide index 257b50bcaec..00437ce869e 100644 --- a/wpimath/.styleguide +++ b/wpimath/.styleguide @@ -21,6 +21,7 @@ generatedFileExclude { src/test/native/cpp/UnitsTest\.cpp$ src/test/native/cpp/drake/ src/test/native/include/drake/ + src/generated/main/java/edu/wpi/first/math/proto } repoRootNameOverride { diff --git a/wpimath/CMakeLists.txt b/wpimath/CMakeLists.txt index dbae16e65e4..f938c4df7e1 100644 --- a/wpimath/CMakeLists.txt +++ b/wpimath/CMakeLists.txt @@ -17,52 +17,6 @@ protobuf_generate_cpp( ${wpimath_proto_src} ) -function(quickbuf_generate SRCS JAVA_PACKAGE) - if(NOT ARGN) - message(SEND_ERROR "Error: PROTOBUF_GENERATE_QUICKBUF() called without any proto files") - return() - endif() - - set(_generated_srcs_all) - foreach(_proto ${ARGN}) - get_filename_component(_abs_file ${_proto} ABSOLUTE) - get_filename_component(_abs_dir ${_abs_file} DIRECTORY) - get_filename_component(_basename ${_proto} NAME_WLE) - file(RELATIVE_PATH _rel_dir ${CMAKE_CURRENT_SOURCE_DIR} ${_abs_dir}) - - # convert to QuickBuffers Java case (geometry2d -> Geometry2D) - string(REGEX MATCHALL "[A-Za-z_]+|[0-9]+" _name_components ${_basename}) - set(_name_components_out) - foreach(_part ${_name_components}) - string(SUBSTRING ${_part} 0 1 _first_letter) - string(TOUPPER ${_first_letter} _first_letter) - string(REGEX REPLACE "^.(.*)" "${_first_letter}\\1" _part_out "${_part}") - list(APPEND _name_components_out ${_part_out}) - endforeach() - list(JOIN _name_components_out "" _basename_title) - - set(_generated_src - "${CMAKE_CURRENT_BINARY_DIR}/quickbuf/${JAVA_PACKAGE}/${_basename_title}.java" - ) - - list(APPEND _generated_srcs_all ${_generated_src}) - - add_custom_command( - OUTPUT ${_generated_src} - COMMAND protobuf::protoc - ARGS - --plugin=protoc-gen-quickbuf=${Quickbuf_EXECUTABLE} - --quickbuf_out=gen_descriptors=true:${CMAKE_CURRENT_BINARY_DIR}/quickbuf - -I${_abs_dir} ${_abs_file} - DEPENDS ${_abs_file} protobuf::protoc - COMMENT "Running quickbuf protocol buffer compiler on ${_proto}" - VERBATIM - ) - endforeach() - - set(${SRCS} ${_generated_srcs_all} PARENT_SCOPE) -endfunction() - file( GLOB wpimath_jni_src src/main/native/cpp/jni/WPIMathJNI_DARE.cpp @@ -80,8 +34,6 @@ if(WITH_JAVA) include(UseJava) set(CMAKE_JAVA_COMPILE_FLAGS "-encoding" "UTF8" "-Xlint:unchecked") - quickbuf_generate(WPIMATH_QUICKBUF_SRCS "edu/wpi/first/math/proto" ${wpimath_proto_src}) - if(NOT EXISTS "${WPILIB_BINARY_DIR}/wpimath/thirdparty/ejml/ejml-simple-0.43.1.jar") set(BASE_URL "https://search.maven.org/remotecontent?filepath=") set(JAR_ROOT "${WPILIB_BINARY_DIR}/wpimath/thirdparty/ejml") @@ -126,7 +78,6 @@ if(WITH_JAVA) add_jar( wpimath_jar ${JAVA_SOURCES} - ${WPIMATH_QUICKBUF_SRCS} INCLUDE_JARS ${EJML_JARS} wpiutil_jar wpiunits_jar OUTPUT_NAME wpimath GENERATE_NATIVE_HEADERS wpimath_jni_headers diff --git a/wpimath/generate_quickbuf.py b/wpimath/generate_quickbuf.py new file mode 100755 index 00000000000..506c5bc92d2 --- /dev/null +++ b/wpimath/generate_quickbuf.py @@ -0,0 +1,33 @@ +#!/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 os.path +import subprocess +import sys +from glob import glob + +if __name__ == "__main__": + proto_files = glob("wpimath/src/main/proto/*.proto") + for path in proto_files: + absolute_filename = os.path.abspath(path) + absolute_dir, filename = os.path.split(absolute_filename) + subprocess.run( + [ + sys.argv[1], + f"--plugin=protoc-gen-quickbuf={sys.argv[2]}", + f"--quickbuf_out=gen_descriptors=true:{os.path.abspath('./wpimath/src/generated/main/java')}", + f"-I{absolute_dir}", + absolute_filename, + ] + ) + java_files = glob("wpimath/src/generated/main/java/edu/wpi/first/math/proto/*.java") + for java_file in java_files: + with open(java_file) as file: + content = file.read() + with open(java_file, "tw") as file: + file.write( + "// 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 + ) diff --git a/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Controller.java b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Controller.java new file mode 100644 index 00000000000..ed423da5831 --- /dev/null +++ b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Controller.java @@ -0,0 +1,2309 @@ +// 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. +// Code generated by protocol buffer compiler. Do not edit! +package edu.wpi.first.math.proto; + +import java.io.IOException; +import us.hebi.quickbuf.Descriptors; +import us.hebi.quickbuf.FieldName; +import us.hebi.quickbuf.InvalidProtocolBufferException; +import us.hebi.quickbuf.JsonSink; +import us.hebi.quickbuf.JsonSource; +import us.hebi.quickbuf.MessageFactory; +import us.hebi.quickbuf.ProtoMessage; +import us.hebi.quickbuf.ProtoSink; +import us.hebi.quickbuf.ProtoSource; +import us.hebi.quickbuf.ProtoUtil; +import us.hebi.quickbuf.RepeatedByte; + +public final class Controller { + private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(1684, + "ChBjb250cm9sbGVyLnByb3RvEgl3cGkucHJvdG8iWAoWUHJvdG9idWZBcm1GZWVkZm9yd2FyZBIOCgJr" + + "cxgBIAEoAVICa3MSDgoCa2cYAiABKAFSAmtnEg4KAmt2GAMgASgBUgJrdhIOCgJrYRgEIAEoAVICa2Ei" + + "ngEKJFByb3RvYnVmRGlmZmVyZW50aWFsRHJpdmVGZWVkZm9yd2FyZBIbCglrdl9saW5lYXIYASABKAFS" + + "CGt2TGluZWFyEhsKCWthX2xpbmVhchgCIAEoAVIIa2FMaW5lYXISHQoKa3ZfYW5ndWxhchgDIAEoAVIJ" + + "a3ZBbmd1bGFyEh0KCmthX2FuZ3VsYXIYBCABKAFSCWthQW5ndWxhciJdChtQcm90b2J1ZkVsZXZhdG9y" + + "RmVlZGZvcndhcmQSDgoCa3MYASABKAFSAmtzEg4KAmtnGAIgASgBUgJrZxIOCgJrdhgDIAEoAVICa3YS" + + "DgoCa2EYBCABKAFSAmthIlAKHlByb3RvYnVmU2ltcGxlTW90b3JGZWVkZm9yd2FyZBIOCgJrcxgBIAEo" + + "AVICa3MSDgoCa3YYAiABKAFSAmt2Eg4KAmthGAMgASgBUgJrYSJSCiZQcm90b2J1ZkRpZmZlcmVudGlh" + + "bERyaXZlV2hlZWxWb2x0YWdlcxISCgRsZWZ0GAEgASgBUgRsZWZ0EhQKBXJpZ2h0GAIgASgBUgVyaWdo" + + "dEIaChhlZHUud3BpLmZpcnN0Lm1hdGgucHJvdG9K0AgKBhIEAAAkAQoICgEMEgMAABIKCAoBAhIDAgAS" + + "CggKAQgSAwQAMQoJCgIIARIDBAAxCgoKAgQAEgQGAAsBCgoKAwQAARIDBggeCgsKBAQAAgASAwcCEAoM" + + "CgUEAAIABRIDBwIICgwKBQQAAgABEgMHCQsKDAoFBAACAAMSAwcODwoLCgQEAAIBEgMIAhAKDAoFBAAC" + + "AQUSAwgCCAoMCgUEAAIBARIDCAkLCgwKBQQAAgEDEgMIDg8KCwoEBAACAhIDCQIQCgwKBQQAAgIFEgMJ" + + "AggKDAoFBAACAgESAwkJCwoMCgUEAAICAxIDCQ4PCgsKBAQAAgMSAwoCEAoMCgUEAAIDBRIDCgIICgwK" + + "BQQAAgMBEgMKCQsKDAoFBAACAwMSAwoODwoKCgIEARIEDQASAQoKCgMEAQESAw0ILAoLCgQEAQIAEgMO" + + "AhcKDAoFBAECAAUSAw4CCAoMCgUEAQIAARIDDgkSCgwKBQQBAgADEgMOFRYKCwoEBAECARIDDwIXCgwK" + + "BQQBAgEFEgMPAggKDAoFBAECAQESAw8JEgoMCgUEAQIBAxIDDxUWCgsKBAQBAgISAxACGAoMCgUEAQIC" + + "BRIDEAIICgwKBQQBAgIBEgMQCRMKDAoFBAECAgMSAxAWFwoLCgQEAQIDEgMRAhgKDAoFBAECAwUSAxEC" + + "CAoMCgUEAQIDARIDEQkTCgwKBQQBAgMDEgMRFhcKCgoCBAISBBQAGQEKCgoDBAIBEgMUCCMKCwoEBAIC" + + "ABIDFQIQCgwKBQQCAgAFEgMVAggKDAoFBAICAAESAxUJCwoMCgUEAgIAAxIDFQ4PCgsKBAQCAgESAxYC", + "EAoMCgUEAgIBBRIDFgIICgwKBQQCAgEBEgMWCQsKDAoFBAICAQMSAxYODwoLCgQEAgICEgMXAhAKDAoF" + + "BAICAgUSAxcCCAoMCgUEAgICARIDFwkLCgwKBQQCAgIDEgMXDg8KCwoEBAICAxIDGAIQCgwKBQQCAgMF" + + "EgMYAggKDAoFBAICAwESAxgJCwoMCgUEAgIDAxIDGA4PCgoKAgQDEgQbAB8BCgoKAwQDARIDGwgmCgsK" + + "BAQDAgASAxwCEAoMCgUEAwIABRIDHAIICgwKBQQDAgABEgMcCQsKDAoFBAMCAAMSAxwODwoLCgQEAwIB" + + "EgMdAhAKDAoFBAMCAQUSAx0CCAoMCgUEAwIBARIDHQkLCgwKBQQDAgEDEgMdDg8KCwoEBAMCAhIDHgIQ" + + "CgwKBQQDAgIFEgMeAggKDAoFBAMCAgESAx4JCwoMCgUEAwICAxIDHg4PCgoKAgQEEgQhACQBCgoKAwQE" + + "ARIDIQguCgsKBAQEAgASAyICEgoMCgUEBAIABRIDIgIICgwKBQQEAgABEgMiCQ0KDAoFBAQCAAMSAyIQ" + + "EQoLCgQEBAIBEgMjAhMKDAoFBAQCAQUSAyMCCAoMCgUEBAIBARIDIwkOCgwKBQQEAgEDEgMjERJiBnBy" + + "b3RvMw=="); + + static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("controller.proto", "wpi.proto", descriptorData); + + static final Descriptors.Descriptor wpi_proto_ProtobufArmFeedforward_descriptor = descriptor.internalContainedType(31, 88, "ProtobufArmFeedforward", "wpi.proto.ProtobufArmFeedforward"); + + static final Descriptors.Descriptor wpi_proto_ProtobufDifferentialDriveFeedforward_descriptor = descriptor.internalContainedType(122, 158, "ProtobufDifferentialDriveFeedforward", "wpi.proto.ProtobufDifferentialDriveFeedforward"); + + static final Descriptors.Descriptor wpi_proto_ProtobufElevatorFeedforward_descriptor = descriptor.internalContainedType(282, 93, "ProtobufElevatorFeedforward", "wpi.proto.ProtobufElevatorFeedforward"); + + static final Descriptors.Descriptor wpi_proto_ProtobufSimpleMotorFeedforward_descriptor = descriptor.internalContainedType(377, 80, "ProtobufSimpleMotorFeedforward", "wpi.proto.ProtobufSimpleMotorFeedforward"); + + static final Descriptors.Descriptor wpi_proto_ProtobufDifferentialDriveWheelVoltages_descriptor = descriptor.internalContainedType(459, 82, "ProtobufDifferentialDriveWheelVoltages", "wpi.proto.ProtobufDifferentialDriveWheelVoltages"); + + /** + * @return this proto file's descriptor. + */ + public static Descriptors.FileDescriptor getDescriptor() { + return descriptor; + } + + /** + * Protobuf type {@code ProtobufArmFeedforward} + */ + public static final class ProtobufArmFeedforward extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double ks = 1; + */ + private double ks; + + /** + * optional double kg = 2; + */ + private double kg; + + /** + * optional double kv = 3; + */ + private double kv; + + /** + * optional double ka = 4; + */ + private double ka; + + private ProtobufArmFeedforward() { + } + + /** + * @return a new empty instance of {@code ProtobufArmFeedforward} + */ + public static ProtobufArmFeedforward newInstance() { + return new ProtobufArmFeedforward(); + } + + /** + * optional double ks = 1; + * @return whether the ks field is set + */ + public boolean hasKs() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double ks = 1; + * @return this + */ + public ProtobufArmFeedforward clearKs() { + bitField0_ &= ~0x00000001; + ks = 0D; + return this; + } + + /** + * optional double ks = 1; + * @return the ks + */ + public double getKs() { + return ks; + } + + /** + * optional double ks = 1; + * @param value the ks to set + * @return this + */ + public ProtobufArmFeedforward setKs(final double value) { + bitField0_ |= 0x00000001; + ks = value; + return this; + } + + /** + * optional double kg = 2; + * @return whether the kg field is set + */ + public boolean hasKg() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double kg = 2; + * @return this + */ + public ProtobufArmFeedforward clearKg() { + bitField0_ &= ~0x00000002; + kg = 0D; + return this; + } + + /** + * optional double kg = 2; + * @return the kg + */ + public double getKg() { + return kg; + } + + /** + * optional double kg = 2; + * @param value the kg to set + * @return this + */ + public ProtobufArmFeedforward setKg(final double value) { + bitField0_ |= 0x00000002; + kg = value; + return this; + } + + /** + * optional double kv = 3; + * @return whether the kv field is set + */ + public boolean hasKv() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional double kv = 3; + * @return this + */ + public ProtobufArmFeedforward clearKv() { + bitField0_ &= ~0x00000004; + kv = 0D; + return this; + } + + /** + * optional double kv = 3; + * @return the kv + */ + public double getKv() { + return kv; + } + + /** + * optional double kv = 3; + * @param value the kv to set + * @return this + */ + public ProtobufArmFeedforward setKv(final double value) { + bitField0_ |= 0x00000004; + kv = value; + return this; + } + + /** + * optional double ka = 4; + * @return whether the ka field is set + */ + public boolean hasKa() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * optional double ka = 4; + * @return this + */ + public ProtobufArmFeedforward clearKa() { + bitField0_ &= ~0x00000008; + ka = 0D; + return this; + } + + /** + * optional double ka = 4; + * @return the ka + */ + public double getKa() { + return ka; + } + + /** + * optional double ka = 4; + * @param value the ka to set + * @return this + */ + public ProtobufArmFeedforward setKa(final double value) { + bitField0_ |= 0x00000008; + ka = value; + return this; + } + + @Override + public ProtobufArmFeedforward copyFrom(final ProtobufArmFeedforward other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + ks = other.ks; + kg = other.kg; + kv = other.kv; + ka = other.ka; + } + return this; + } + + @Override + public ProtobufArmFeedforward mergeFrom(final ProtobufArmFeedforward other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasKs()) { + setKs(other.ks); + } + if (other.hasKg()) { + setKg(other.kg); + } + if (other.hasKv()) { + setKv(other.kv); + } + if (other.hasKa()) { + setKa(other.ka); + } + return this; + } + + @Override + public ProtobufArmFeedforward clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + ks = 0D; + kg = 0D; + kv = 0D; + ka = 0D; + return this; + } + + @Override + public ProtobufArmFeedforward clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufArmFeedforward)) { + return false; + } + ProtobufArmFeedforward other = (ProtobufArmFeedforward) o; + return bitField0_ == other.bitField0_ + && (!hasKs() || ProtoUtil.isEqual(ks, other.ks)) + && (!hasKg() || ProtoUtil.isEqual(kg, other.kg)) + && (!hasKv() || ProtoUtil.isEqual(kv, other.kv)) + && (!hasKa() || ProtoUtil.isEqual(ka, other.ka)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(ks); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(kg); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(kv); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRawByte((byte) 33); + output.writeDoubleNoTag(ka); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000004) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000008) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufArmFeedforward mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // ks + ks = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // kg + kg = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 25) { + break; + } + } + case 25: { + // kv + kv = input.readDouble(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 33) { + break; + } + } + case 33: { + // ka + ka = input.readDouble(); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.ks, ks); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.kg, kg); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeDouble(FieldNames.kv, kv); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeDouble(FieldNames.ka, ka); + } + output.endObject(); + } + + @Override + public ProtobufArmFeedforward mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 3432: { + if (input.isAtField(FieldNames.ks)) { + if (!input.trySkipNullValue()) { + ks = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3420: { + if (input.isAtField(FieldNames.kg)) { + if (!input.trySkipNullValue()) { + kg = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3435: { + if (input.isAtField(FieldNames.kv)) { + if (!input.trySkipNullValue()) { + kv = input.readDouble(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3414: { + if (input.isAtField(FieldNames.ka)) { + if (!input.trySkipNullValue()) { + ka = input.readDouble(); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufArmFeedforward clone() { + return new ProtobufArmFeedforward().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufArmFeedforward parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufArmFeedforward(), data).checkInitialized(); + } + + public static ProtobufArmFeedforward parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufArmFeedforward(), input).checkInitialized(); + } + + public static ProtobufArmFeedforward parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufArmFeedforward(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufArmFeedforward messages + */ + public static MessageFactory getFactory() { + return ProtobufArmFeedforwardFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Controller.wpi_proto_ProtobufArmFeedforward_descriptor; + } + + private enum ProtobufArmFeedforwardFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufArmFeedforward create() { + return ProtobufArmFeedforward.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName ks = FieldName.forField("ks"); + + static final FieldName kg = FieldName.forField("kg"); + + static final FieldName kv = FieldName.forField("kv"); + + static final FieldName ka = FieldName.forField("ka"); + } + } + + /** + * Protobuf type {@code ProtobufDifferentialDriveFeedforward} + */ + public static final class ProtobufDifferentialDriveFeedforward extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double kv_linear = 1; + */ + private double kvLinear; + + /** + * optional double ka_linear = 2; + */ + private double kaLinear; + + /** + * optional double kv_angular = 3; + */ + private double kvAngular; + + /** + * optional double ka_angular = 4; + */ + private double kaAngular; + + private ProtobufDifferentialDriveFeedforward() { + } + + /** + * @return a new empty instance of {@code ProtobufDifferentialDriveFeedforward} + */ + public static ProtobufDifferentialDriveFeedforward newInstance() { + return new ProtobufDifferentialDriveFeedforward(); + } + + /** + * optional double kv_linear = 1; + * @return whether the kvLinear field is set + */ + public boolean hasKvLinear() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double kv_linear = 1; + * @return this + */ + public ProtobufDifferentialDriveFeedforward clearKvLinear() { + bitField0_ &= ~0x00000001; + kvLinear = 0D; + return this; + } + + /** + * optional double kv_linear = 1; + * @return the kvLinear + */ + public double getKvLinear() { + return kvLinear; + } + + /** + * optional double kv_linear = 1; + * @param value the kvLinear to set + * @return this + */ + public ProtobufDifferentialDriveFeedforward setKvLinear(final double value) { + bitField0_ |= 0x00000001; + kvLinear = value; + return this; + } + + /** + * optional double ka_linear = 2; + * @return whether the kaLinear field is set + */ + public boolean hasKaLinear() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double ka_linear = 2; + * @return this + */ + public ProtobufDifferentialDriveFeedforward clearKaLinear() { + bitField0_ &= ~0x00000002; + kaLinear = 0D; + return this; + } + + /** + * optional double ka_linear = 2; + * @return the kaLinear + */ + public double getKaLinear() { + return kaLinear; + } + + /** + * optional double ka_linear = 2; + * @param value the kaLinear to set + * @return this + */ + public ProtobufDifferentialDriveFeedforward setKaLinear(final double value) { + bitField0_ |= 0x00000002; + kaLinear = value; + return this; + } + + /** + * optional double kv_angular = 3; + * @return whether the kvAngular field is set + */ + public boolean hasKvAngular() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional double kv_angular = 3; + * @return this + */ + public ProtobufDifferentialDriveFeedforward clearKvAngular() { + bitField0_ &= ~0x00000004; + kvAngular = 0D; + return this; + } + + /** + * optional double kv_angular = 3; + * @return the kvAngular + */ + public double getKvAngular() { + return kvAngular; + } + + /** + * optional double kv_angular = 3; + * @param value the kvAngular to set + * @return this + */ + public ProtobufDifferentialDriveFeedforward setKvAngular(final double value) { + bitField0_ |= 0x00000004; + kvAngular = value; + return this; + } + + /** + * optional double ka_angular = 4; + * @return whether the kaAngular field is set + */ + public boolean hasKaAngular() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * optional double ka_angular = 4; + * @return this + */ + public ProtobufDifferentialDriveFeedforward clearKaAngular() { + bitField0_ &= ~0x00000008; + kaAngular = 0D; + return this; + } + + /** + * optional double ka_angular = 4; + * @return the kaAngular + */ + public double getKaAngular() { + return kaAngular; + } + + /** + * optional double ka_angular = 4; + * @param value the kaAngular to set + * @return this + */ + public ProtobufDifferentialDriveFeedforward setKaAngular(final double value) { + bitField0_ |= 0x00000008; + kaAngular = value; + return this; + } + + @Override + public ProtobufDifferentialDriveFeedforward copyFrom( + final ProtobufDifferentialDriveFeedforward other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + kvLinear = other.kvLinear; + kaLinear = other.kaLinear; + kvAngular = other.kvAngular; + kaAngular = other.kaAngular; + } + return this; + } + + @Override + public ProtobufDifferentialDriveFeedforward mergeFrom( + final ProtobufDifferentialDriveFeedforward other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasKvLinear()) { + setKvLinear(other.kvLinear); + } + if (other.hasKaLinear()) { + setKaLinear(other.kaLinear); + } + if (other.hasKvAngular()) { + setKvAngular(other.kvAngular); + } + if (other.hasKaAngular()) { + setKaAngular(other.kaAngular); + } + return this; + } + + @Override + public ProtobufDifferentialDriveFeedforward clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + kvLinear = 0D; + kaLinear = 0D; + kvAngular = 0D; + kaAngular = 0D; + return this; + } + + @Override + public ProtobufDifferentialDriveFeedforward clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufDifferentialDriveFeedforward)) { + return false; + } + ProtobufDifferentialDriveFeedforward other = (ProtobufDifferentialDriveFeedforward) o; + return bitField0_ == other.bitField0_ + && (!hasKvLinear() || ProtoUtil.isEqual(kvLinear, other.kvLinear)) + && (!hasKaLinear() || ProtoUtil.isEqual(kaLinear, other.kaLinear)) + && (!hasKvAngular() || ProtoUtil.isEqual(kvAngular, other.kvAngular)) + && (!hasKaAngular() || ProtoUtil.isEqual(kaAngular, other.kaAngular)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(kvLinear); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(kaLinear); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(kvAngular); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRawByte((byte) 33); + output.writeDoubleNoTag(kaAngular); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000004) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000008) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufDifferentialDriveFeedforward mergeFrom(final ProtoSource input) throws + IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // kvLinear + kvLinear = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // kaLinear + kaLinear = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 25) { + break; + } + } + case 25: { + // kvAngular + kvAngular = input.readDouble(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 33) { + break; + } + } + case 33: { + // kaAngular + kaAngular = input.readDouble(); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.kvLinear, kvLinear); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.kaLinear, kaLinear); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeDouble(FieldNames.kvAngular, kvAngular); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeDouble(FieldNames.kaAngular, kaAngular); + } + output.endObject(); + } + + @Override + public ProtobufDifferentialDriveFeedforward mergeFrom(final JsonSource input) throws + IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 1424526448: + case 974889081: { + if (input.isAtField(FieldNames.kvLinear)) { + if (!input.trySkipNullValue()) { + kvLinear = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case -33181669: + case -1264389586: { + if (input.isAtField(FieldNames.kaLinear)) { + if (!input.trySkipNullValue()) { + kaLinear = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case 175208951: + case -878647538: { + if (input.isAtField(FieldNames.kvAngular)) { + if (!input.trySkipNullValue()) { + kvAngular = input.readDouble(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case -2064069716: + case -1576809479: { + if (input.isAtField(FieldNames.kaAngular)) { + if (!input.trySkipNullValue()) { + kaAngular = input.readDouble(); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufDifferentialDriveFeedforward clone() { + return new ProtobufDifferentialDriveFeedforward().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufDifferentialDriveFeedforward parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufDifferentialDriveFeedforward(), data).checkInitialized(); + } + + public static ProtobufDifferentialDriveFeedforward parseFrom(final ProtoSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufDifferentialDriveFeedforward(), input).checkInitialized(); + } + + public static ProtobufDifferentialDriveFeedforward parseFrom(final JsonSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufDifferentialDriveFeedforward(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufDifferentialDriveFeedforward messages + */ + public static MessageFactory getFactory() { + return ProtobufDifferentialDriveFeedforwardFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Controller.wpi_proto_ProtobufDifferentialDriveFeedforward_descriptor; + } + + private enum ProtobufDifferentialDriveFeedforwardFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufDifferentialDriveFeedforward create() { + return ProtobufDifferentialDriveFeedforward.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName kvLinear = FieldName.forField("kvLinear", "kv_linear"); + + static final FieldName kaLinear = FieldName.forField("kaLinear", "ka_linear"); + + static final FieldName kvAngular = FieldName.forField("kvAngular", "kv_angular"); + + static final FieldName kaAngular = FieldName.forField("kaAngular", "ka_angular"); + } + } + + /** + * Protobuf type {@code ProtobufElevatorFeedforward} + */ + public static final class ProtobufElevatorFeedforward extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double ks = 1; + */ + private double ks; + + /** + * optional double kg = 2; + */ + private double kg; + + /** + * optional double kv = 3; + */ + private double kv; + + /** + * optional double ka = 4; + */ + private double ka; + + private ProtobufElevatorFeedforward() { + } + + /** + * @return a new empty instance of {@code ProtobufElevatorFeedforward} + */ + public static ProtobufElevatorFeedforward newInstance() { + return new ProtobufElevatorFeedforward(); + } + + /** + * optional double ks = 1; + * @return whether the ks field is set + */ + public boolean hasKs() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double ks = 1; + * @return this + */ + public ProtobufElevatorFeedforward clearKs() { + bitField0_ &= ~0x00000001; + ks = 0D; + return this; + } + + /** + * optional double ks = 1; + * @return the ks + */ + public double getKs() { + return ks; + } + + /** + * optional double ks = 1; + * @param value the ks to set + * @return this + */ + public ProtobufElevatorFeedforward setKs(final double value) { + bitField0_ |= 0x00000001; + ks = value; + return this; + } + + /** + * optional double kg = 2; + * @return whether the kg field is set + */ + public boolean hasKg() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double kg = 2; + * @return this + */ + public ProtobufElevatorFeedforward clearKg() { + bitField0_ &= ~0x00000002; + kg = 0D; + return this; + } + + /** + * optional double kg = 2; + * @return the kg + */ + public double getKg() { + return kg; + } + + /** + * optional double kg = 2; + * @param value the kg to set + * @return this + */ + public ProtobufElevatorFeedforward setKg(final double value) { + bitField0_ |= 0x00000002; + kg = value; + return this; + } + + /** + * optional double kv = 3; + * @return whether the kv field is set + */ + public boolean hasKv() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional double kv = 3; + * @return this + */ + public ProtobufElevatorFeedforward clearKv() { + bitField0_ &= ~0x00000004; + kv = 0D; + return this; + } + + /** + * optional double kv = 3; + * @return the kv + */ + public double getKv() { + return kv; + } + + /** + * optional double kv = 3; + * @param value the kv to set + * @return this + */ + public ProtobufElevatorFeedforward setKv(final double value) { + bitField0_ |= 0x00000004; + kv = value; + return this; + } + + /** + * optional double ka = 4; + * @return whether the ka field is set + */ + public boolean hasKa() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * optional double ka = 4; + * @return this + */ + public ProtobufElevatorFeedforward clearKa() { + bitField0_ &= ~0x00000008; + ka = 0D; + return this; + } + + /** + * optional double ka = 4; + * @return the ka + */ + public double getKa() { + return ka; + } + + /** + * optional double ka = 4; + * @param value the ka to set + * @return this + */ + public ProtobufElevatorFeedforward setKa(final double value) { + bitField0_ |= 0x00000008; + ka = value; + return this; + } + + @Override + public ProtobufElevatorFeedforward copyFrom(final ProtobufElevatorFeedforward other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + ks = other.ks; + kg = other.kg; + kv = other.kv; + ka = other.ka; + } + return this; + } + + @Override + public ProtobufElevatorFeedforward mergeFrom(final ProtobufElevatorFeedforward other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasKs()) { + setKs(other.ks); + } + if (other.hasKg()) { + setKg(other.kg); + } + if (other.hasKv()) { + setKv(other.kv); + } + if (other.hasKa()) { + setKa(other.ka); + } + return this; + } + + @Override + public ProtobufElevatorFeedforward clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + ks = 0D; + kg = 0D; + kv = 0D; + ka = 0D; + return this; + } + + @Override + public ProtobufElevatorFeedforward clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufElevatorFeedforward)) { + return false; + } + ProtobufElevatorFeedforward other = (ProtobufElevatorFeedforward) o; + return bitField0_ == other.bitField0_ + && (!hasKs() || ProtoUtil.isEqual(ks, other.ks)) + && (!hasKg() || ProtoUtil.isEqual(kg, other.kg)) + && (!hasKv() || ProtoUtil.isEqual(kv, other.kv)) + && (!hasKa() || ProtoUtil.isEqual(ka, other.ka)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(ks); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(kg); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(kv); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRawByte((byte) 33); + output.writeDoubleNoTag(ka); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000004) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000008) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufElevatorFeedforward mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // ks + ks = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // kg + kg = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 25) { + break; + } + } + case 25: { + // kv + kv = input.readDouble(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 33) { + break; + } + } + case 33: { + // ka + ka = input.readDouble(); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.ks, ks); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.kg, kg); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeDouble(FieldNames.kv, kv); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeDouble(FieldNames.ka, ka); + } + output.endObject(); + } + + @Override + public ProtobufElevatorFeedforward mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 3432: { + if (input.isAtField(FieldNames.ks)) { + if (!input.trySkipNullValue()) { + ks = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3420: { + if (input.isAtField(FieldNames.kg)) { + if (!input.trySkipNullValue()) { + kg = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3435: { + if (input.isAtField(FieldNames.kv)) { + if (!input.trySkipNullValue()) { + kv = input.readDouble(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3414: { + if (input.isAtField(FieldNames.ka)) { + if (!input.trySkipNullValue()) { + ka = input.readDouble(); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufElevatorFeedforward clone() { + return new ProtobufElevatorFeedforward().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufElevatorFeedforward parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufElevatorFeedforward(), data).checkInitialized(); + } + + public static ProtobufElevatorFeedforward parseFrom(final ProtoSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufElevatorFeedforward(), input).checkInitialized(); + } + + public static ProtobufElevatorFeedforward parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufElevatorFeedforward(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufElevatorFeedforward messages + */ + public static MessageFactory getFactory() { + return ProtobufElevatorFeedforwardFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Controller.wpi_proto_ProtobufElevatorFeedforward_descriptor; + } + + private enum ProtobufElevatorFeedforwardFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufElevatorFeedforward create() { + return ProtobufElevatorFeedforward.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName ks = FieldName.forField("ks"); + + static final FieldName kg = FieldName.forField("kg"); + + static final FieldName kv = FieldName.forField("kv"); + + static final FieldName ka = FieldName.forField("ka"); + } + } + + /** + * Protobuf type {@code ProtobufSimpleMotorFeedforward} + */ + public static final class ProtobufSimpleMotorFeedforward extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double ks = 1; + */ + private double ks; + + /** + * optional double kv = 2; + */ + private double kv; + + /** + * optional double ka = 3; + */ + private double ka; + + private ProtobufSimpleMotorFeedforward() { + } + + /** + * @return a new empty instance of {@code ProtobufSimpleMotorFeedforward} + */ + public static ProtobufSimpleMotorFeedforward newInstance() { + return new ProtobufSimpleMotorFeedforward(); + } + + /** + * optional double ks = 1; + * @return whether the ks field is set + */ + public boolean hasKs() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double ks = 1; + * @return this + */ + public ProtobufSimpleMotorFeedforward clearKs() { + bitField0_ &= ~0x00000001; + ks = 0D; + return this; + } + + /** + * optional double ks = 1; + * @return the ks + */ + public double getKs() { + return ks; + } + + /** + * optional double ks = 1; + * @param value the ks to set + * @return this + */ + public ProtobufSimpleMotorFeedforward setKs(final double value) { + bitField0_ |= 0x00000001; + ks = value; + return this; + } + + /** + * optional double kv = 2; + * @return whether the kv field is set + */ + public boolean hasKv() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double kv = 2; + * @return this + */ + public ProtobufSimpleMotorFeedforward clearKv() { + bitField0_ &= ~0x00000002; + kv = 0D; + return this; + } + + /** + * optional double kv = 2; + * @return the kv + */ + public double getKv() { + return kv; + } + + /** + * optional double kv = 2; + * @param value the kv to set + * @return this + */ + public ProtobufSimpleMotorFeedforward setKv(final double value) { + bitField0_ |= 0x00000002; + kv = value; + return this; + } + + /** + * optional double ka = 3; + * @return whether the ka field is set + */ + public boolean hasKa() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional double ka = 3; + * @return this + */ + public ProtobufSimpleMotorFeedforward clearKa() { + bitField0_ &= ~0x00000004; + ka = 0D; + return this; + } + + /** + * optional double ka = 3; + * @return the ka + */ + public double getKa() { + return ka; + } + + /** + * optional double ka = 3; + * @param value the ka to set + * @return this + */ + public ProtobufSimpleMotorFeedforward setKa(final double value) { + bitField0_ |= 0x00000004; + ka = value; + return this; + } + + @Override + public ProtobufSimpleMotorFeedforward copyFrom(final ProtobufSimpleMotorFeedforward other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + ks = other.ks; + kv = other.kv; + ka = other.ka; + } + return this; + } + + @Override + public ProtobufSimpleMotorFeedforward mergeFrom(final ProtobufSimpleMotorFeedforward other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasKs()) { + setKs(other.ks); + } + if (other.hasKv()) { + setKv(other.kv); + } + if (other.hasKa()) { + setKa(other.ka); + } + return this; + } + + @Override + public ProtobufSimpleMotorFeedforward clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + ks = 0D; + kv = 0D; + ka = 0D; + return this; + } + + @Override + public ProtobufSimpleMotorFeedforward clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufSimpleMotorFeedforward)) { + return false; + } + ProtobufSimpleMotorFeedforward other = (ProtobufSimpleMotorFeedforward) o; + return bitField0_ == other.bitField0_ + && (!hasKs() || ProtoUtil.isEqual(ks, other.ks)) + && (!hasKv() || ProtoUtil.isEqual(kv, other.kv)) + && (!hasKa() || ProtoUtil.isEqual(ka, other.ka)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(ks); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(kv); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(ka); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000004) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufSimpleMotorFeedforward mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // ks + ks = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // kv + kv = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 25) { + break; + } + } + case 25: { + // ka + ka = input.readDouble(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.ks, ks); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.kv, kv); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeDouble(FieldNames.ka, ka); + } + output.endObject(); + } + + @Override + public ProtobufSimpleMotorFeedforward mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 3432: { + if (input.isAtField(FieldNames.ks)) { + if (!input.trySkipNullValue()) { + ks = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3435: { + if (input.isAtField(FieldNames.kv)) { + if (!input.trySkipNullValue()) { + kv = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3414: { + if (input.isAtField(FieldNames.ka)) { + if (!input.trySkipNullValue()) { + ka = input.readDouble(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufSimpleMotorFeedforward clone() { + return new ProtobufSimpleMotorFeedforward().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufSimpleMotorFeedforward parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufSimpleMotorFeedforward(), data).checkInitialized(); + } + + public static ProtobufSimpleMotorFeedforward parseFrom(final ProtoSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufSimpleMotorFeedforward(), input).checkInitialized(); + } + + public static ProtobufSimpleMotorFeedforward parseFrom(final JsonSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufSimpleMotorFeedforward(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufSimpleMotorFeedforward messages + */ + public static MessageFactory getFactory() { + return ProtobufSimpleMotorFeedforwardFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Controller.wpi_proto_ProtobufSimpleMotorFeedforward_descriptor; + } + + private enum ProtobufSimpleMotorFeedforwardFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufSimpleMotorFeedforward create() { + return ProtobufSimpleMotorFeedforward.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName ks = FieldName.forField("ks"); + + static final FieldName kv = FieldName.forField("kv"); + + static final FieldName ka = FieldName.forField("ka"); + } + } + + /** + * Protobuf type {@code ProtobufDifferentialDriveWheelVoltages} + */ + public static final class ProtobufDifferentialDriveWheelVoltages extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double left = 1; + */ + private double left; + + /** + * optional double right = 2; + */ + private double right; + + private ProtobufDifferentialDriveWheelVoltages() { + } + + /** + * @return a new empty instance of {@code ProtobufDifferentialDriveWheelVoltages} + */ + public static ProtobufDifferentialDriveWheelVoltages newInstance() { + return new ProtobufDifferentialDriveWheelVoltages(); + } + + /** + * optional double left = 1; + * @return whether the left field is set + */ + public boolean hasLeft() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double left = 1; + * @return this + */ + public ProtobufDifferentialDriveWheelVoltages clearLeft() { + bitField0_ &= ~0x00000001; + left = 0D; + return this; + } + + /** + * optional double left = 1; + * @return the left + */ + public double getLeft() { + return left; + } + + /** + * optional double left = 1; + * @param value the left to set + * @return this + */ + public ProtobufDifferentialDriveWheelVoltages setLeft(final double value) { + bitField0_ |= 0x00000001; + left = value; + return this; + } + + /** + * optional double right = 2; + * @return whether the right field is set + */ + public boolean hasRight() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double right = 2; + * @return this + */ + public ProtobufDifferentialDriveWheelVoltages clearRight() { + bitField0_ &= ~0x00000002; + right = 0D; + return this; + } + + /** + * optional double right = 2; + * @return the right + */ + public double getRight() { + return right; + } + + /** + * optional double right = 2; + * @param value the right to set + * @return this + */ + public ProtobufDifferentialDriveWheelVoltages setRight(final double value) { + bitField0_ |= 0x00000002; + right = value; + return this; + } + + @Override + public ProtobufDifferentialDriveWheelVoltages copyFrom( + final ProtobufDifferentialDriveWheelVoltages other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + left = other.left; + right = other.right; + } + return this; + } + + @Override + public ProtobufDifferentialDriveWheelVoltages mergeFrom( + final ProtobufDifferentialDriveWheelVoltages other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasLeft()) { + setLeft(other.left); + } + if (other.hasRight()) { + setRight(other.right); + } + return this; + } + + @Override + public ProtobufDifferentialDriveWheelVoltages clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + left = 0D; + right = 0D; + return this; + } + + @Override + public ProtobufDifferentialDriveWheelVoltages clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufDifferentialDriveWheelVoltages)) { + return false; + } + ProtobufDifferentialDriveWheelVoltages other = (ProtobufDifferentialDriveWheelVoltages) o; + return bitField0_ == other.bitField0_ + && (!hasLeft() || ProtoUtil.isEqual(left, other.left)) + && (!hasRight() || ProtoUtil.isEqual(right, other.right)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(left); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(right); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufDifferentialDriveWheelVoltages mergeFrom(final ProtoSource input) throws + IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // left + left = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // right + right = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.left, left); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.right, right); + } + output.endObject(); + } + + @Override + public ProtobufDifferentialDriveWheelVoltages mergeFrom(final JsonSource input) throws + IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 3317767: { + if (input.isAtField(FieldNames.left)) { + if (!input.trySkipNullValue()) { + left = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 108511772: { + if (input.isAtField(FieldNames.right)) { + if (!input.trySkipNullValue()) { + right = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufDifferentialDriveWheelVoltages clone() { + return new ProtobufDifferentialDriveWheelVoltages().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufDifferentialDriveWheelVoltages parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufDifferentialDriveWheelVoltages(), data).checkInitialized(); + } + + public static ProtobufDifferentialDriveWheelVoltages parseFrom(final ProtoSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufDifferentialDriveWheelVoltages(), input).checkInitialized(); + } + + public static ProtobufDifferentialDriveWheelVoltages parseFrom(final JsonSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufDifferentialDriveWheelVoltages(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufDifferentialDriveWheelVoltages messages + */ + public static MessageFactory getFactory() { + return ProtobufDifferentialDriveWheelVoltagesFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Controller.wpi_proto_ProtobufDifferentialDriveWheelVoltages_descriptor; + } + + private enum ProtobufDifferentialDriveWheelVoltagesFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufDifferentialDriveWheelVoltages create() { + return ProtobufDifferentialDriveWheelVoltages.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName left = FieldName.forField("left"); + + static final FieldName right = FieldName.forField("right"); + } + } +} diff --git a/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Geometry2D.java b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Geometry2D.java new file mode 100644 index 00000000000..331ccd1c8ad --- /dev/null +++ b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Geometry2D.java @@ -0,0 +1,1806 @@ +// 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. +// Code generated by protocol buffer compiler. Do not edit! +package edu.wpi.first.math.proto; + +import java.io.IOException; +import us.hebi.quickbuf.Descriptors; +import us.hebi.quickbuf.FieldName; +import us.hebi.quickbuf.InvalidProtocolBufferException; +import us.hebi.quickbuf.JsonSink; +import us.hebi.quickbuf.JsonSource; +import us.hebi.quickbuf.MessageFactory; +import us.hebi.quickbuf.ProtoMessage; +import us.hebi.quickbuf.ProtoSink; +import us.hebi.quickbuf.ProtoSource; +import us.hebi.quickbuf.ProtoUtil; +import us.hebi.quickbuf.RepeatedByte; + +public final class Geometry2D { + private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(1256, + "ChBnZW9tZXRyeTJkLnByb3RvEgl3cGkucHJvdG8iMwoVUHJvdG9idWZUcmFuc2xhdGlvbjJkEgwKAXgY" + + "ASABKAFSAXgSDAoBeRgCIAEoAVIBeSIqChJQcm90b2J1ZlJvdGF0aW9uMmQSFAoFdmFsdWUYASABKAFS" + + "BXZhbHVlIo8BCg5Qcm90b2J1ZlBvc2UyZBJCCgt0cmFuc2xhdGlvbhgBIAEoCzIgLndwaS5wcm90by5Q" + + "cm90b2J1ZlRyYW5zbGF0aW9uMmRSC3RyYW5zbGF0aW9uEjkKCHJvdGF0aW9uGAIgASgLMh0ud3BpLnBy" + + "b3RvLlByb3RvYnVmUm90YXRpb24yZFIIcm90YXRpb24ilAEKE1Byb3RvYnVmVHJhbnNmb3JtMmQSQgoL" + + "dHJhbnNsYXRpb24YASABKAsyIC53cGkucHJvdG8uUHJvdG9idWZUcmFuc2xhdGlvbjJkUgt0cmFuc2xh" + + "dGlvbhI5Cghyb3RhdGlvbhgCIAEoCzIdLndwaS5wcm90by5Qcm90b2J1ZlJvdGF0aW9uMmRSCHJvdGF0" + + "aW9uIkkKD1Byb3RvYnVmVHdpc3QyZBIOCgJkeBgBIAEoAVICZHgSDgoCZHkYAiABKAFSAmR5EhYKBmR0" + + "aGV0YRgDIAEoAVIGZHRoZXRhQhoKGGVkdS53cGkuZmlyc3QubWF0aC5wcm90b0rPBQoGEgQAAB0BCggK" + + "AQwSAwAAEgoICgECEgMCABIKCAoBCBIDBAAxCgkKAggBEgMEADEKCgoCBAASBAYACQEKCgoDBAABEgMG" + + "CB0KCwoEBAACABIDBwIPCgwKBQQAAgAFEgMHAggKDAoFBAACAAESAwcJCgoMCgUEAAIAAxIDBw0OCgsK" + + "BAQAAgESAwgCDwoMCgUEAAIBBRIDCAIICgwKBQQAAgEBEgMICQoKDAoFBAACAQMSAwgNDgoKCgIEARIE" + + "CwANAQoKCgMEAQESAwsIGgoLCgQEAQIAEgMMAhMKDAoFBAECAAUSAwwCCAoMCgUEAQIAARIDDAkOCgwK" + + "BQQBAgADEgMMERIKCgoCBAISBA8AEgEKCgoDBAIBEgMPCBYKCwoEBAICABIDEAIoCgwKBQQCAgAGEgMQ" + + "AhcKDAoFBAICAAESAxAYIwoMCgUEAgIAAxIDECYnCgsKBAQCAgESAxECIgoMCgUEAgIBBhIDEQIUCgwK" + + "BQQCAgEBEgMRFR0KDAoFBAICAQMSAxEgIQoKCgIEAxIEFAAXAQoKCgMEAwESAxQIGwoLCgQEAwIAEgMV" + + "AigKDAoFBAMCAAYSAxUCFwoMCgUEAwIAARIDFRgjCgwKBQQDAgADEgMVJicKCwoEBAMCARIDFgIiCgwK" + + "BQQDAgEGEgMWAhQKDAoFBAMCAQESAxYVHQoMCgUEAwIBAxIDFiAhCgoKAgQEEgQZAB0BCgoKAwQEARID" + + "GQgXCgsKBAQEAgASAxoCEAoMCgUEBAIABRIDGgIICgwKBQQEAgABEgMaCQsKDAoFBAQCAAMSAxoODwoL" + + "CgQEBAIBEgMbAhAKDAoFBAQCAQUSAxsCCAoMCgUEBAIBARIDGwkLCgwKBQQEAgEDEgMbDg8KCwoEBAQC", + "AhIDHAIUCgwKBQQEAgIFEgMcAggKDAoFBAQCAgESAxwJDwoMCgUEBAICAxIDHBITYgZwcm90bzM="); + + static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("geometry2d.proto", "wpi.proto", descriptorData); + + static final Descriptors.Descriptor wpi_proto_ProtobufTranslation2d_descriptor = descriptor.internalContainedType(31, 51, "ProtobufTranslation2d", "wpi.proto.ProtobufTranslation2d"); + + static final Descriptors.Descriptor wpi_proto_ProtobufRotation2d_descriptor = descriptor.internalContainedType(84, 42, "ProtobufRotation2d", "wpi.proto.ProtobufRotation2d"); + + static final Descriptors.Descriptor wpi_proto_ProtobufPose2d_descriptor = descriptor.internalContainedType(129, 143, "ProtobufPose2d", "wpi.proto.ProtobufPose2d"); + + static final Descriptors.Descriptor wpi_proto_ProtobufTransform2d_descriptor = descriptor.internalContainedType(275, 148, "ProtobufTransform2d", "wpi.proto.ProtobufTransform2d"); + + static final Descriptors.Descriptor wpi_proto_ProtobufTwist2d_descriptor = descriptor.internalContainedType(425, 73, "ProtobufTwist2d", "wpi.proto.ProtobufTwist2d"); + + /** + * @return this proto file's descriptor. + */ + public static Descriptors.FileDescriptor getDescriptor() { + return descriptor; + } + + /** + * Protobuf type {@code ProtobufTranslation2d} + */ + public static final class ProtobufTranslation2d extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double x = 1; + */ + private double x; + + /** + * optional double y = 2; + */ + private double y; + + private ProtobufTranslation2d() { + } + + /** + * @return a new empty instance of {@code ProtobufTranslation2d} + */ + public static ProtobufTranslation2d newInstance() { + return new ProtobufTranslation2d(); + } + + /** + * optional double x = 1; + * @return whether the x field is set + */ + public boolean hasX() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double x = 1; + * @return this + */ + public ProtobufTranslation2d clearX() { + bitField0_ &= ~0x00000001; + x = 0D; + return this; + } + + /** + * optional double x = 1; + * @return the x + */ + public double getX() { + return x; + } + + /** + * optional double x = 1; + * @param value the x to set + * @return this + */ + public ProtobufTranslation2d setX(final double value) { + bitField0_ |= 0x00000001; + x = value; + return this; + } + + /** + * optional double y = 2; + * @return whether the y field is set + */ + public boolean hasY() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double y = 2; + * @return this + */ + public ProtobufTranslation2d clearY() { + bitField0_ &= ~0x00000002; + y = 0D; + return this; + } + + /** + * optional double y = 2; + * @return the y + */ + public double getY() { + return y; + } + + /** + * optional double y = 2; + * @param value the y to set + * @return this + */ + public ProtobufTranslation2d setY(final double value) { + bitField0_ |= 0x00000002; + y = value; + return this; + } + + @Override + public ProtobufTranslation2d copyFrom(final ProtobufTranslation2d other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + x = other.x; + y = other.y; + } + return this; + } + + @Override + public ProtobufTranslation2d mergeFrom(final ProtobufTranslation2d other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasX()) { + setX(other.x); + } + if (other.hasY()) { + setY(other.y); + } + return this; + } + + @Override + public ProtobufTranslation2d clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + x = 0D; + y = 0D; + return this; + } + + @Override + public ProtobufTranslation2d clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufTranslation2d)) { + return false; + } + ProtobufTranslation2d other = (ProtobufTranslation2d) o; + return bitField0_ == other.bitField0_ + && (!hasX() || ProtoUtil.isEqual(x, other.x)) + && (!hasY() || ProtoUtil.isEqual(y, other.y)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(x); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(y); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufTranslation2d mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // x + x = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // y + y = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.x, x); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.y, y); + } + output.endObject(); + } + + @Override + public ProtobufTranslation2d mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 120: { + if (input.isAtField(FieldNames.x)) { + if (!input.trySkipNullValue()) { + x = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 121: { + if (input.isAtField(FieldNames.y)) { + if (!input.trySkipNullValue()) { + y = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufTranslation2d clone() { + return new ProtobufTranslation2d().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufTranslation2d parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufTranslation2d(), data).checkInitialized(); + } + + public static ProtobufTranslation2d parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTranslation2d(), input).checkInitialized(); + } + + public static ProtobufTranslation2d parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTranslation2d(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufTranslation2d messages + */ + public static MessageFactory getFactory() { + return ProtobufTranslation2dFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Geometry2D.wpi_proto_ProtobufTranslation2d_descriptor; + } + + private enum ProtobufTranslation2dFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufTranslation2d create() { + return ProtobufTranslation2d.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName x = FieldName.forField("x"); + + static final FieldName y = FieldName.forField("y"); + } + } + + /** + * Protobuf type {@code ProtobufRotation2d} + */ + public static final class ProtobufRotation2d extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double value = 1; + */ + private double value_; + + private ProtobufRotation2d() { + } + + /** + * @return a new empty instance of {@code ProtobufRotation2d} + */ + public static ProtobufRotation2d newInstance() { + return new ProtobufRotation2d(); + } + + /** + * optional double value = 1; + * @return whether the value_ field is set + */ + public boolean hasValue() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double value = 1; + * @return this + */ + public ProtobufRotation2d clearValue() { + bitField0_ &= ~0x00000001; + value_ = 0D; + return this; + } + + /** + * optional double value = 1; + * @return the value_ + */ + public double getValue() { + return value_; + } + + /** + * optional double value = 1; + * @param value the value_ to set + * @return this + */ + public ProtobufRotation2d setValue(final double value) { + bitField0_ |= 0x00000001; + value_ = value; + return this; + } + + @Override + public ProtobufRotation2d copyFrom(final ProtobufRotation2d other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + value_ = other.value_; + } + return this; + } + + @Override + public ProtobufRotation2d mergeFrom(final ProtobufRotation2d other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasValue()) { + setValue(other.value_); + } + return this; + } + + @Override + public ProtobufRotation2d clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + value_ = 0D; + return this; + } + + @Override + public ProtobufRotation2d clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufRotation2d)) { + return false; + } + ProtobufRotation2d other = (ProtobufRotation2d) o; + return bitField0_ == other.bitField0_ + && (!hasValue() || ProtoUtil.isEqual(value_, other.value_)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(value_); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufRotation2d mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // value_ + value_ = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.value_, value_); + } + output.endObject(); + } + + @Override + public ProtobufRotation2d mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 111972721: { + if (input.isAtField(FieldNames.value_)) { + if (!input.trySkipNullValue()) { + value_ = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufRotation2d clone() { + return new ProtobufRotation2d().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufRotation2d parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufRotation2d(), data).checkInitialized(); + } + + public static ProtobufRotation2d parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufRotation2d(), input).checkInitialized(); + } + + public static ProtobufRotation2d parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufRotation2d(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufRotation2d messages + */ + public static MessageFactory getFactory() { + return ProtobufRotation2dFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Geometry2D.wpi_proto_ProtobufRotation2d_descriptor; + } + + private enum ProtobufRotation2dFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufRotation2d create() { + return ProtobufRotation2d.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName value_ = FieldName.forField("value"); + } + } + + /** + * Protobuf type {@code ProtobufPose2d} + */ + public static final class ProtobufPose2d extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional .wpi.proto.ProtobufTranslation2d translation = 1; + */ + private final ProtobufTranslation2d translation = ProtobufTranslation2d.newInstance(); + + /** + * optional .wpi.proto.ProtobufRotation2d rotation = 2; + */ + private final ProtobufRotation2d rotation = ProtobufRotation2d.newInstance(); + + private ProtobufPose2d() { + } + + /** + * @return a new empty instance of {@code ProtobufPose2d} + */ + public static ProtobufPose2d newInstance() { + return new ProtobufPose2d(); + } + + /** + * optional .wpi.proto.ProtobufTranslation2d translation = 1; + * @return whether the translation field is set + */ + public boolean hasTranslation() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d translation = 1; + * @return this + */ + public ProtobufPose2d clearTranslation() { + bitField0_ &= ~0x00000001; + translation.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d translation = 1; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableTranslation()} if you want to modify it. + * + * @return internal storage object for reading + */ + public ProtobufTranslation2d getTranslation() { + return translation; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d translation = 1; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public ProtobufTranslation2d getMutableTranslation() { + bitField0_ |= 0x00000001; + return translation; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d translation = 1; + * @param value the translation to set + * @return this + */ + public ProtobufPose2d setTranslation(final ProtobufTranslation2d value) { + bitField0_ |= 0x00000001; + translation.copyFrom(value); + return this; + } + + /** + * optional .wpi.proto.ProtobufRotation2d rotation = 2; + * @return whether the rotation field is set + */ + public boolean hasRotation() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional .wpi.proto.ProtobufRotation2d rotation = 2; + * @return this + */ + public ProtobufPose2d clearRotation() { + bitField0_ &= ~0x00000002; + rotation.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufRotation2d rotation = 2; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableRotation()} if you want to modify it. + * + * @return internal storage object for reading + */ + public ProtobufRotation2d getRotation() { + return rotation; + } + + /** + * optional .wpi.proto.ProtobufRotation2d rotation = 2; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public ProtobufRotation2d getMutableRotation() { + bitField0_ |= 0x00000002; + return rotation; + } + + /** + * optional .wpi.proto.ProtobufRotation2d rotation = 2; + * @param value the rotation to set + * @return this + */ + public ProtobufPose2d setRotation(final ProtobufRotation2d value) { + bitField0_ |= 0x00000002; + rotation.copyFrom(value); + return this; + } + + @Override + public ProtobufPose2d copyFrom(final ProtobufPose2d other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + translation.copyFrom(other.translation); + rotation.copyFrom(other.rotation); + } + return this; + } + + @Override + public ProtobufPose2d mergeFrom(final ProtobufPose2d other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasTranslation()) { + getMutableTranslation().mergeFrom(other.translation); + } + if (other.hasRotation()) { + getMutableRotation().mergeFrom(other.rotation); + } + return this; + } + + @Override + public ProtobufPose2d clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + translation.clear(); + rotation.clear(); + return this; + } + + @Override + public ProtobufPose2d clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + translation.clearQuick(); + rotation.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufPose2d)) { + return false; + } + ProtobufPose2d other = (ProtobufPose2d) o; + return bitField0_ == other.bitField0_ + && (!hasTranslation() || translation.equals(other.translation)) + && (!hasRotation() || rotation.equals(other.rotation)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 10); + output.writeMessageNoTag(translation); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 18); + output.writeMessageNoTag(rotation); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(translation); + } + if ((bitField0_ & 0x00000002) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(rotation); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufPose2d mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 10: { + // translation + input.readMessage(translation); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 18) { + break; + } + } + case 18: { + // rotation + input.readMessage(rotation); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeMessage(FieldNames.translation, translation); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeMessage(FieldNames.rotation, rotation); + } + output.endObject(); + } + + @Override + public ProtobufPose2d mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case -1840647503: { + if (input.isAtField(FieldNames.translation)) { + if (!input.trySkipNullValue()) { + input.readMessage(translation); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case -40300674: { + if (input.isAtField(FieldNames.rotation)) { + if (!input.trySkipNullValue()) { + input.readMessage(rotation); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufPose2d clone() { + return new ProtobufPose2d().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufPose2d parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufPose2d(), data).checkInitialized(); + } + + public static ProtobufPose2d parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufPose2d(), input).checkInitialized(); + } + + public static ProtobufPose2d parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufPose2d(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufPose2d messages + */ + public static MessageFactory getFactory() { + return ProtobufPose2dFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Geometry2D.wpi_proto_ProtobufPose2d_descriptor; + } + + private enum ProtobufPose2dFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufPose2d create() { + return ProtobufPose2d.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName translation = FieldName.forField("translation"); + + static final FieldName rotation = FieldName.forField("rotation"); + } + } + + /** + * Protobuf type {@code ProtobufTransform2d} + */ + public static final class ProtobufTransform2d extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional .wpi.proto.ProtobufTranslation2d translation = 1; + */ + private final ProtobufTranslation2d translation = ProtobufTranslation2d.newInstance(); + + /** + * optional .wpi.proto.ProtobufRotation2d rotation = 2; + */ + private final ProtobufRotation2d rotation = ProtobufRotation2d.newInstance(); + + private ProtobufTransform2d() { + } + + /** + * @return a new empty instance of {@code ProtobufTransform2d} + */ + public static ProtobufTransform2d newInstance() { + return new ProtobufTransform2d(); + } + + /** + * optional .wpi.proto.ProtobufTranslation2d translation = 1; + * @return whether the translation field is set + */ + public boolean hasTranslation() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d translation = 1; + * @return this + */ + public ProtobufTransform2d clearTranslation() { + bitField0_ &= ~0x00000001; + translation.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d translation = 1; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableTranslation()} if you want to modify it. + * + * @return internal storage object for reading + */ + public ProtobufTranslation2d getTranslation() { + return translation; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d translation = 1; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public ProtobufTranslation2d getMutableTranslation() { + bitField0_ |= 0x00000001; + return translation; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d translation = 1; + * @param value the translation to set + * @return this + */ + public ProtobufTransform2d setTranslation(final ProtobufTranslation2d value) { + bitField0_ |= 0x00000001; + translation.copyFrom(value); + return this; + } + + /** + * optional .wpi.proto.ProtobufRotation2d rotation = 2; + * @return whether the rotation field is set + */ + public boolean hasRotation() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional .wpi.proto.ProtobufRotation2d rotation = 2; + * @return this + */ + public ProtobufTransform2d clearRotation() { + bitField0_ &= ~0x00000002; + rotation.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufRotation2d rotation = 2; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableRotation()} if you want to modify it. + * + * @return internal storage object for reading + */ + public ProtobufRotation2d getRotation() { + return rotation; + } + + /** + * optional .wpi.proto.ProtobufRotation2d rotation = 2; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public ProtobufRotation2d getMutableRotation() { + bitField0_ |= 0x00000002; + return rotation; + } + + /** + * optional .wpi.proto.ProtobufRotation2d rotation = 2; + * @param value the rotation to set + * @return this + */ + public ProtobufTransform2d setRotation(final ProtobufRotation2d value) { + bitField0_ |= 0x00000002; + rotation.copyFrom(value); + return this; + } + + @Override + public ProtobufTransform2d copyFrom(final ProtobufTransform2d other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + translation.copyFrom(other.translation); + rotation.copyFrom(other.rotation); + } + return this; + } + + @Override + public ProtobufTransform2d mergeFrom(final ProtobufTransform2d other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasTranslation()) { + getMutableTranslation().mergeFrom(other.translation); + } + if (other.hasRotation()) { + getMutableRotation().mergeFrom(other.rotation); + } + return this; + } + + @Override + public ProtobufTransform2d clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + translation.clear(); + rotation.clear(); + return this; + } + + @Override + public ProtobufTransform2d clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + translation.clearQuick(); + rotation.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufTransform2d)) { + return false; + } + ProtobufTransform2d other = (ProtobufTransform2d) o; + return bitField0_ == other.bitField0_ + && (!hasTranslation() || translation.equals(other.translation)) + && (!hasRotation() || rotation.equals(other.rotation)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 10); + output.writeMessageNoTag(translation); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 18); + output.writeMessageNoTag(rotation); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(translation); + } + if ((bitField0_ & 0x00000002) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(rotation); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufTransform2d mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 10: { + // translation + input.readMessage(translation); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 18) { + break; + } + } + case 18: { + // rotation + input.readMessage(rotation); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeMessage(FieldNames.translation, translation); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeMessage(FieldNames.rotation, rotation); + } + output.endObject(); + } + + @Override + public ProtobufTransform2d mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case -1840647503: { + if (input.isAtField(FieldNames.translation)) { + if (!input.trySkipNullValue()) { + input.readMessage(translation); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case -40300674: { + if (input.isAtField(FieldNames.rotation)) { + if (!input.trySkipNullValue()) { + input.readMessage(rotation); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufTransform2d clone() { + return new ProtobufTransform2d().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufTransform2d parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufTransform2d(), data).checkInitialized(); + } + + public static ProtobufTransform2d parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTransform2d(), input).checkInitialized(); + } + + public static ProtobufTransform2d parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTransform2d(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufTransform2d messages + */ + public static MessageFactory getFactory() { + return ProtobufTransform2dFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Geometry2D.wpi_proto_ProtobufTransform2d_descriptor; + } + + private enum ProtobufTransform2dFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufTransform2d create() { + return ProtobufTransform2d.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName translation = FieldName.forField("translation"); + + static final FieldName rotation = FieldName.forField("rotation"); + } + } + + /** + * Protobuf type {@code ProtobufTwist2d} + */ + public static final class ProtobufTwist2d extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double dx = 1; + */ + private double dx; + + /** + * optional double dy = 2; + */ + private double dy; + + /** + * optional double dtheta = 3; + */ + private double dtheta; + + private ProtobufTwist2d() { + } + + /** + * @return a new empty instance of {@code ProtobufTwist2d} + */ + public static ProtobufTwist2d newInstance() { + return new ProtobufTwist2d(); + } + + /** + * optional double dx = 1; + * @return whether the dx field is set + */ + public boolean hasDx() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double dx = 1; + * @return this + */ + public ProtobufTwist2d clearDx() { + bitField0_ &= ~0x00000001; + dx = 0D; + return this; + } + + /** + * optional double dx = 1; + * @return the dx + */ + public double getDx() { + return dx; + } + + /** + * optional double dx = 1; + * @param value the dx to set + * @return this + */ + public ProtobufTwist2d setDx(final double value) { + bitField0_ |= 0x00000001; + dx = value; + return this; + } + + /** + * optional double dy = 2; + * @return whether the dy field is set + */ + public boolean hasDy() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double dy = 2; + * @return this + */ + public ProtobufTwist2d clearDy() { + bitField0_ &= ~0x00000002; + dy = 0D; + return this; + } + + /** + * optional double dy = 2; + * @return the dy + */ + public double getDy() { + return dy; + } + + /** + * optional double dy = 2; + * @param value the dy to set + * @return this + */ + public ProtobufTwist2d setDy(final double value) { + bitField0_ |= 0x00000002; + dy = value; + return this; + } + + /** + * optional double dtheta = 3; + * @return whether the dtheta field is set + */ + public boolean hasDtheta() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional double dtheta = 3; + * @return this + */ + public ProtobufTwist2d clearDtheta() { + bitField0_ &= ~0x00000004; + dtheta = 0D; + return this; + } + + /** + * optional double dtheta = 3; + * @return the dtheta + */ + public double getDtheta() { + return dtheta; + } + + /** + * optional double dtheta = 3; + * @param value the dtheta to set + * @return this + */ + public ProtobufTwist2d setDtheta(final double value) { + bitField0_ |= 0x00000004; + dtheta = value; + return this; + } + + @Override + public ProtobufTwist2d copyFrom(final ProtobufTwist2d other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + dx = other.dx; + dy = other.dy; + dtheta = other.dtheta; + } + return this; + } + + @Override + public ProtobufTwist2d mergeFrom(final ProtobufTwist2d other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasDx()) { + setDx(other.dx); + } + if (other.hasDy()) { + setDy(other.dy); + } + if (other.hasDtheta()) { + setDtheta(other.dtheta); + } + return this; + } + + @Override + public ProtobufTwist2d clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + dx = 0D; + dy = 0D; + dtheta = 0D; + return this; + } + + @Override + public ProtobufTwist2d clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufTwist2d)) { + return false; + } + ProtobufTwist2d other = (ProtobufTwist2d) o; + return bitField0_ == other.bitField0_ + && (!hasDx() || ProtoUtil.isEqual(dx, other.dx)) + && (!hasDy() || ProtoUtil.isEqual(dy, other.dy)) + && (!hasDtheta() || ProtoUtil.isEqual(dtheta, other.dtheta)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(dx); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(dy); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(dtheta); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000004) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufTwist2d mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // dx + dx = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // dy + dy = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 25) { + break; + } + } + case 25: { + // dtheta + dtheta = input.readDouble(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.dx, dx); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.dy, dy); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeDouble(FieldNames.dtheta, dtheta); + } + output.endObject(); + } + + @Override + public ProtobufTwist2d mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 3220: { + if (input.isAtField(FieldNames.dx)) { + if (!input.trySkipNullValue()) { + dx = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3221: { + if (input.isAtField(FieldNames.dy)) { + if (!input.trySkipNullValue()) { + dy = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case -1321724742: { + if (input.isAtField(FieldNames.dtheta)) { + if (!input.trySkipNullValue()) { + dtheta = input.readDouble(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufTwist2d clone() { + return new ProtobufTwist2d().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufTwist2d parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufTwist2d(), data).checkInitialized(); + } + + public static ProtobufTwist2d parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTwist2d(), input).checkInitialized(); + } + + public static ProtobufTwist2d parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTwist2d(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufTwist2d messages + */ + public static MessageFactory getFactory() { + return ProtobufTwist2dFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Geometry2D.wpi_proto_ProtobufTwist2d_descriptor; + } + + private enum ProtobufTwist2dFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufTwist2d create() { + return ProtobufTwist2d.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName dx = FieldName.forField("dx"); + + static final FieldName dy = FieldName.forField("dy"); + + static final FieldName dtheta = FieldName.forField("dtheta"); + } + } +} diff --git a/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Geometry3D.java b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Geometry3D.java new file mode 100644 index 00000000000..404d7b0719e --- /dev/null +++ b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Geometry3D.java @@ -0,0 +1,2652 @@ +// 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. +// Code generated by protocol buffer compiler. Do not edit! +package edu.wpi.first.math.proto; + +import java.io.IOException; +import us.hebi.quickbuf.Descriptors; +import us.hebi.quickbuf.FieldName; +import us.hebi.quickbuf.InvalidProtocolBufferException; +import us.hebi.quickbuf.JsonSink; +import us.hebi.quickbuf.JsonSource; +import us.hebi.quickbuf.MessageFactory; +import us.hebi.quickbuf.ProtoMessage; +import us.hebi.quickbuf.ProtoSink; +import us.hebi.quickbuf.ProtoSource; +import us.hebi.quickbuf.ProtoUtil; +import us.hebi.quickbuf.RepeatedByte; + +public final class Geometry3D { + private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(1875, + "ChBnZW9tZXRyeTNkLnByb3RvEgl3cGkucHJvdG8iQQoVUHJvdG9idWZUcmFuc2xhdGlvbjNkEgwKAXgY" + + "ASABKAFSAXgSDAoBeRgCIAEoAVIBeRIMCgF6GAMgASgBUgF6IkwKElByb3RvYnVmUXVhdGVybmlvbhIM" + + "CgF3GAEgASgBUgF3EgwKAXgYAiABKAFSAXgSDAoBeRgDIAEoAVIBeRIMCgF6GAQgASgBUgF6IkEKElBy" + + "b3RvYnVmUm90YXRpb24zZBIrCgFxGAEgASgLMh0ud3BpLnByb3RvLlByb3RvYnVmUXVhdGVybmlvblIB" + + "cSKPAQoOUHJvdG9idWZQb3NlM2QSQgoLdHJhbnNsYXRpb24YASABKAsyIC53cGkucHJvdG8uUHJvdG9i" + + "dWZUcmFuc2xhdGlvbjNkUgt0cmFuc2xhdGlvbhI5Cghyb3RhdGlvbhgCIAEoCzIdLndwaS5wcm90by5Q" + + "cm90b2J1ZlJvdGF0aW9uM2RSCHJvdGF0aW9uIpQBChNQcm90b2J1ZlRyYW5zZm9ybTNkEkIKC3RyYW5z" + + "bGF0aW9uGAEgASgLMiAud3BpLnByb3RvLlByb3RvYnVmVHJhbnNsYXRpb24zZFILdHJhbnNsYXRpb24S" + + "OQoIcm90YXRpb24YAiABKAsyHS53cGkucHJvdG8uUHJvdG9idWZSb3RhdGlvbjNkUghyb3RhdGlvbiJx" + + "Cg9Qcm90b2J1ZlR3aXN0M2QSDgoCZHgYASABKAFSAmR4Eg4KAmR5GAIgASgBUgJkeRIOCgJkehgDIAEo" + + "AVICZHoSDgoCcngYBCABKAFSAnJ4Eg4KAnJ5GAUgASgBUgJyeRIOCgJyehgGIAEoAVICcnpCGgoYZWR1" + + "LndwaS5maXJzdC5tYXRoLnByb3RvSp8JCgYSBAAAKAEKCAoBDBIDAAASCggKAQISAwIAEgoICgEIEgME" + + "ADEKCQoCCAESAwQAMQoKCgIEABIEBgAKAQoKCgMEAAESAwYIHQoLCgQEAAIAEgMHAg8KDAoFBAACAAUS" + + "AwcCCAoMCgUEAAIAARIDBwkKCgwKBQQAAgADEgMHDQ4KCwoEBAACARIDCAIPCgwKBQQAAgEFEgMIAggK" + + "DAoFBAACAQESAwgJCgoMCgUEAAIBAxIDCA0OCgsKBAQAAgISAwkCDwoMCgUEAAICBRIDCQIICgwKBQQA" + + "AgIBEgMJCQoKDAoFBAACAgMSAwkNDgoKCgIEARIEDAARAQoKCgMEAQESAwwIGgoLCgQEAQIAEgMNAg8K" + + "DAoFBAECAAUSAw0CCAoMCgUEAQIAARIDDQkKCgwKBQQBAgADEgMNDQ4KCwoEBAECARIDDgIPCgwKBQQB" + + "AgEFEgMOAggKDAoFBAECAQESAw4JCgoMCgUEAQIBAxIDDg0OCgsKBAQBAgISAw8CDwoMCgUEAQICBRID" + + "DwIICgwKBQQBAgIBEgMPCQoKDAoFBAECAgMSAw8NDgoLCgQEAQIDEgMQAg8KDAoFBAECAwUSAxACCAoM" + + "CgUEAQIDARIDEAkKCgwKBQQBAgMDEgMQDQ4KCgoCBAISBBMAFQEKCgoDBAIBEgMTCBoKCwoEBAICABID", + "FAIbCgwKBQQCAgAGEgMUAhQKDAoFBAICAAESAxQVFgoMCgUEAgIAAxIDFBkaCgoKAgQDEgQXABoBCgoK" + + "AwQDARIDFwgWCgsKBAQDAgASAxgCKAoMCgUEAwIABhIDGAIXCgwKBQQDAgABEgMYGCMKDAoFBAMCAAMS" + + "AxgmJwoLCgQEAwIBEgMZAiIKDAoFBAMCAQYSAxkCFAoMCgUEAwIBARIDGRUdCgwKBQQDAgEDEgMZICEK" + + "CgoCBAQSBBwAHwEKCgoDBAQBEgMcCBsKCwoEBAQCABIDHQIoCgwKBQQEAgAGEgMdAhcKDAoFBAQCAAES" + + "Ax0YIwoMCgUEBAIAAxIDHSYnCgsKBAQEAgESAx4CIgoMCgUEBAIBBhIDHgIUCgwKBQQEAgEBEgMeFR0K" + + "DAoFBAQCAQMSAx4gIQoKCgIEBRIEIQAoAQoKCgMEBQESAyEIFwoLCgQEBQIAEgMiAhAKDAoFBAUCAAUS" + + "AyICCAoMCgUEBQIAARIDIgkLCgwKBQQFAgADEgMiDg8KCwoEBAUCARIDIwIQCgwKBQQFAgEFEgMjAggK" + + "DAoFBAUCAQESAyMJCwoMCgUEBQIBAxIDIw4PCgsKBAQFAgISAyQCEAoMCgUEBQICBRIDJAIICgwKBQQF" + + "AgIBEgMkCQsKDAoFBAUCAgMSAyQODwoLCgQEBQIDEgMlAhAKDAoFBAUCAwUSAyUCCAoMCgUEBQIDARID" + + "JQkLCgwKBQQFAgMDEgMlDg8KCwoEBAUCBBIDJgIQCgwKBQQFAgQFEgMmAggKDAoFBAUCBAESAyYJCwoM" + + "CgUEBQIEAxIDJg4PCgsKBAQFAgUSAycCEAoMCgUEBQIFBRIDJwIICgwKBQQFAgUBEgMnCQsKDAoFBAUC" + + "BQMSAycOD2IGcHJvdG8z"); + + static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("geometry3d.proto", "wpi.proto", descriptorData); + + static final Descriptors.Descriptor wpi_proto_ProtobufTranslation3d_descriptor = descriptor.internalContainedType(31, 65, "ProtobufTranslation3d", "wpi.proto.ProtobufTranslation3d"); + + static final Descriptors.Descriptor wpi_proto_ProtobufQuaternion_descriptor = descriptor.internalContainedType(98, 76, "ProtobufQuaternion", "wpi.proto.ProtobufQuaternion"); + + static final Descriptors.Descriptor wpi_proto_ProtobufRotation3d_descriptor = descriptor.internalContainedType(176, 65, "ProtobufRotation3d", "wpi.proto.ProtobufRotation3d"); + + static final Descriptors.Descriptor wpi_proto_ProtobufPose3d_descriptor = descriptor.internalContainedType(244, 143, "ProtobufPose3d", "wpi.proto.ProtobufPose3d"); + + static final Descriptors.Descriptor wpi_proto_ProtobufTransform3d_descriptor = descriptor.internalContainedType(390, 148, "ProtobufTransform3d", "wpi.proto.ProtobufTransform3d"); + + static final Descriptors.Descriptor wpi_proto_ProtobufTwist3d_descriptor = descriptor.internalContainedType(540, 113, "ProtobufTwist3d", "wpi.proto.ProtobufTwist3d"); + + /** + * @return this proto file's descriptor. + */ + public static Descriptors.FileDescriptor getDescriptor() { + return descriptor; + } + + /** + * Protobuf type {@code ProtobufTranslation3d} + */ + public static final class ProtobufTranslation3d extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double x = 1; + */ + private double x; + + /** + * optional double y = 2; + */ + private double y; + + /** + * optional double z = 3; + */ + private double z; + + private ProtobufTranslation3d() { + } + + /** + * @return a new empty instance of {@code ProtobufTranslation3d} + */ + public static ProtobufTranslation3d newInstance() { + return new ProtobufTranslation3d(); + } + + /** + * optional double x = 1; + * @return whether the x field is set + */ + public boolean hasX() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double x = 1; + * @return this + */ + public ProtobufTranslation3d clearX() { + bitField0_ &= ~0x00000001; + x = 0D; + return this; + } + + /** + * optional double x = 1; + * @return the x + */ + public double getX() { + return x; + } + + /** + * optional double x = 1; + * @param value the x to set + * @return this + */ + public ProtobufTranslation3d setX(final double value) { + bitField0_ |= 0x00000001; + x = value; + return this; + } + + /** + * optional double y = 2; + * @return whether the y field is set + */ + public boolean hasY() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double y = 2; + * @return this + */ + public ProtobufTranslation3d clearY() { + bitField0_ &= ~0x00000002; + y = 0D; + return this; + } + + /** + * optional double y = 2; + * @return the y + */ + public double getY() { + return y; + } + + /** + * optional double y = 2; + * @param value the y to set + * @return this + */ + public ProtobufTranslation3d setY(final double value) { + bitField0_ |= 0x00000002; + y = value; + return this; + } + + /** + * optional double z = 3; + * @return whether the z field is set + */ + public boolean hasZ() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional double z = 3; + * @return this + */ + public ProtobufTranslation3d clearZ() { + bitField0_ &= ~0x00000004; + z = 0D; + return this; + } + + /** + * optional double z = 3; + * @return the z + */ + public double getZ() { + return z; + } + + /** + * optional double z = 3; + * @param value the z to set + * @return this + */ + public ProtobufTranslation3d setZ(final double value) { + bitField0_ |= 0x00000004; + z = value; + return this; + } + + @Override + public ProtobufTranslation3d copyFrom(final ProtobufTranslation3d other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + x = other.x; + y = other.y; + z = other.z; + } + return this; + } + + @Override + public ProtobufTranslation3d mergeFrom(final ProtobufTranslation3d other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasX()) { + setX(other.x); + } + if (other.hasY()) { + setY(other.y); + } + if (other.hasZ()) { + setZ(other.z); + } + return this; + } + + @Override + public ProtobufTranslation3d clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + x = 0D; + y = 0D; + z = 0D; + return this; + } + + @Override + public ProtobufTranslation3d clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufTranslation3d)) { + return false; + } + ProtobufTranslation3d other = (ProtobufTranslation3d) o; + return bitField0_ == other.bitField0_ + && (!hasX() || ProtoUtil.isEqual(x, other.x)) + && (!hasY() || ProtoUtil.isEqual(y, other.y)) + && (!hasZ() || ProtoUtil.isEqual(z, other.z)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(x); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(y); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(z); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000004) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufTranslation3d mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // x + x = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // y + y = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 25) { + break; + } + } + case 25: { + // z + z = input.readDouble(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.x, x); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.y, y); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeDouble(FieldNames.z, z); + } + output.endObject(); + } + + @Override + public ProtobufTranslation3d mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 120: { + if (input.isAtField(FieldNames.x)) { + if (!input.trySkipNullValue()) { + x = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 121: { + if (input.isAtField(FieldNames.y)) { + if (!input.trySkipNullValue()) { + y = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case 122: { + if (input.isAtField(FieldNames.z)) { + if (!input.trySkipNullValue()) { + z = input.readDouble(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufTranslation3d clone() { + return new ProtobufTranslation3d().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufTranslation3d parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufTranslation3d(), data).checkInitialized(); + } + + public static ProtobufTranslation3d parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTranslation3d(), input).checkInitialized(); + } + + public static ProtobufTranslation3d parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTranslation3d(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufTranslation3d messages + */ + public static MessageFactory getFactory() { + return ProtobufTranslation3dFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Geometry3D.wpi_proto_ProtobufTranslation3d_descriptor; + } + + private enum ProtobufTranslation3dFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufTranslation3d create() { + return ProtobufTranslation3d.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName x = FieldName.forField("x"); + + static final FieldName y = FieldName.forField("y"); + + static final FieldName z = FieldName.forField("z"); + } + } + + /** + * Protobuf type {@code ProtobufQuaternion} + */ + public static final class ProtobufQuaternion extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double w = 1; + */ + private double w; + + /** + * optional double x = 2; + */ + private double x; + + /** + * optional double y = 3; + */ + private double y; + + /** + * optional double z = 4; + */ + private double z; + + private ProtobufQuaternion() { + } + + /** + * @return a new empty instance of {@code ProtobufQuaternion} + */ + public static ProtobufQuaternion newInstance() { + return new ProtobufQuaternion(); + } + + /** + * optional double w = 1; + * @return whether the w field is set + */ + public boolean hasW() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double w = 1; + * @return this + */ + public ProtobufQuaternion clearW() { + bitField0_ &= ~0x00000001; + w = 0D; + return this; + } + + /** + * optional double w = 1; + * @return the w + */ + public double getW() { + return w; + } + + /** + * optional double w = 1; + * @param value the w to set + * @return this + */ + public ProtobufQuaternion setW(final double value) { + bitField0_ |= 0x00000001; + w = value; + return this; + } + + /** + * optional double x = 2; + * @return whether the x field is set + */ + public boolean hasX() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double x = 2; + * @return this + */ + public ProtobufQuaternion clearX() { + bitField0_ &= ~0x00000002; + x = 0D; + return this; + } + + /** + * optional double x = 2; + * @return the x + */ + public double getX() { + return x; + } + + /** + * optional double x = 2; + * @param value the x to set + * @return this + */ + public ProtobufQuaternion setX(final double value) { + bitField0_ |= 0x00000002; + x = value; + return this; + } + + /** + * optional double y = 3; + * @return whether the y field is set + */ + public boolean hasY() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional double y = 3; + * @return this + */ + public ProtobufQuaternion clearY() { + bitField0_ &= ~0x00000004; + y = 0D; + return this; + } + + /** + * optional double y = 3; + * @return the y + */ + public double getY() { + return y; + } + + /** + * optional double y = 3; + * @param value the y to set + * @return this + */ + public ProtobufQuaternion setY(final double value) { + bitField0_ |= 0x00000004; + y = value; + return this; + } + + /** + * optional double z = 4; + * @return whether the z field is set + */ + public boolean hasZ() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * optional double z = 4; + * @return this + */ + public ProtobufQuaternion clearZ() { + bitField0_ &= ~0x00000008; + z = 0D; + return this; + } + + /** + * optional double z = 4; + * @return the z + */ + public double getZ() { + return z; + } + + /** + * optional double z = 4; + * @param value the z to set + * @return this + */ + public ProtobufQuaternion setZ(final double value) { + bitField0_ |= 0x00000008; + z = value; + return this; + } + + @Override + public ProtobufQuaternion copyFrom(final ProtobufQuaternion other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + w = other.w; + x = other.x; + y = other.y; + z = other.z; + } + return this; + } + + @Override + public ProtobufQuaternion mergeFrom(final ProtobufQuaternion other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasW()) { + setW(other.w); + } + if (other.hasX()) { + setX(other.x); + } + if (other.hasY()) { + setY(other.y); + } + if (other.hasZ()) { + setZ(other.z); + } + return this; + } + + @Override + public ProtobufQuaternion clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + w = 0D; + x = 0D; + y = 0D; + z = 0D; + return this; + } + + @Override + public ProtobufQuaternion clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufQuaternion)) { + return false; + } + ProtobufQuaternion other = (ProtobufQuaternion) o; + return bitField0_ == other.bitField0_ + && (!hasW() || ProtoUtil.isEqual(w, other.w)) + && (!hasX() || ProtoUtil.isEqual(x, other.x)) + && (!hasY() || ProtoUtil.isEqual(y, other.y)) + && (!hasZ() || ProtoUtil.isEqual(z, other.z)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(w); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(x); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(y); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRawByte((byte) 33); + output.writeDoubleNoTag(z); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000004) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000008) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufQuaternion mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // w + w = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // x + x = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 25) { + break; + } + } + case 25: { + // y + y = input.readDouble(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 33) { + break; + } + } + case 33: { + // z + z = input.readDouble(); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.w, w); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.x, x); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeDouble(FieldNames.y, y); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeDouble(FieldNames.z, z); + } + output.endObject(); + } + + @Override + public ProtobufQuaternion mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 119: { + if (input.isAtField(FieldNames.w)) { + if (!input.trySkipNullValue()) { + w = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 120: { + if (input.isAtField(FieldNames.x)) { + if (!input.trySkipNullValue()) { + x = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case 121: { + if (input.isAtField(FieldNames.y)) { + if (!input.trySkipNullValue()) { + y = input.readDouble(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case 122: { + if (input.isAtField(FieldNames.z)) { + if (!input.trySkipNullValue()) { + z = input.readDouble(); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufQuaternion clone() { + return new ProtobufQuaternion().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufQuaternion parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufQuaternion(), data).checkInitialized(); + } + + public static ProtobufQuaternion parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufQuaternion(), input).checkInitialized(); + } + + public static ProtobufQuaternion parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufQuaternion(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufQuaternion messages + */ + public static MessageFactory getFactory() { + return ProtobufQuaternionFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Geometry3D.wpi_proto_ProtobufQuaternion_descriptor; + } + + private enum ProtobufQuaternionFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufQuaternion create() { + return ProtobufQuaternion.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName w = FieldName.forField("w"); + + static final FieldName x = FieldName.forField("x"); + + static final FieldName y = FieldName.forField("y"); + + static final FieldName z = FieldName.forField("z"); + } + } + + /** + * Protobuf type {@code ProtobufRotation3d} + */ + public static final class ProtobufRotation3d extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional .wpi.proto.ProtobufQuaternion q = 1; + */ + private final ProtobufQuaternion q = ProtobufQuaternion.newInstance(); + + private ProtobufRotation3d() { + } + + /** + * @return a new empty instance of {@code ProtobufRotation3d} + */ + public static ProtobufRotation3d newInstance() { + return new ProtobufRotation3d(); + } + + /** + * optional .wpi.proto.ProtobufQuaternion q = 1; + * @return whether the q field is set + */ + public boolean hasQ() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional .wpi.proto.ProtobufQuaternion q = 1; + * @return this + */ + public ProtobufRotation3d clearQ() { + bitField0_ &= ~0x00000001; + q.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufQuaternion q = 1; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableQ()} if you want to modify it. + * + * @return internal storage object for reading + */ + public ProtobufQuaternion getQ() { + return q; + } + + /** + * optional .wpi.proto.ProtobufQuaternion q = 1; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public ProtobufQuaternion getMutableQ() { + bitField0_ |= 0x00000001; + return q; + } + + /** + * optional .wpi.proto.ProtobufQuaternion q = 1; + * @param value the q to set + * @return this + */ + public ProtobufRotation3d setQ(final ProtobufQuaternion value) { + bitField0_ |= 0x00000001; + q.copyFrom(value); + return this; + } + + @Override + public ProtobufRotation3d copyFrom(final ProtobufRotation3d other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + q.copyFrom(other.q); + } + return this; + } + + @Override + public ProtobufRotation3d mergeFrom(final ProtobufRotation3d other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasQ()) { + getMutableQ().mergeFrom(other.q); + } + return this; + } + + @Override + public ProtobufRotation3d clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + q.clear(); + return this; + } + + @Override + public ProtobufRotation3d clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + q.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufRotation3d)) { + return false; + } + ProtobufRotation3d other = (ProtobufRotation3d) o; + return bitField0_ == other.bitField0_ + && (!hasQ() || q.equals(other.q)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 10); + output.writeMessageNoTag(q); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(q); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufRotation3d mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 10: { + // q + input.readMessage(q); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeMessage(FieldNames.q, q); + } + output.endObject(); + } + + @Override + public ProtobufRotation3d mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 113: { + if (input.isAtField(FieldNames.q)) { + if (!input.trySkipNullValue()) { + input.readMessage(q); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufRotation3d clone() { + return new ProtobufRotation3d().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufRotation3d parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufRotation3d(), data).checkInitialized(); + } + + public static ProtobufRotation3d parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufRotation3d(), input).checkInitialized(); + } + + public static ProtobufRotation3d parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufRotation3d(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufRotation3d messages + */ + public static MessageFactory getFactory() { + return ProtobufRotation3dFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Geometry3D.wpi_proto_ProtobufRotation3d_descriptor; + } + + private enum ProtobufRotation3dFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufRotation3d create() { + return ProtobufRotation3d.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName q = FieldName.forField("q"); + } + } + + /** + * Protobuf type {@code ProtobufPose3d} + */ + public static final class ProtobufPose3d extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional .wpi.proto.ProtobufTranslation3d translation = 1; + */ + private final ProtobufTranslation3d translation = ProtobufTranslation3d.newInstance(); + + /** + * optional .wpi.proto.ProtobufRotation3d rotation = 2; + */ + private final ProtobufRotation3d rotation = ProtobufRotation3d.newInstance(); + + private ProtobufPose3d() { + } + + /** + * @return a new empty instance of {@code ProtobufPose3d} + */ + public static ProtobufPose3d newInstance() { + return new ProtobufPose3d(); + } + + /** + * optional .wpi.proto.ProtobufTranslation3d translation = 1; + * @return whether the translation field is set + */ + public boolean hasTranslation() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional .wpi.proto.ProtobufTranslation3d translation = 1; + * @return this + */ + public ProtobufPose3d clearTranslation() { + bitField0_ &= ~0x00000001; + translation.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufTranslation3d translation = 1; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableTranslation()} if you want to modify it. + * + * @return internal storage object for reading + */ + public ProtobufTranslation3d getTranslation() { + return translation; + } + + /** + * optional .wpi.proto.ProtobufTranslation3d translation = 1; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public ProtobufTranslation3d getMutableTranslation() { + bitField0_ |= 0x00000001; + return translation; + } + + /** + * optional .wpi.proto.ProtobufTranslation3d translation = 1; + * @param value the translation to set + * @return this + */ + public ProtobufPose3d setTranslation(final ProtobufTranslation3d value) { + bitField0_ |= 0x00000001; + translation.copyFrom(value); + return this; + } + + /** + * optional .wpi.proto.ProtobufRotation3d rotation = 2; + * @return whether the rotation field is set + */ + public boolean hasRotation() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional .wpi.proto.ProtobufRotation3d rotation = 2; + * @return this + */ + public ProtobufPose3d clearRotation() { + bitField0_ &= ~0x00000002; + rotation.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufRotation3d rotation = 2; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableRotation()} if you want to modify it. + * + * @return internal storage object for reading + */ + public ProtobufRotation3d getRotation() { + return rotation; + } + + /** + * optional .wpi.proto.ProtobufRotation3d rotation = 2; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public ProtobufRotation3d getMutableRotation() { + bitField0_ |= 0x00000002; + return rotation; + } + + /** + * optional .wpi.proto.ProtobufRotation3d rotation = 2; + * @param value the rotation to set + * @return this + */ + public ProtobufPose3d setRotation(final ProtobufRotation3d value) { + bitField0_ |= 0x00000002; + rotation.copyFrom(value); + return this; + } + + @Override + public ProtobufPose3d copyFrom(final ProtobufPose3d other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + translation.copyFrom(other.translation); + rotation.copyFrom(other.rotation); + } + return this; + } + + @Override + public ProtobufPose3d mergeFrom(final ProtobufPose3d other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasTranslation()) { + getMutableTranslation().mergeFrom(other.translation); + } + if (other.hasRotation()) { + getMutableRotation().mergeFrom(other.rotation); + } + return this; + } + + @Override + public ProtobufPose3d clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + translation.clear(); + rotation.clear(); + return this; + } + + @Override + public ProtobufPose3d clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + translation.clearQuick(); + rotation.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufPose3d)) { + return false; + } + ProtobufPose3d other = (ProtobufPose3d) o; + return bitField0_ == other.bitField0_ + && (!hasTranslation() || translation.equals(other.translation)) + && (!hasRotation() || rotation.equals(other.rotation)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 10); + output.writeMessageNoTag(translation); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 18); + output.writeMessageNoTag(rotation); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(translation); + } + if ((bitField0_ & 0x00000002) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(rotation); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufPose3d mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 10: { + // translation + input.readMessage(translation); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 18) { + break; + } + } + case 18: { + // rotation + input.readMessage(rotation); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeMessage(FieldNames.translation, translation); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeMessage(FieldNames.rotation, rotation); + } + output.endObject(); + } + + @Override + public ProtobufPose3d mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case -1840647503: { + if (input.isAtField(FieldNames.translation)) { + if (!input.trySkipNullValue()) { + input.readMessage(translation); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case -40300674: { + if (input.isAtField(FieldNames.rotation)) { + if (!input.trySkipNullValue()) { + input.readMessage(rotation); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufPose3d clone() { + return new ProtobufPose3d().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufPose3d parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufPose3d(), data).checkInitialized(); + } + + public static ProtobufPose3d parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufPose3d(), input).checkInitialized(); + } + + public static ProtobufPose3d parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufPose3d(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufPose3d messages + */ + public static MessageFactory getFactory() { + return ProtobufPose3dFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Geometry3D.wpi_proto_ProtobufPose3d_descriptor; + } + + private enum ProtobufPose3dFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufPose3d create() { + return ProtobufPose3d.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName translation = FieldName.forField("translation"); + + static final FieldName rotation = FieldName.forField("rotation"); + } + } + + /** + * Protobuf type {@code ProtobufTransform3d} + */ + public static final class ProtobufTransform3d extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional .wpi.proto.ProtobufTranslation3d translation = 1; + */ + private final ProtobufTranslation3d translation = ProtobufTranslation3d.newInstance(); + + /** + * optional .wpi.proto.ProtobufRotation3d rotation = 2; + */ + private final ProtobufRotation3d rotation = ProtobufRotation3d.newInstance(); + + private ProtobufTransform3d() { + } + + /** + * @return a new empty instance of {@code ProtobufTransform3d} + */ + public static ProtobufTransform3d newInstance() { + return new ProtobufTransform3d(); + } + + /** + * optional .wpi.proto.ProtobufTranslation3d translation = 1; + * @return whether the translation field is set + */ + public boolean hasTranslation() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional .wpi.proto.ProtobufTranslation3d translation = 1; + * @return this + */ + public ProtobufTransform3d clearTranslation() { + bitField0_ &= ~0x00000001; + translation.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufTranslation3d translation = 1; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableTranslation()} if you want to modify it. + * + * @return internal storage object for reading + */ + public ProtobufTranslation3d getTranslation() { + return translation; + } + + /** + * optional .wpi.proto.ProtobufTranslation3d translation = 1; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public ProtobufTranslation3d getMutableTranslation() { + bitField0_ |= 0x00000001; + return translation; + } + + /** + * optional .wpi.proto.ProtobufTranslation3d translation = 1; + * @param value the translation to set + * @return this + */ + public ProtobufTransform3d setTranslation(final ProtobufTranslation3d value) { + bitField0_ |= 0x00000001; + translation.copyFrom(value); + return this; + } + + /** + * optional .wpi.proto.ProtobufRotation3d rotation = 2; + * @return whether the rotation field is set + */ + public boolean hasRotation() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional .wpi.proto.ProtobufRotation3d rotation = 2; + * @return this + */ + public ProtobufTransform3d clearRotation() { + bitField0_ &= ~0x00000002; + rotation.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufRotation3d rotation = 2; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableRotation()} if you want to modify it. + * + * @return internal storage object for reading + */ + public ProtobufRotation3d getRotation() { + return rotation; + } + + /** + * optional .wpi.proto.ProtobufRotation3d rotation = 2; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public ProtobufRotation3d getMutableRotation() { + bitField0_ |= 0x00000002; + return rotation; + } + + /** + * optional .wpi.proto.ProtobufRotation3d rotation = 2; + * @param value the rotation to set + * @return this + */ + public ProtobufTransform3d setRotation(final ProtobufRotation3d value) { + bitField0_ |= 0x00000002; + rotation.copyFrom(value); + return this; + } + + @Override + public ProtobufTransform3d copyFrom(final ProtobufTransform3d other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + translation.copyFrom(other.translation); + rotation.copyFrom(other.rotation); + } + return this; + } + + @Override + public ProtobufTransform3d mergeFrom(final ProtobufTransform3d other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasTranslation()) { + getMutableTranslation().mergeFrom(other.translation); + } + if (other.hasRotation()) { + getMutableRotation().mergeFrom(other.rotation); + } + return this; + } + + @Override + public ProtobufTransform3d clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + translation.clear(); + rotation.clear(); + return this; + } + + @Override + public ProtobufTransform3d clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + translation.clearQuick(); + rotation.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufTransform3d)) { + return false; + } + ProtobufTransform3d other = (ProtobufTransform3d) o; + return bitField0_ == other.bitField0_ + && (!hasTranslation() || translation.equals(other.translation)) + && (!hasRotation() || rotation.equals(other.rotation)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 10); + output.writeMessageNoTag(translation); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 18); + output.writeMessageNoTag(rotation); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(translation); + } + if ((bitField0_ & 0x00000002) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(rotation); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufTransform3d mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 10: { + // translation + input.readMessage(translation); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 18) { + break; + } + } + case 18: { + // rotation + input.readMessage(rotation); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeMessage(FieldNames.translation, translation); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeMessage(FieldNames.rotation, rotation); + } + output.endObject(); + } + + @Override + public ProtobufTransform3d mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case -1840647503: { + if (input.isAtField(FieldNames.translation)) { + if (!input.trySkipNullValue()) { + input.readMessage(translation); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case -40300674: { + if (input.isAtField(FieldNames.rotation)) { + if (!input.trySkipNullValue()) { + input.readMessage(rotation); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufTransform3d clone() { + return new ProtobufTransform3d().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufTransform3d parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufTransform3d(), data).checkInitialized(); + } + + public static ProtobufTransform3d parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTransform3d(), input).checkInitialized(); + } + + public static ProtobufTransform3d parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTransform3d(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufTransform3d messages + */ + public static MessageFactory getFactory() { + return ProtobufTransform3dFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Geometry3D.wpi_proto_ProtobufTransform3d_descriptor; + } + + private enum ProtobufTransform3dFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufTransform3d create() { + return ProtobufTransform3d.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName translation = FieldName.forField("translation"); + + static final FieldName rotation = FieldName.forField("rotation"); + } + } + + /** + * Protobuf type {@code ProtobufTwist3d} + */ + public static final class ProtobufTwist3d extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double dx = 1; + */ + private double dx; + + /** + * optional double dy = 2; + */ + private double dy; + + /** + * optional double dz = 3; + */ + private double dz; + + /** + * optional double rx = 4; + */ + private double rx; + + /** + * optional double ry = 5; + */ + private double ry; + + /** + * optional double rz = 6; + */ + private double rz; + + private ProtobufTwist3d() { + } + + /** + * @return a new empty instance of {@code ProtobufTwist3d} + */ + public static ProtobufTwist3d newInstance() { + return new ProtobufTwist3d(); + } + + /** + * optional double dx = 1; + * @return whether the dx field is set + */ + public boolean hasDx() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double dx = 1; + * @return this + */ + public ProtobufTwist3d clearDx() { + bitField0_ &= ~0x00000001; + dx = 0D; + return this; + } + + /** + * optional double dx = 1; + * @return the dx + */ + public double getDx() { + return dx; + } + + /** + * optional double dx = 1; + * @param value the dx to set + * @return this + */ + public ProtobufTwist3d setDx(final double value) { + bitField0_ |= 0x00000001; + dx = value; + return this; + } + + /** + * optional double dy = 2; + * @return whether the dy field is set + */ + public boolean hasDy() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double dy = 2; + * @return this + */ + public ProtobufTwist3d clearDy() { + bitField0_ &= ~0x00000002; + dy = 0D; + return this; + } + + /** + * optional double dy = 2; + * @return the dy + */ + public double getDy() { + return dy; + } + + /** + * optional double dy = 2; + * @param value the dy to set + * @return this + */ + public ProtobufTwist3d setDy(final double value) { + bitField0_ |= 0x00000002; + dy = value; + return this; + } + + /** + * optional double dz = 3; + * @return whether the dz field is set + */ + public boolean hasDz() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional double dz = 3; + * @return this + */ + public ProtobufTwist3d clearDz() { + bitField0_ &= ~0x00000004; + dz = 0D; + return this; + } + + /** + * optional double dz = 3; + * @return the dz + */ + public double getDz() { + return dz; + } + + /** + * optional double dz = 3; + * @param value the dz to set + * @return this + */ + public ProtobufTwist3d setDz(final double value) { + bitField0_ |= 0x00000004; + dz = value; + return this; + } + + /** + * optional double rx = 4; + * @return whether the rx field is set + */ + public boolean hasRx() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * optional double rx = 4; + * @return this + */ + public ProtobufTwist3d clearRx() { + bitField0_ &= ~0x00000008; + rx = 0D; + return this; + } + + /** + * optional double rx = 4; + * @return the rx + */ + public double getRx() { + return rx; + } + + /** + * optional double rx = 4; + * @param value the rx to set + * @return this + */ + public ProtobufTwist3d setRx(final double value) { + bitField0_ |= 0x00000008; + rx = value; + return this; + } + + /** + * optional double ry = 5; + * @return whether the ry field is set + */ + public boolean hasRy() { + return (bitField0_ & 0x00000010) != 0; + } + + /** + * optional double ry = 5; + * @return this + */ + public ProtobufTwist3d clearRy() { + bitField0_ &= ~0x00000010; + ry = 0D; + return this; + } + + /** + * optional double ry = 5; + * @return the ry + */ + public double getRy() { + return ry; + } + + /** + * optional double ry = 5; + * @param value the ry to set + * @return this + */ + public ProtobufTwist3d setRy(final double value) { + bitField0_ |= 0x00000010; + ry = value; + return this; + } + + /** + * optional double rz = 6; + * @return whether the rz field is set + */ + public boolean hasRz() { + return (bitField0_ & 0x00000020) != 0; + } + + /** + * optional double rz = 6; + * @return this + */ + public ProtobufTwist3d clearRz() { + bitField0_ &= ~0x00000020; + rz = 0D; + return this; + } + + /** + * optional double rz = 6; + * @return the rz + */ + public double getRz() { + return rz; + } + + /** + * optional double rz = 6; + * @param value the rz to set + * @return this + */ + public ProtobufTwist3d setRz(final double value) { + bitField0_ |= 0x00000020; + rz = value; + return this; + } + + @Override + public ProtobufTwist3d copyFrom(final ProtobufTwist3d other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + dx = other.dx; + dy = other.dy; + dz = other.dz; + rx = other.rx; + ry = other.ry; + rz = other.rz; + } + return this; + } + + @Override + public ProtobufTwist3d mergeFrom(final ProtobufTwist3d other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasDx()) { + setDx(other.dx); + } + if (other.hasDy()) { + setDy(other.dy); + } + if (other.hasDz()) { + setDz(other.dz); + } + if (other.hasRx()) { + setRx(other.rx); + } + if (other.hasRy()) { + setRy(other.ry); + } + if (other.hasRz()) { + setRz(other.rz); + } + return this; + } + + @Override + public ProtobufTwist3d clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + dx = 0D; + dy = 0D; + dz = 0D; + rx = 0D; + ry = 0D; + rz = 0D; + return this; + } + + @Override + public ProtobufTwist3d clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufTwist3d)) { + return false; + } + ProtobufTwist3d other = (ProtobufTwist3d) o; + return bitField0_ == other.bitField0_ + && (!hasDx() || ProtoUtil.isEqual(dx, other.dx)) + && (!hasDy() || ProtoUtil.isEqual(dy, other.dy)) + && (!hasDz() || ProtoUtil.isEqual(dz, other.dz)) + && (!hasRx() || ProtoUtil.isEqual(rx, other.rx)) + && (!hasRy() || ProtoUtil.isEqual(ry, other.ry)) + && (!hasRz() || ProtoUtil.isEqual(rz, other.rz)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(dx); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(dy); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(dz); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRawByte((byte) 33); + output.writeDoubleNoTag(rx); + } + if ((bitField0_ & 0x00000010) != 0) { + output.writeRawByte((byte) 41); + output.writeDoubleNoTag(ry); + } + if ((bitField0_ & 0x00000020) != 0) { + output.writeRawByte((byte) 49); + output.writeDoubleNoTag(rz); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000004) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000008) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000010) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000020) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufTwist3d mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // dx + dx = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // dy + dy = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 25) { + break; + } + } + case 25: { + // dz + dz = input.readDouble(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 33) { + break; + } + } + case 33: { + // rx + rx = input.readDouble(); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 41) { + break; + } + } + case 41: { + // ry + ry = input.readDouble(); + bitField0_ |= 0x00000010; + tag = input.readTag(); + if (tag != 49) { + break; + } + } + case 49: { + // rz + rz = input.readDouble(); + bitField0_ |= 0x00000020; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.dx, dx); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.dy, dy); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeDouble(FieldNames.dz, dz); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeDouble(FieldNames.rx, rx); + } + if ((bitField0_ & 0x00000010) != 0) { + output.writeDouble(FieldNames.ry, ry); + } + if ((bitField0_ & 0x00000020) != 0) { + output.writeDouble(FieldNames.rz, rz); + } + output.endObject(); + } + + @Override + public ProtobufTwist3d mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 3220: { + if (input.isAtField(FieldNames.dx)) { + if (!input.trySkipNullValue()) { + dx = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3221: { + if (input.isAtField(FieldNames.dy)) { + if (!input.trySkipNullValue()) { + dy = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3222: { + if (input.isAtField(FieldNames.dz)) { + if (!input.trySkipNullValue()) { + dz = input.readDouble(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3654: { + if (input.isAtField(FieldNames.rx)) { + if (!input.trySkipNullValue()) { + rx = input.readDouble(); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3655: { + if (input.isAtField(FieldNames.ry)) { + if (!input.trySkipNullValue()) { + ry = input.readDouble(); + bitField0_ |= 0x00000010; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3656: { + if (input.isAtField(FieldNames.rz)) { + if (!input.trySkipNullValue()) { + rz = input.readDouble(); + bitField0_ |= 0x00000020; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufTwist3d clone() { + return new ProtobufTwist3d().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufTwist3d parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufTwist3d(), data).checkInitialized(); + } + + public static ProtobufTwist3d parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTwist3d(), input).checkInitialized(); + } + + public static ProtobufTwist3d parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTwist3d(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufTwist3d messages + */ + public static MessageFactory getFactory() { + return ProtobufTwist3dFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Geometry3D.wpi_proto_ProtobufTwist3d_descriptor; + } + + private enum ProtobufTwist3dFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufTwist3d create() { + return ProtobufTwist3d.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName dx = FieldName.forField("dx"); + + static final FieldName dy = FieldName.forField("dy"); + + static final FieldName dz = FieldName.forField("dz"); + + static final FieldName rx = FieldName.forField("rx"); + + static final FieldName ry = FieldName.forField("ry"); + + static final FieldName rz = FieldName.forField("rz"); + } + } +} diff --git a/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Kinematics.java b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Kinematics.java new file mode 100644 index 00000000000..bd0c4450cb5 --- /dev/null +++ b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Kinematics.java @@ -0,0 +1,4196 @@ +// 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. +// Code generated by protocol buffer compiler. Do not edit! +package edu.wpi.first.math.proto; + +import java.io.IOException; +import us.hebi.quickbuf.Descriptors; +import us.hebi.quickbuf.FieldName; +import us.hebi.quickbuf.InvalidProtocolBufferException; +import us.hebi.quickbuf.JsonSink; +import us.hebi.quickbuf.JsonSource; +import us.hebi.quickbuf.MessageFactory; +import us.hebi.quickbuf.ProtoMessage; +import us.hebi.quickbuf.ProtoSink; +import us.hebi.quickbuf.ProtoSource; +import us.hebi.quickbuf.ProtoUtil; +import us.hebi.quickbuf.RepeatedByte; +import us.hebi.quickbuf.RepeatedMessage; + +public final class Kinematics { + private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(3208, + "ChBraW5lbWF0aWNzLnByb3RvEgl3cGkucHJvdG8aEGdlb21ldHJ5MmQucHJvdG8iTQoVUHJvdG9idWZD" + + "aGFzc2lzU3BlZWRzEg4KAnZ4GAEgASgBUgJ2eBIOCgJ2eRgCIAEoAVICdnkSFAoFb21lZ2EYAyABKAFS" + + "BW9tZWdhIkYKI1Byb3RvYnVmRGlmZmVyZW50aWFsRHJpdmVLaW5lbWF0aWNzEh8KC3RyYWNrX3dpZHRo" + + "GAEgASgBUgp0cmFja1dpZHRoIlAKJFByb3RvYnVmRGlmZmVyZW50aWFsRHJpdmVXaGVlbFNwZWVkcxIS" + + "CgRsZWZ0GAEgASgBUgRsZWZ0EhQKBXJpZ2h0GAIgASgBUgVyaWdodCKkAgoeUHJvdG9idWZNZWNhbnVt" + + "RHJpdmVLaW5lbWF0aWNzEj8KCmZyb250X2xlZnQYASABKAsyIC53cGkucHJvdG8uUHJvdG9idWZUcmFu" + + "c2xhdGlvbjJkUglmcm9udExlZnQSQQoLZnJvbnRfcmlnaHQYAiABKAsyIC53cGkucHJvdG8uUHJvdG9i" + + "dWZUcmFuc2xhdGlvbjJkUgpmcm9udFJpZ2h0Ej0KCXJlYXJfbGVmdBgDIAEoCzIgLndwaS5wcm90by5Q" + + "cm90b2J1ZlRyYW5zbGF0aW9uMmRSCHJlYXJMZWZ0Ej8KCnJlYXJfcmlnaHQYBCABKAsyIC53cGkucHJv" + + "dG8uUHJvdG9idWZUcmFuc2xhdGlvbjJkUglyZWFyUmlnaHQinwEKIVByb3RvYnVmTWVjYW51bURyaXZl" + + "TW90b3JWb2x0YWdlcxIdCgpmcm9udF9sZWZ0GAEgASgBUglmcm9udExlZnQSHwoLZnJvbnRfcmlnaHQY" + + "AiABKAFSCmZyb250UmlnaHQSGwoJcmVhcl9sZWZ0GAMgASgBUghyZWFyTGVmdBIdCgpyZWFyX3JpZ2h0" + + "GAQgASgBUglyZWFyUmlnaHQioAEKIlByb3RvYnVmTWVjYW51bURyaXZlV2hlZWxQb3NpdGlvbnMSHQoK" + + "ZnJvbnRfbGVmdBgBIAEoAVIJZnJvbnRMZWZ0Eh8KC2Zyb250X3JpZ2h0GAIgASgBUgpmcm9udFJpZ2h0" + + "EhsKCXJlYXJfbGVmdBgDIAEoAVIIcmVhckxlZnQSHQoKcmVhcl9yaWdodBgEIAEoAVIJcmVhclJpZ2h0" + + "Ip0BCh9Qcm90b2J1Zk1lY2FudW1Ecml2ZVdoZWVsU3BlZWRzEh0KCmZyb250X2xlZnQYASABKAFSCWZy" + + "b250TGVmdBIfCgtmcm9udF9yaWdodBgCIAEoAVIKZnJvbnRSaWdodBIbCglyZWFyX2xlZnQYAyABKAFS" + + "CHJlYXJMZWZ0Eh0KCnJlYXJfcmlnaHQYBCABKAFSCXJlYXJSaWdodCJbCh1Qcm90b2J1ZlN3ZXJ2ZURy" + + "aXZlS2luZW1hdGljcxI6Cgdtb2R1bGVzGAEgAygLMiAud3BpLnByb3RvLlByb3RvYnVmVHJhbnNsYXRp" + + "b24yZFIHbW9kdWxlcyJvChxQcm90b2J1ZlN3ZXJ2ZU1vZHVsZVBvc2l0aW9uEhoKCGRpc3RhbmNlGAEg", + "ASgBUghkaXN0YW5jZRIzCgVhbmdsZRgCIAEoCzIdLndwaS5wcm90by5Qcm90b2J1ZlJvdGF0aW9uMmRS" + + "BWFuZ2xlImYKGVByb3RvYnVmU3dlcnZlTW9kdWxlU3RhdGUSFAoFc3BlZWQYASABKAFSBXNwZWVkEjMK" + + "BWFuZ2xlGAIgASgLMh0ud3BpLnByb3RvLlByb3RvYnVmUm90YXRpb24yZFIFYW5nbGVCGgoYZWR1Lndw" + + "aS5maXJzdC5tYXRoLnByb3RvSocOCgYSBAAAPwEKCAoBDBIDAAASCggKAQISAwIAEgoJCgIDABIDBAAa" + + "CggKAQgSAwYAMQoJCgIIARIDBgAxCgoKAgQAEgQIAAwBCgoKAwQAARIDCAgdCgsKBAQAAgASAwkCEAoM" + + "CgUEAAIABRIDCQIICgwKBQQAAgABEgMJCQsKDAoFBAACAAMSAwkODwoLCgQEAAIBEgMKAhAKDAoFBAAC" + + "AQUSAwoCCAoMCgUEAAIBARIDCgkLCgwKBQQAAgEDEgMKDg8KCwoEBAACAhIDCwITCgwKBQQAAgIFEgML" + + "AggKDAoFBAACAgESAwsJDgoMCgUEAAICAxIDCxESCgoKAgQBEgQOABABCgoKAwQBARIDDggrCgsKBAQB" + + "AgASAw8CGQoMCgUEAQIABRIDDwIICgwKBQQBAgABEgMPCRQKDAoFBAECAAMSAw8XGAoKCgIEAhIEEgAV" + + "AQoKCgMEAgESAxIILAoLCgQEAgIAEgMTAhIKDAoFBAICAAUSAxMCCAoMCgUEAgIAARIDEwkNCgwKBQQC" + + "AgADEgMTEBEKCwoEBAICARIDFAITCgwKBQQCAgEFEgMUAggKDAoFBAICAQESAxQJDgoMCgUEAgIBAxID" + + "FBESCgoKAgQDEgQXABwBCgoKAwQDARIDFwgmCgsKBAQDAgASAxgCJwoMCgUEAwIABhIDGAIXCgwKBQQD" + + "AgABEgMYGCIKDAoFBAMCAAMSAxglJgoLCgQEAwIBEgMZAigKDAoFBAMCAQYSAxkCFwoMCgUEAwIBARID" + + "GRgjCgwKBQQDAgEDEgMZJicKCwoEBAMCAhIDGgImCgwKBQQDAgIGEgMaAhcKDAoFBAMCAgESAxoYIQoM" + + "CgUEAwICAxIDGiQlCgsKBAQDAgMSAxsCJwoMCgUEAwIDBhIDGwIXCgwKBQQDAgMBEgMbGCIKDAoFBAMC" + + "AwMSAxslJgoKCgIEBBIEHgAjAQoKCgMEBAESAx4IKQoLCgQEBAIAEgMfAhgKDAoFBAQCAAUSAx8CCAoM" + + "CgUEBAIAARIDHwkTCgwKBQQEAgADEgMfFhcKCwoEBAQCARIDIAIZCgwKBQQEAgEFEgMgAggKDAoFBAQC" + + "AQESAyAJFAoMCgUEBAIBAxIDIBcYCgsKBAQEAgISAyECFwoMCgUEBAICBRIDIQIICgwKBQQEAgIBEgMh" + + "CRIKDAoFBAQCAgMSAyEVFgoLCgQEBAIDEgMiAhgKDAoFBAQCAwUSAyICCAoMCgUEBAIDARIDIgkTCgwK" + + "BQQEAgMDEgMiFhcKCgoCBAUSBCUAKgEKCgoDBAUBEgMlCCoKCwoEBAUCABIDJgIYCgwKBQQFAgAFEgMm", + "AggKDAoFBAUCAAESAyYJEwoMCgUEBQIAAxIDJhYXCgsKBAQFAgESAycCGQoMCgUEBQIBBRIDJwIICgwK" + + "BQQFAgEBEgMnCRQKDAoFBAUCAQMSAycXGAoLCgQEBQICEgMoAhcKDAoFBAUCAgUSAygCCAoMCgUEBQIC" + + "ARIDKAkSCgwKBQQFAgIDEgMoFRYKCwoEBAUCAxIDKQIYCgwKBQQFAgMFEgMpAggKDAoFBAUCAwESAykJ" + + "EwoMCgUEBQIDAxIDKRYXCgoKAgQGEgQsADEBCgoKAwQGARIDLAgnCgsKBAQGAgASAy0CGAoMCgUEBgIA" + + "BRIDLQIICgwKBQQGAgABEgMtCRMKDAoFBAYCAAMSAy0WFwoLCgQEBgIBEgMuAhkKDAoFBAYCAQUSAy4C" + + "CAoMCgUEBgIBARIDLgkUCgwKBQQGAgEDEgMuFxgKCwoEBAYCAhIDLwIXCgwKBQQGAgIFEgMvAggKDAoF" + + "BAYCAgESAy8JEgoMCgUEBgICAxIDLxUWCgsKBAQGAgMSAzACGAoMCgUEBgIDBRIDMAIICgwKBQQGAgMB" + + "EgMwCRMKDAoFBAYCAwMSAzAWFwoKCgIEBxIEMwA1AQoKCgMEBwESAzMIJQoLCgQEBwIAEgM0Ai0KDAoF" + + "BAcCAAQSAzQCCgoMCgUEBwIABhIDNAsgCgwKBQQHAgABEgM0ISgKDAoFBAcCAAMSAzQrLAoKCgIECBIE" + + "NwA6AQoKCgMECAESAzcIJAoLCgQECAIAEgM4AhYKDAoFBAgCAAUSAzgCCAoMCgUECAIAARIDOAkRCgwK" + + "BQQIAgADEgM4FBUKCwoEBAgCARIDOQIfCgwKBQQIAgEGEgM5AhQKDAoFBAgCAQESAzkVGgoMCgUECAIB" + + "AxIDOR0eCgoKAgQJEgQ8AD8BCgoKAwQJARIDPAghCgsKBAQJAgASAz0CEwoMCgUECQIABRIDPQIICgwK" + + "BQQJAgABEgM9CQ4KDAoFBAkCAAMSAz0REgoLCgQECQIBEgM+Ah8KDAoFBAkCAQYSAz4CFAoMCgUECQIB" + + "ARIDPhUaCgwKBQQJAgEDEgM+HR5iBnByb3RvMw=="); + + static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("kinematics.proto", "wpi.proto", descriptorData, Geometry2D.getDescriptor()); + + static final Descriptors.Descriptor wpi_proto_ProtobufChassisSpeeds_descriptor = descriptor.internalContainedType(49, 77, "ProtobufChassisSpeeds", "wpi.proto.ProtobufChassisSpeeds"); + + static final Descriptors.Descriptor wpi_proto_ProtobufDifferentialDriveKinematics_descriptor = descriptor.internalContainedType(128, 70, "ProtobufDifferentialDriveKinematics", "wpi.proto.ProtobufDifferentialDriveKinematics"); + + static final Descriptors.Descriptor wpi_proto_ProtobufDifferentialDriveWheelSpeeds_descriptor = descriptor.internalContainedType(200, 80, "ProtobufDifferentialDriveWheelSpeeds", "wpi.proto.ProtobufDifferentialDriveWheelSpeeds"); + + static final Descriptors.Descriptor wpi_proto_ProtobufMecanumDriveKinematics_descriptor = descriptor.internalContainedType(283, 292, "ProtobufMecanumDriveKinematics", "wpi.proto.ProtobufMecanumDriveKinematics"); + + static final Descriptors.Descriptor wpi_proto_ProtobufMecanumDriveMotorVoltages_descriptor = descriptor.internalContainedType(578, 159, "ProtobufMecanumDriveMotorVoltages", "wpi.proto.ProtobufMecanumDriveMotorVoltages"); + + static final Descriptors.Descriptor wpi_proto_ProtobufMecanumDriveWheelPositions_descriptor = descriptor.internalContainedType(740, 160, "ProtobufMecanumDriveWheelPositions", "wpi.proto.ProtobufMecanumDriveWheelPositions"); + + static final Descriptors.Descriptor wpi_proto_ProtobufMecanumDriveWheelSpeeds_descriptor = descriptor.internalContainedType(903, 157, "ProtobufMecanumDriveWheelSpeeds", "wpi.proto.ProtobufMecanumDriveWheelSpeeds"); + + static final Descriptors.Descriptor wpi_proto_ProtobufSwerveDriveKinematics_descriptor = descriptor.internalContainedType(1062, 91, "ProtobufSwerveDriveKinematics", "wpi.proto.ProtobufSwerveDriveKinematics"); + + static final Descriptors.Descriptor wpi_proto_ProtobufSwerveModulePosition_descriptor = descriptor.internalContainedType(1155, 111, "ProtobufSwerveModulePosition", "wpi.proto.ProtobufSwerveModulePosition"); + + static final Descriptors.Descriptor wpi_proto_ProtobufSwerveModuleState_descriptor = descriptor.internalContainedType(1268, 102, "ProtobufSwerveModuleState", "wpi.proto.ProtobufSwerveModuleState"); + + /** + * @return this proto file's descriptor. + */ + public static Descriptors.FileDescriptor getDescriptor() { + return descriptor; + } + + /** + * Protobuf type {@code ProtobufChassisSpeeds} + */ + public static final class ProtobufChassisSpeeds extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double vx = 1; + */ + private double vx; + + /** + * optional double vy = 2; + */ + private double vy; + + /** + * optional double omega = 3; + */ + private double omega; + + private ProtobufChassisSpeeds() { + } + + /** + * @return a new empty instance of {@code ProtobufChassisSpeeds} + */ + public static ProtobufChassisSpeeds newInstance() { + return new ProtobufChassisSpeeds(); + } + + /** + * optional double vx = 1; + * @return whether the vx field is set + */ + public boolean hasVx() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double vx = 1; + * @return this + */ + public ProtobufChassisSpeeds clearVx() { + bitField0_ &= ~0x00000001; + vx = 0D; + return this; + } + + /** + * optional double vx = 1; + * @return the vx + */ + public double getVx() { + return vx; + } + + /** + * optional double vx = 1; + * @param value the vx to set + * @return this + */ + public ProtobufChassisSpeeds setVx(final double value) { + bitField0_ |= 0x00000001; + vx = value; + return this; + } + + /** + * optional double vy = 2; + * @return whether the vy field is set + */ + public boolean hasVy() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double vy = 2; + * @return this + */ + public ProtobufChassisSpeeds clearVy() { + bitField0_ &= ~0x00000002; + vy = 0D; + return this; + } + + /** + * optional double vy = 2; + * @return the vy + */ + public double getVy() { + return vy; + } + + /** + * optional double vy = 2; + * @param value the vy to set + * @return this + */ + public ProtobufChassisSpeeds setVy(final double value) { + bitField0_ |= 0x00000002; + vy = value; + return this; + } + + /** + * optional double omega = 3; + * @return whether the omega field is set + */ + public boolean hasOmega() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional double omega = 3; + * @return this + */ + public ProtobufChassisSpeeds clearOmega() { + bitField0_ &= ~0x00000004; + omega = 0D; + return this; + } + + /** + * optional double omega = 3; + * @return the omega + */ + public double getOmega() { + return omega; + } + + /** + * optional double omega = 3; + * @param value the omega to set + * @return this + */ + public ProtobufChassisSpeeds setOmega(final double value) { + bitField0_ |= 0x00000004; + omega = value; + return this; + } + + @Override + public ProtobufChassisSpeeds copyFrom(final ProtobufChassisSpeeds other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + vx = other.vx; + vy = other.vy; + omega = other.omega; + } + return this; + } + + @Override + public ProtobufChassisSpeeds mergeFrom(final ProtobufChassisSpeeds other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasVx()) { + setVx(other.vx); + } + if (other.hasVy()) { + setVy(other.vy); + } + if (other.hasOmega()) { + setOmega(other.omega); + } + return this; + } + + @Override + public ProtobufChassisSpeeds clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + vx = 0D; + vy = 0D; + omega = 0D; + return this; + } + + @Override + public ProtobufChassisSpeeds clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufChassisSpeeds)) { + return false; + } + ProtobufChassisSpeeds other = (ProtobufChassisSpeeds) o; + return bitField0_ == other.bitField0_ + && (!hasVx() || ProtoUtil.isEqual(vx, other.vx)) + && (!hasVy() || ProtoUtil.isEqual(vy, other.vy)) + && (!hasOmega() || ProtoUtil.isEqual(omega, other.omega)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(vx); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(vy); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(omega); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000004) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufChassisSpeeds mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // vx + vx = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // vy + vy = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 25) { + break; + } + } + case 25: { + // omega + omega = input.readDouble(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.vx, vx); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.vy, vy); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeDouble(FieldNames.omega, omega); + } + output.endObject(); + } + + @Override + public ProtobufChassisSpeeds mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 3778: { + if (input.isAtField(FieldNames.vx)) { + if (!input.trySkipNullValue()) { + vx = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3779: { + if (input.isAtField(FieldNames.vy)) { + if (!input.trySkipNullValue()) { + vy = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case 105858401: { + if (input.isAtField(FieldNames.omega)) { + if (!input.trySkipNullValue()) { + omega = input.readDouble(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufChassisSpeeds clone() { + return new ProtobufChassisSpeeds().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufChassisSpeeds parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufChassisSpeeds(), data).checkInitialized(); + } + + public static ProtobufChassisSpeeds parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufChassisSpeeds(), input).checkInitialized(); + } + + public static ProtobufChassisSpeeds parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufChassisSpeeds(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufChassisSpeeds messages + */ + public static MessageFactory getFactory() { + return ProtobufChassisSpeedsFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Kinematics.wpi_proto_ProtobufChassisSpeeds_descriptor; + } + + private enum ProtobufChassisSpeedsFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufChassisSpeeds create() { + return ProtobufChassisSpeeds.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName vx = FieldName.forField("vx"); + + static final FieldName vy = FieldName.forField("vy"); + + static final FieldName omega = FieldName.forField("omega"); + } + } + + /** + * Protobuf type {@code ProtobufDifferentialDriveKinematics} + */ + public static final class ProtobufDifferentialDriveKinematics extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double track_width = 1; + */ + private double trackWidth; + + private ProtobufDifferentialDriveKinematics() { + } + + /** + * @return a new empty instance of {@code ProtobufDifferentialDriveKinematics} + */ + public static ProtobufDifferentialDriveKinematics newInstance() { + return new ProtobufDifferentialDriveKinematics(); + } + + /** + * optional double track_width = 1; + * @return whether the trackWidth field is set + */ + public boolean hasTrackWidth() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double track_width = 1; + * @return this + */ + public ProtobufDifferentialDriveKinematics clearTrackWidth() { + bitField0_ &= ~0x00000001; + trackWidth = 0D; + return this; + } + + /** + * optional double track_width = 1; + * @return the trackWidth + */ + public double getTrackWidth() { + return trackWidth; + } + + /** + * optional double track_width = 1; + * @param value the trackWidth to set + * @return this + */ + public ProtobufDifferentialDriveKinematics setTrackWidth(final double value) { + bitField0_ |= 0x00000001; + trackWidth = value; + return this; + } + + @Override + public ProtobufDifferentialDriveKinematics copyFrom( + final ProtobufDifferentialDriveKinematics other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + trackWidth = other.trackWidth; + } + return this; + } + + @Override + public ProtobufDifferentialDriveKinematics mergeFrom( + final ProtobufDifferentialDriveKinematics other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasTrackWidth()) { + setTrackWidth(other.trackWidth); + } + return this; + } + + @Override + public ProtobufDifferentialDriveKinematics clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + trackWidth = 0D; + return this; + } + + @Override + public ProtobufDifferentialDriveKinematics clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufDifferentialDriveKinematics)) { + return false; + } + ProtobufDifferentialDriveKinematics other = (ProtobufDifferentialDriveKinematics) o; + return bitField0_ == other.bitField0_ + && (!hasTrackWidth() || ProtoUtil.isEqual(trackWidth, other.trackWidth)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(trackWidth); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufDifferentialDriveKinematics mergeFrom(final ProtoSource input) throws + IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // trackWidth + trackWidth = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.trackWidth, trackWidth); + } + output.endObject(); + } + + @Override + public ProtobufDifferentialDriveKinematics mergeFrom(final JsonSource input) throws + IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 1152213819: + case 1600986578: { + if (input.isAtField(FieldNames.trackWidth)) { + if (!input.trySkipNullValue()) { + trackWidth = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufDifferentialDriveKinematics clone() { + return new ProtobufDifferentialDriveKinematics().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufDifferentialDriveKinematics parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufDifferentialDriveKinematics(), data).checkInitialized(); + } + + public static ProtobufDifferentialDriveKinematics parseFrom(final ProtoSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufDifferentialDriveKinematics(), input).checkInitialized(); + } + + public static ProtobufDifferentialDriveKinematics parseFrom(final JsonSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufDifferentialDriveKinematics(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufDifferentialDriveKinematics messages + */ + public static MessageFactory getFactory() { + return ProtobufDifferentialDriveKinematicsFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Kinematics.wpi_proto_ProtobufDifferentialDriveKinematics_descriptor; + } + + private enum ProtobufDifferentialDriveKinematicsFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufDifferentialDriveKinematics create() { + return ProtobufDifferentialDriveKinematics.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName trackWidth = FieldName.forField("trackWidth", "track_width"); + } + } + + /** + * Protobuf type {@code ProtobufDifferentialDriveWheelSpeeds} + */ + public static final class ProtobufDifferentialDriveWheelSpeeds extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double left = 1; + */ + private double left; + + /** + * optional double right = 2; + */ + private double right; + + private ProtobufDifferentialDriveWheelSpeeds() { + } + + /** + * @return a new empty instance of {@code ProtobufDifferentialDriveWheelSpeeds} + */ + public static ProtobufDifferentialDriveWheelSpeeds newInstance() { + return new ProtobufDifferentialDriveWheelSpeeds(); + } + + /** + * optional double left = 1; + * @return whether the left field is set + */ + public boolean hasLeft() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double left = 1; + * @return this + */ + public ProtobufDifferentialDriveWheelSpeeds clearLeft() { + bitField0_ &= ~0x00000001; + left = 0D; + return this; + } + + /** + * optional double left = 1; + * @return the left + */ + public double getLeft() { + return left; + } + + /** + * optional double left = 1; + * @param value the left to set + * @return this + */ + public ProtobufDifferentialDriveWheelSpeeds setLeft(final double value) { + bitField0_ |= 0x00000001; + left = value; + return this; + } + + /** + * optional double right = 2; + * @return whether the right field is set + */ + public boolean hasRight() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double right = 2; + * @return this + */ + public ProtobufDifferentialDriveWheelSpeeds clearRight() { + bitField0_ &= ~0x00000002; + right = 0D; + return this; + } + + /** + * optional double right = 2; + * @return the right + */ + public double getRight() { + return right; + } + + /** + * optional double right = 2; + * @param value the right to set + * @return this + */ + public ProtobufDifferentialDriveWheelSpeeds setRight(final double value) { + bitField0_ |= 0x00000002; + right = value; + return this; + } + + @Override + public ProtobufDifferentialDriveWheelSpeeds copyFrom( + final ProtobufDifferentialDriveWheelSpeeds other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + left = other.left; + right = other.right; + } + return this; + } + + @Override + public ProtobufDifferentialDriveWheelSpeeds mergeFrom( + final ProtobufDifferentialDriveWheelSpeeds other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasLeft()) { + setLeft(other.left); + } + if (other.hasRight()) { + setRight(other.right); + } + return this; + } + + @Override + public ProtobufDifferentialDriveWheelSpeeds clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + left = 0D; + right = 0D; + return this; + } + + @Override + public ProtobufDifferentialDriveWheelSpeeds clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufDifferentialDriveWheelSpeeds)) { + return false; + } + ProtobufDifferentialDriveWheelSpeeds other = (ProtobufDifferentialDriveWheelSpeeds) o; + return bitField0_ == other.bitField0_ + && (!hasLeft() || ProtoUtil.isEqual(left, other.left)) + && (!hasRight() || ProtoUtil.isEqual(right, other.right)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(left); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(right); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufDifferentialDriveWheelSpeeds mergeFrom(final ProtoSource input) throws + IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // left + left = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // right + right = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.left, left); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.right, right); + } + output.endObject(); + } + + @Override + public ProtobufDifferentialDriveWheelSpeeds mergeFrom(final JsonSource input) throws + IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 3317767: { + if (input.isAtField(FieldNames.left)) { + if (!input.trySkipNullValue()) { + left = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 108511772: { + if (input.isAtField(FieldNames.right)) { + if (!input.trySkipNullValue()) { + right = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufDifferentialDriveWheelSpeeds clone() { + return new ProtobufDifferentialDriveWheelSpeeds().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufDifferentialDriveWheelSpeeds parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufDifferentialDriveWheelSpeeds(), data).checkInitialized(); + } + + public static ProtobufDifferentialDriveWheelSpeeds parseFrom(final ProtoSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufDifferentialDriveWheelSpeeds(), input).checkInitialized(); + } + + public static ProtobufDifferentialDriveWheelSpeeds parseFrom(final JsonSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufDifferentialDriveWheelSpeeds(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufDifferentialDriveWheelSpeeds messages + */ + public static MessageFactory getFactory() { + return ProtobufDifferentialDriveWheelSpeedsFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Kinematics.wpi_proto_ProtobufDifferentialDriveWheelSpeeds_descriptor; + } + + private enum ProtobufDifferentialDriveWheelSpeedsFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufDifferentialDriveWheelSpeeds create() { + return ProtobufDifferentialDriveWheelSpeeds.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName left = FieldName.forField("left"); + + static final FieldName right = FieldName.forField("right"); + } + } + + /** + * Protobuf type {@code ProtobufMecanumDriveKinematics} + */ + public static final class ProtobufMecanumDriveKinematics extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional .wpi.proto.ProtobufTranslation2d front_left = 1; + */ + private final Geometry2D.ProtobufTranslation2d frontLeft = Geometry2D.ProtobufTranslation2d.newInstance(); + + /** + * optional .wpi.proto.ProtobufTranslation2d front_right = 2; + */ + private final Geometry2D.ProtobufTranslation2d frontRight = Geometry2D.ProtobufTranslation2d.newInstance(); + + /** + * optional .wpi.proto.ProtobufTranslation2d rear_left = 3; + */ + private final Geometry2D.ProtobufTranslation2d rearLeft = Geometry2D.ProtobufTranslation2d.newInstance(); + + /** + * optional .wpi.proto.ProtobufTranslation2d rear_right = 4; + */ + private final Geometry2D.ProtobufTranslation2d rearRight = Geometry2D.ProtobufTranslation2d.newInstance(); + + private ProtobufMecanumDriveKinematics() { + } + + /** + * @return a new empty instance of {@code ProtobufMecanumDriveKinematics} + */ + public static ProtobufMecanumDriveKinematics newInstance() { + return new ProtobufMecanumDriveKinematics(); + } + + /** + * optional .wpi.proto.ProtobufTranslation2d front_left = 1; + * @return whether the frontLeft field is set + */ + public boolean hasFrontLeft() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d front_left = 1; + * @return this + */ + public ProtobufMecanumDriveKinematics clearFrontLeft() { + bitField0_ &= ~0x00000001; + frontLeft.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d front_left = 1; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableFrontLeft()} if you want to modify it. + * + * @return internal storage object for reading + */ + public Geometry2D.ProtobufTranslation2d getFrontLeft() { + return frontLeft; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d front_left = 1; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public Geometry2D.ProtobufTranslation2d getMutableFrontLeft() { + bitField0_ |= 0x00000001; + return frontLeft; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d front_left = 1; + * @param value the frontLeft to set + * @return this + */ + public ProtobufMecanumDriveKinematics setFrontLeft( + final Geometry2D.ProtobufTranslation2d value) { + bitField0_ |= 0x00000001; + frontLeft.copyFrom(value); + return this; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d front_right = 2; + * @return whether the frontRight field is set + */ + public boolean hasFrontRight() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d front_right = 2; + * @return this + */ + public ProtobufMecanumDriveKinematics clearFrontRight() { + bitField0_ &= ~0x00000002; + frontRight.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d front_right = 2; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableFrontRight()} if you want to modify it. + * + * @return internal storage object for reading + */ + public Geometry2D.ProtobufTranslation2d getFrontRight() { + return frontRight; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d front_right = 2; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public Geometry2D.ProtobufTranslation2d getMutableFrontRight() { + bitField0_ |= 0x00000002; + return frontRight; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d front_right = 2; + * @param value the frontRight to set + * @return this + */ + public ProtobufMecanumDriveKinematics setFrontRight( + final Geometry2D.ProtobufTranslation2d value) { + bitField0_ |= 0x00000002; + frontRight.copyFrom(value); + return this; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d rear_left = 3; + * @return whether the rearLeft field is set + */ + public boolean hasRearLeft() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d rear_left = 3; + * @return this + */ + public ProtobufMecanumDriveKinematics clearRearLeft() { + bitField0_ &= ~0x00000004; + rearLeft.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d rear_left = 3; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableRearLeft()} if you want to modify it. + * + * @return internal storage object for reading + */ + public Geometry2D.ProtobufTranslation2d getRearLeft() { + return rearLeft; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d rear_left = 3; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public Geometry2D.ProtobufTranslation2d getMutableRearLeft() { + bitField0_ |= 0x00000004; + return rearLeft; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d rear_left = 3; + * @param value the rearLeft to set + * @return this + */ + public ProtobufMecanumDriveKinematics setRearLeft( + final Geometry2D.ProtobufTranslation2d value) { + bitField0_ |= 0x00000004; + rearLeft.copyFrom(value); + return this; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d rear_right = 4; + * @return whether the rearRight field is set + */ + public boolean hasRearRight() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d rear_right = 4; + * @return this + */ + public ProtobufMecanumDriveKinematics clearRearRight() { + bitField0_ &= ~0x00000008; + rearRight.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d rear_right = 4; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableRearRight()} if you want to modify it. + * + * @return internal storage object for reading + */ + public Geometry2D.ProtobufTranslation2d getRearRight() { + return rearRight; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d rear_right = 4; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public Geometry2D.ProtobufTranslation2d getMutableRearRight() { + bitField0_ |= 0x00000008; + return rearRight; + } + + /** + * optional .wpi.proto.ProtobufTranslation2d rear_right = 4; + * @param value the rearRight to set + * @return this + */ + public ProtobufMecanumDriveKinematics setRearRight( + final Geometry2D.ProtobufTranslation2d value) { + bitField0_ |= 0x00000008; + rearRight.copyFrom(value); + return this; + } + + @Override + public ProtobufMecanumDriveKinematics copyFrom(final ProtobufMecanumDriveKinematics other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + frontLeft.copyFrom(other.frontLeft); + frontRight.copyFrom(other.frontRight); + rearLeft.copyFrom(other.rearLeft); + rearRight.copyFrom(other.rearRight); + } + return this; + } + + @Override + public ProtobufMecanumDriveKinematics mergeFrom(final ProtobufMecanumDriveKinematics other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasFrontLeft()) { + getMutableFrontLeft().mergeFrom(other.frontLeft); + } + if (other.hasFrontRight()) { + getMutableFrontRight().mergeFrom(other.frontRight); + } + if (other.hasRearLeft()) { + getMutableRearLeft().mergeFrom(other.rearLeft); + } + if (other.hasRearRight()) { + getMutableRearRight().mergeFrom(other.rearRight); + } + return this; + } + + @Override + public ProtobufMecanumDriveKinematics clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + frontLeft.clear(); + frontRight.clear(); + rearLeft.clear(); + rearRight.clear(); + return this; + } + + @Override + public ProtobufMecanumDriveKinematics clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + frontLeft.clearQuick(); + frontRight.clearQuick(); + rearLeft.clearQuick(); + rearRight.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufMecanumDriveKinematics)) { + return false; + } + ProtobufMecanumDriveKinematics other = (ProtobufMecanumDriveKinematics) o; + return bitField0_ == other.bitField0_ + && (!hasFrontLeft() || frontLeft.equals(other.frontLeft)) + && (!hasFrontRight() || frontRight.equals(other.frontRight)) + && (!hasRearLeft() || rearLeft.equals(other.rearLeft)) + && (!hasRearRight() || rearRight.equals(other.rearRight)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 10); + output.writeMessageNoTag(frontLeft); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 18); + output.writeMessageNoTag(frontRight); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 26); + output.writeMessageNoTag(rearLeft); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRawByte((byte) 34); + output.writeMessageNoTag(rearRight); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(frontLeft); + } + if ((bitField0_ & 0x00000002) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(frontRight); + } + if ((bitField0_ & 0x00000004) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(rearLeft); + } + if ((bitField0_ & 0x00000008) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(rearRight); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufMecanumDriveKinematics mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 10: { + // frontLeft + input.readMessage(frontLeft); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 18) { + break; + } + } + case 18: { + // frontRight + input.readMessage(frontRight); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 26) { + break; + } + } + case 26: { + // rearLeft + input.readMessage(rearLeft); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 34) { + break; + } + } + case 34: { + // rearRight + input.readMessage(rearRight); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeMessage(FieldNames.frontLeft, frontLeft); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeMessage(FieldNames.frontRight, frontRight); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeMessage(FieldNames.rearLeft, rearLeft); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeMessage(FieldNames.rearRight, rearRight); + } + output.endObject(); + } + + @Override + public ProtobufMecanumDriveKinematics mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 127514064: + case -324277155: { + if (input.isAtField(FieldNames.frontLeft)) { + if (!input.trySkipNullValue()) { + input.readMessage(frontLeft); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case -336370317: + case -1456996218: { + if (input.isAtField(FieldNames.frontRight)) { + if (!input.trySkipNullValue()) { + input.readMessage(frontRight); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case -854852661: + case -712874558: { + if (input.isAtField(FieldNames.rearLeft)) { + if (!input.trySkipNullValue()) { + input.readMessage(rearLeft); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case -724967720: + case -618613823: { + if (input.isAtField(FieldNames.rearRight)) { + if (!input.trySkipNullValue()) { + input.readMessage(rearRight); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufMecanumDriveKinematics clone() { + return new ProtobufMecanumDriveKinematics().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufMecanumDriveKinematics parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufMecanumDriveKinematics(), data).checkInitialized(); + } + + public static ProtobufMecanumDriveKinematics parseFrom(final ProtoSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufMecanumDriveKinematics(), input).checkInitialized(); + } + + public static ProtobufMecanumDriveKinematics parseFrom(final JsonSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufMecanumDriveKinematics(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufMecanumDriveKinematics messages + */ + public static MessageFactory getFactory() { + return ProtobufMecanumDriveKinematicsFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Kinematics.wpi_proto_ProtobufMecanumDriveKinematics_descriptor; + } + + private enum ProtobufMecanumDriveKinematicsFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufMecanumDriveKinematics create() { + return ProtobufMecanumDriveKinematics.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName frontLeft = FieldName.forField("frontLeft", "front_left"); + + static final FieldName frontRight = FieldName.forField("frontRight", "front_right"); + + static final FieldName rearLeft = FieldName.forField("rearLeft", "rear_left"); + + static final FieldName rearRight = FieldName.forField("rearRight", "rear_right"); + } + } + + /** + * Protobuf type {@code ProtobufMecanumDriveMotorVoltages} + */ + public static final class ProtobufMecanumDriveMotorVoltages extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double front_left = 1; + */ + private double frontLeft; + + /** + * optional double front_right = 2; + */ + private double frontRight; + + /** + * optional double rear_left = 3; + */ + private double rearLeft; + + /** + * optional double rear_right = 4; + */ + private double rearRight; + + private ProtobufMecanumDriveMotorVoltages() { + } + + /** + * @return a new empty instance of {@code ProtobufMecanumDriveMotorVoltages} + */ + public static ProtobufMecanumDriveMotorVoltages newInstance() { + return new ProtobufMecanumDriveMotorVoltages(); + } + + /** + * optional double front_left = 1; + * @return whether the frontLeft field is set + */ + public boolean hasFrontLeft() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double front_left = 1; + * @return this + */ + public ProtobufMecanumDriveMotorVoltages clearFrontLeft() { + bitField0_ &= ~0x00000001; + frontLeft = 0D; + return this; + } + + /** + * optional double front_left = 1; + * @return the frontLeft + */ + public double getFrontLeft() { + return frontLeft; + } + + /** + * optional double front_left = 1; + * @param value the frontLeft to set + * @return this + */ + public ProtobufMecanumDriveMotorVoltages setFrontLeft(final double value) { + bitField0_ |= 0x00000001; + frontLeft = value; + return this; + } + + /** + * optional double front_right = 2; + * @return whether the frontRight field is set + */ + public boolean hasFrontRight() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double front_right = 2; + * @return this + */ + public ProtobufMecanumDriveMotorVoltages clearFrontRight() { + bitField0_ &= ~0x00000002; + frontRight = 0D; + return this; + } + + /** + * optional double front_right = 2; + * @return the frontRight + */ + public double getFrontRight() { + return frontRight; + } + + /** + * optional double front_right = 2; + * @param value the frontRight to set + * @return this + */ + public ProtobufMecanumDriveMotorVoltages setFrontRight(final double value) { + bitField0_ |= 0x00000002; + frontRight = value; + return this; + } + + /** + * optional double rear_left = 3; + * @return whether the rearLeft field is set + */ + public boolean hasRearLeft() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional double rear_left = 3; + * @return this + */ + public ProtobufMecanumDriveMotorVoltages clearRearLeft() { + bitField0_ &= ~0x00000004; + rearLeft = 0D; + return this; + } + + /** + * optional double rear_left = 3; + * @return the rearLeft + */ + public double getRearLeft() { + return rearLeft; + } + + /** + * optional double rear_left = 3; + * @param value the rearLeft to set + * @return this + */ + public ProtobufMecanumDriveMotorVoltages setRearLeft(final double value) { + bitField0_ |= 0x00000004; + rearLeft = value; + return this; + } + + /** + * optional double rear_right = 4; + * @return whether the rearRight field is set + */ + public boolean hasRearRight() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * optional double rear_right = 4; + * @return this + */ + public ProtobufMecanumDriveMotorVoltages clearRearRight() { + bitField0_ &= ~0x00000008; + rearRight = 0D; + return this; + } + + /** + * optional double rear_right = 4; + * @return the rearRight + */ + public double getRearRight() { + return rearRight; + } + + /** + * optional double rear_right = 4; + * @param value the rearRight to set + * @return this + */ + public ProtobufMecanumDriveMotorVoltages setRearRight(final double value) { + bitField0_ |= 0x00000008; + rearRight = value; + return this; + } + + @Override + public ProtobufMecanumDriveMotorVoltages copyFrom( + final ProtobufMecanumDriveMotorVoltages other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + frontLeft = other.frontLeft; + frontRight = other.frontRight; + rearLeft = other.rearLeft; + rearRight = other.rearRight; + } + return this; + } + + @Override + public ProtobufMecanumDriveMotorVoltages mergeFrom( + final ProtobufMecanumDriveMotorVoltages other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasFrontLeft()) { + setFrontLeft(other.frontLeft); + } + if (other.hasFrontRight()) { + setFrontRight(other.frontRight); + } + if (other.hasRearLeft()) { + setRearLeft(other.rearLeft); + } + if (other.hasRearRight()) { + setRearRight(other.rearRight); + } + return this; + } + + @Override + public ProtobufMecanumDriveMotorVoltages clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + frontLeft = 0D; + frontRight = 0D; + rearLeft = 0D; + rearRight = 0D; + return this; + } + + @Override + public ProtobufMecanumDriveMotorVoltages clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufMecanumDriveMotorVoltages)) { + return false; + } + ProtobufMecanumDriveMotorVoltages other = (ProtobufMecanumDriveMotorVoltages) o; + return bitField0_ == other.bitField0_ + && (!hasFrontLeft() || ProtoUtil.isEqual(frontLeft, other.frontLeft)) + && (!hasFrontRight() || ProtoUtil.isEqual(frontRight, other.frontRight)) + && (!hasRearLeft() || ProtoUtil.isEqual(rearLeft, other.rearLeft)) + && (!hasRearRight() || ProtoUtil.isEqual(rearRight, other.rearRight)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(frontLeft); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(frontRight); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(rearLeft); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRawByte((byte) 33); + output.writeDoubleNoTag(rearRight); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000004) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000008) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufMecanumDriveMotorVoltages mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // frontLeft + frontLeft = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // frontRight + frontRight = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 25) { + break; + } + } + case 25: { + // rearLeft + rearLeft = input.readDouble(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 33) { + break; + } + } + case 33: { + // rearRight + rearRight = input.readDouble(); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.frontLeft, frontLeft); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.frontRight, frontRight); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeDouble(FieldNames.rearLeft, rearLeft); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeDouble(FieldNames.rearRight, rearRight); + } + output.endObject(); + } + + @Override + public ProtobufMecanumDriveMotorVoltages mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 127514064: + case -324277155: { + if (input.isAtField(FieldNames.frontLeft)) { + if (!input.trySkipNullValue()) { + frontLeft = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case -336370317: + case -1456996218: { + if (input.isAtField(FieldNames.frontRight)) { + if (!input.trySkipNullValue()) { + frontRight = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case -854852661: + case -712874558: { + if (input.isAtField(FieldNames.rearLeft)) { + if (!input.trySkipNullValue()) { + rearLeft = input.readDouble(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case -724967720: + case -618613823: { + if (input.isAtField(FieldNames.rearRight)) { + if (!input.trySkipNullValue()) { + rearRight = input.readDouble(); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufMecanumDriveMotorVoltages clone() { + return new ProtobufMecanumDriveMotorVoltages().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufMecanumDriveMotorVoltages parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufMecanumDriveMotorVoltages(), data).checkInitialized(); + } + + public static ProtobufMecanumDriveMotorVoltages parseFrom(final ProtoSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufMecanumDriveMotorVoltages(), input).checkInitialized(); + } + + public static ProtobufMecanumDriveMotorVoltages parseFrom(final JsonSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufMecanumDriveMotorVoltages(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufMecanumDriveMotorVoltages messages + */ + public static MessageFactory getFactory() { + return ProtobufMecanumDriveMotorVoltagesFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Kinematics.wpi_proto_ProtobufMecanumDriveMotorVoltages_descriptor; + } + + private enum ProtobufMecanumDriveMotorVoltagesFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufMecanumDriveMotorVoltages create() { + return ProtobufMecanumDriveMotorVoltages.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName frontLeft = FieldName.forField("frontLeft", "front_left"); + + static final FieldName frontRight = FieldName.forField("frontRight", "front_right"); + + static final FieldName rearLeft = FieldName.forField("rearLeft", "rear_left"); + + static final FieldName rearRight = FieldName.forField("rearRight", "rear_right"); + } + } + + /** + * Protobuf type {@code ProtobufMecanumDriveWheelPositions} + */ + public static final class ProtobufMecanumDriveWheelPositions extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double front_left = 1; + */ + private double frontLeft; + + /** + * optional double front_right = 2; + */ + private double frontRight; + + /** + * optional double rear_left = 3; + */ + private double rearLeft; + + /** + * optional double rear_right = 4; + */ + private double rearRight; + + private ProtobufMecanumDriveWheelPositions() { + } + + /** + * @return a new empty instance of {@code ProtobufMecanumDriveWheelPositions} + */ + public static ProtobufMecanumDriveWheelPositions newInstance() { + return new ProtobufMecanumDriveWheelPositions(); + } + + /** + * optional double front_left = 1; + * @return whether the frontLeft field is set + */ + public boolean hasFrontLeft() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double front_left = 1; + * @return this + */ + public ProtobufMecanumDriveWheelPositions clearFrontLeft() { + bitField0_ &= ~0x00000001; + frontLeft = 0D; + return this; + } + + /** + * optional double front_left = 1; + * @return the frontLeft + */ + public double getFrontLeft() { + return frontLeft; + } + + /** + * optional double front_left = 1; + * @param value the frontLeft to set + * @return this + */ + public ProtobufMecanumDriveWheelPositions setFrontLeft(final double value) { + bitField0_ |= 0x00000001; + frontLeft = value; + return this; + } + + /** + * optional double front_right = 2; + * @return whether the frontRight field is set + */ + public boolean hasFrontRight() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double front_right = 2; + * @return this + */ + public ProtobufMecanumDriveWheelPositions clearFrontRight() { + bitField0_ &= ~0x00000002; + frontRight = 0D; + return this; + } + + /** + * optional double front_right = 2; + * @return the frontRight + */ + public double getFrontRight() { + return frontRight; + } + + /** + * optional double front_right = 2; + * @param value the frontRight to set + * @return this + */ + public ProtobufMecanumDriveWheelPositions setFrontRight(final double value) { + bitField0_ |= 0x00000002; + frontRight = value; + return this; + } + + /** + * optional double rear_left = 3; + * @return whether the rearLeft field is set + */ + public boolean hasRearLeft() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional double rear_left = 3; + * @return this + */ + public ProtobufMecanumDriveWheelPositions clearRearLeft() { + bitField0_ &= ~0x00000004; + rearLeft = 0D; + return this; + } + + /** + * optional double rear_left = 3; + * @return the rearLeft + */ + public double getRearLeft() { + return rearLeft; + } + + /** + * optional double rear_left = 3; + * @param value the rearLeft to set + * @return this + */ + public ProtobufMecanumDriveWheelPositions setRearLeft(final double value) { + bitField0_ |= 0x00000004; + rearLeft = value; + return this; + } + + /** + * optional double rear_right = 4; + * @return whether the rearRight field is set + */ + public boolean hasRearRight() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * optional double rear_right = 4; + * @return this + */ + public ProtobufMecanumDriveWheelPositions clearRearRight() { + bitField0_ &= ~0x00000008; + rearRight = 0D; + return this; + } + + /** + * optional double rear_right = 4; + * @return the rearRight + */ + public double getRearRight() { + return rearRight; + } + + /** + * optional double rear_right = 4; + * @param value the rearRight to set + * @return this + */ + public ProtobufMecanumDriveWheelPositions setRearRight(final double value) { + bitField0_ |= 0x00000008; + rearRight = value; + return this; + } + + @Override + public ProtobufMecanumDriveWheelPositions copyFrom( + final ProtobufMecanumDriveWheelPositions other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + frontLeft = other.frontLeft; + frontRight = other.frontRight; + rearLeft = other.rearLeft; + rearRight = other.rearRight; + } + return this; + } + + @Override + public ProtobufMecanumDriveWheelPositions mergeFrom( + final ProtobufMecanumDriveWheelPositions other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasFrontLeft()) { + setFrontLeft(other.frontLeft); + } + if (other.hasFrontRight()) { + setFrontRight(other.frontRight); + } + if (other.hasRearLeft()) { + setRearLeft(other.rearLeft); + } + if (other.hasRearRight()) { + setRearRight(other.rearRight); + } + return this; + } + + @Override + public ProtobufMecanumDriveWheelPositions clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + frontLeft = 0D; + frontRight = 0D; + rearLeft = 0D; + rearRight = 0D; + return this; + } + + @Override + public ProtobufMecanumDriveWheelPositions clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufMecanumDriveWheelPositions)) { + return false; + } + ProtobufMecanumDriveWheelPositions other = (ProtobufMecanumDriveWheelPositions) o; + return bitField0_ == other.bitField0_ + && (!hasFrontLeft() || ProtoUtil.isEqual(frontLeft, other.frontLeft)) + && (!hasFrontRight() || ProtoUtil.isEqual(frontRight, other.frontRight)) + && (!hasRearLeft() || ProtoUtil.isEqual(rearLeft, other.rearLeft)) + && (!hasRearRight() || ProtoUtil.isEqual(rearRight, other.rearRight)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(frontLeft); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(frontRight); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(rearLeft); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRawByte((byte) 33); + output.writeDoubleNoTag(rearRight); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000004) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000008) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufMecanumDriveWheelPositions mergeFrom(final ProtoSource input) throws + IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // frontLeft + frontLeft = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // frontRight + frontRight = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 25) { + break; + } + } + case 25: { + // rearLeft + rearLeft = input.readDouble(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 33) { + break; + } + } + case 33: { + // rearRight + rearRight = input.readDouble(); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.frontLeft, frontLeft); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.frontRight, frontRight); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeDouble(FieldNames.rearLeft, rearLeft); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeDouble(FieldNames.rearRight, rearRight); + } + output.endObject(); + } + + @Override + public ProtobufMecanumDriveWheelPositions mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 127514064: + case -324277155: { + if (input.isAtField(FieldNames.frontLeft)) { + if (!input.trySkipNullValue()) { + frontLeft = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case -336370317: + case -1456996218: { + if (input.isAtField(FieldNames.frontRight)) { + if (!input.trySkipNullValue()) { + frontRight = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case -854852661: + case -712874558: { + if (input.isAtField(FieldNames.rearLeft)) { + if (!input.trySkipNullValue()) { + rearLeft = input.readDouble(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case -724967720: + case -618613823: { + if (input.isAtField(FieldNames.rearRight)) { + if (!input.trySkipNullValue()) { + rearRight = input.readDouble(); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufMecanumDriveWheelPositions clone() { + return new ProtobufMecanumDriveWheelPositions().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufMecanumDriveWheelPositions parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufMecanumDriveWheelPositions(), data).checkInitialized(); + } + + public static ProtobufMecanumDriveWheelPositions parseFrom(final ProtoSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufMecanumDriveWheelPositions(), input).checkInitialized(); + } + + public static ProtobufMecanumDriveWheelPositions parseFrom(final JsonSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufMecanumDriveWheelPositions(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufMecanumDriveWheelPositions messages + */ + public static MessageFactory getFactory() { + return ProtobufMecanumDriveWheelPositionsFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Kinematics.wpi_proto_ProtobufMecanumDriveWheelPositions_descriptor; + } + + private enum ProtobufMecanumDriveWheelPositionsFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufMecanumDriveWheelPositions create() { + return ProtobufMecanumDriveWheelPositions.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName frontLeft = FieldName.forField("frontLeft", "front_left"); + + static final FieldName frontRight = FieldName.forField("frontRight", "front_right"); + + static final FieldName rearLeft = FieldName.forField("rearLeft", "rear_left"); + + static final FieldName rearRight = FieldName.forField("rearRight", "rear_right"); + } + } + + /** + * Protobuf type {@code ProtobufMecanumDriveWheelSpeeds} + */ + public static final class ProtobufMecanumDriveWheelSpeeds extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double front_left = 1; + */ + private double frontLeft; + + /** + * optional double front_right = 2; + */ + private double frontRight; + + /** + * optional double rear_left = 3; + */ + private double rearLeft; + + /** + * optional double rear_right = 4; + */ + private double rearRight; + + private ProtobufMecanumDriveWheelSpeeds() { + } + + /** + * @return a new empty instance of {@code ProtobufMecanumDriveWheelSpeeds} + */ + public static ProtobufMecanumDriveWheelSpeeds newInstance() { + return new ProtobufMecanumDriveWheelSpeeds(); + } + + /** + * optional double front_left = 1; + * @return whether the frontLeft field is set + */ + public boolean hasFrontLeft() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double front_left = 1; + * @return this + */ + public ProtobufMecanumDriveWheelSpeeds clearFrontLeft() { + bitField0_ &= ~0x00000001; + frontLeft = 0D; + return this; + } + + /** + * optional double front_left = 1; + * @return the frontLeft + */ + public double getFrontLeft() { + return frontLeft; + } + + /** + * optional double front_left = 1; + * @param value the frontLeft to set + * @return this + */ + public ProtobufMecanumDriveWheelSpeeds setFrontLeft(final double value) { + bitField0_ |= 0x00000001; + frontLeft = value; + return this; + } + + /** + * optional double front_right = 2; + * @return whether the frontRight field is set + */ + public boolean hasFrontRight() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double front_right = 2; + * @return this + */ + public ProtobufMecanumDriveWheelSpeeds clearFrontRight() { + bitField0_ &= ~0x00000002; + frontRight = 0D; + return this; + } + + /** + * optional double front_right = 2; + * @return the frontRight + */ + public double getFrontRight() { + return frontRight; + } + + /** + * optional double front_right = 2; + * @param value the frontRight to set + * @return this + */ + public ProtobufMecanumDriveWheelSpeeds setFrontRight(final double value) { + bitField0_ |= 0x00000002; + frontRight = value; + return this; + } + + /** + * optional double rear_left = 3; + * @return whether the rearLeft field is set + */ + public boolean hasRearLeft() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional double rear_left = 3; + * @return this + */ + public ProtobufMecanumDriveWheelSpeeds clearRearLeft() { + bitField0_ &= ~0x00000004; + rearLeft = 0D; + return this; + } + + /** + * optional double rear_left = 3; + * @return the rearLeft + */ + public double getRearLeft() { + return rearLeft; + } + + /** + * optional double rear_left = 3; + * @param value the rearLeft to set + * @return this + */ + public ProtobufMecanumDriveWheelSpeeds setRearLeft(final double value) { + bitField0_ |= 0x00000004; + rearLeft = value; + return this; + } + + /** + * optional double rear_right = 4; + * @return whether the rearRight field is set + */ + public boolean hasRearRight() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * optional double rear_right = 4; + * @return this + */ + public ProtobufMecanumDriveWheelSpeeds clearRearRight() { + bitField0_ &= ~0x00000008; + rearRight = 0D; + return this; + } + + /** + * optional double rear_right = 4; + * @return the rearRight + */ + public double getRearRight() { + return rearRight; + } + + /** + * optional double rear_right = 4; + * @param value the rearRight to set + * @return this + */ + public ProtobufMecanumDriveWheelSpeeds setRearRight(final double value) { + bitField0_ |= 0x00000008; + rearRight = value; + return this; + } + + @Override + public ProtobufMecanumDriveWheelSpeeds copyFrom(final ProtobufMecanumDriveWheelSpeeds other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + frontLeft = other.frontLeft; + frontRight = other.frontRight; + rearLeft = other.rearLeft; + rearRight = other.rearRight; + } + return this; + } + + @Override + public ProtobufMecanumDriveWheelSpeeds mergeFrom(final ProtobufMecanumDriveWheelSpeeds other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasFrontLeft()) { + setFrontLeft(other.frontLeft); + } + if (other.hasFrontRight()) { + setFrontRight(other.frontRight); + } + if (other.hasRearLeft()) { + setRearLeft(other.rearLeft); + } + if (other.hasRearRight()) { + setRearRight(other.rearRight); + } + return this; + } + + @Override + public ProtobufMecanumDriveWheelSpeeds clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + frontLeft = 0D; + frontRight = 0D; + rearLeft = 0D; + rearRight = 0D; + return this; + } + + @Override + public ProtobufMecanumDriveWheelSpeeds clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufMecanumDriveWheelSpeeds)) { + return false; + } + ProtobufMecanumDriveWheelSpeeds other = (ProtobufMecanumDriveWheelSpeeds) o; + return bitField0_ == other.bitField0_ + && (!hasFrontLeft() || ProtoUtil.isEqual(frontLeft, other.frontLeft)) + && (!hasFrontRight() || ProtoUtil.isEqual(frontRight, other.frontRight)) + && (!hasRearLeft() || ProtoUtil.isEqual(rearLeft, other.rearLeft)) + && (!hasRearRight() || ProtoUtil.isEqual(rearRight, other.rearRight)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(frontLeft); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(frontRight); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(rearLeft); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRawByte((byte) 33); + output.writeDoubleNoTag(rearRight); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000004) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000008) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufMecanumDriveWheelSpeeds mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // frontLeft + frontLeft = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // frontRight + frontRight = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 25) { + break; + } + } + case 25: { + // rearLeft + rearLeft = input.readDouble(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 33) { + break; + } + } + case 33: { + // rearRight + rearRight = input.readDouble(); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.frontLeft, frontLeft); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.frontRight, frontRight); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeDouble(FieldNames.rearLeft, rearLeft); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeDouble(FieldNames.rearRight, rearRight); + } + output.endObject(); + } + + @Override + public ProtobufMecanumDriveWheelSpeeds mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 127514064: + case -324277155: { + if (input.isAtField(FieldNames.frontLeft)) { + if (!input.trySkipNullValue()) { + frontLeft = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case -336370317: + case -1456996218: { + if (input.isAtField(FieldNames.frontRight)) { + if (!input.trySkipNullValue()) { + frontRight = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case -854852661: + case -712874558: { + if (input.isAtField(FieldNames.rearLeft)) { + if (!input.trySkipNullValue()) { + rearLeft = input.readDouble(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case -724967720: + case -618613823: { + if (input.isAtField(FieldNames.rearRight)) { + if (!input.trySkipNullValue()) { + rearRight = input.readDouble(); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufMecanumDriveWheelSpeeds clone() { + return new ProtobufMecanumDriveWheelSpeeds().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufMecanumDriveWheelSpeeds parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufMecanumDriveWheelSpeeds(), data).checkInitialized(); + } + + public static ProtobufMecanumDriveWheelSpeeds parseFrom(final ProtoSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufMecanumDriveWheelSpeeds(), input).checkInitialized(); + } + + public static ProtobufMecanumDriveWheelSpeeds parseFrom(final JsonSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufMecanumDriveWheelSpeeds(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufMecanumDriveWheelSpeeds messages + */ + public static MessageFactory getFactory() { + return ProtobufMecanumDriveWheelSpeedsFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Kinematics.wpi_proto_ProtobufMecanumDriveWheelSpeeds_descriptor; + } + + private enum ProtobufMecanumDriveWheelSpeedsFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufMecanumDriveWheelSpeeds create() { + return ProtobufMecanumDriveWheelSpeeds.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName frontLeft = FieldName.forField("frontLeft", "front_left"); + + static final FieldName frontRight = FieldName.forField("frontRight", "front_right"); + + static final FieldName rearLeft = FieldName.forField("rearLeft", "rear_left"); + + static final FieldName rearRight = FieldName.forField("rearRight", "rear_right"); + } + } + + /** + * Protobuf type {@code ProtobufSwerveDriveKinematics} + */ + public static final class ProtobufSwerveDriveKinematics extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * repeated .wpi.proto.ProtobufTranslation2d modules = 1; + */ + private final RepeatedMessage modules = RepeatedMessage.newEmptyInstance(Geometry2D.ProtobufTranslation2d.getFactory()); + + private ProtobufSwerveDriveKinematics() { + } + + /** + * @return a new empty instance of {@code ProtobufSwerveDriveKinematics} + */ + public static ProtobufSwerveDriveKinematics newInstance() { + return new ProtobufSwerveDriveKinematics(); + } + + /** + * repeated .wpi.proto.ProtobufTranslation2d modules = 1; + * @return whether the modules field is set + */ + public boolean hasModules() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * repeated .wpi.proto.ProtobufTranslation2d modules = 1; + * @return this + */ + public ProtobufSwerveDriveKinematics clearModules() { + bitField0_ &= ~0x00000001; + modules.clear(); + return this; + } + + /** + * repeated .wpi.proto.ProtobufTranslation2d modules = 1; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableModules()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedMessage getModules() { + return modules; + } + + /** + * repeated .wpi.proto.ProtobufTranslation2d modules = 1; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedMessage getMutableModules() { + bitField0_ |= 0x00000001; + return modules; + } + + /** + * repeated .wpi.proto.ProtobufTranslation2d modules = 1; + * @param value the modules to add + * @return this + */ + public ProtobufSwerveDriveKinematics addModules(final Geometry2D.ProtobufTranslation2d value) { + bitField0_ |= 0x00000001; + modules.add(value); + return this; + } + + /** + * repeated .wpi.proto.ProtobufTranslation2d modules = 1; + * @param values the modules to add + * @return this + */ + public ProtobufSwerveDriveKinematics addAllModules( + final Geometry2D.ProtobufTranslation2d... values) { + bitField0_ |= 0x00000001; + modules.addAll(values); + return this; + } + + @Override + public ProtobufSwerveDriveKinematics copyFrom(final ProtobufSwerveDriveKinematics other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + modules.copyFrom(other.modules); + } + return this; + } + + @Override + public ProtobufSwerveDriveKinematics mergeFrom(final ProtobufSwerveDriveKinematics other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasModules()) { + getMutableModules().addAll(other.modules); + } + return this; + } + + @Override + public ProtobufSwerveDriveKinematics clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + modules.clear(); + return this; + } + + @Override + public ProtobufSwerveDriveKinematics clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + modules.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufSwerveDriveKinematics)) { + return false; + } + ProtobufSwerveDriveKinematics other = (ProtobufSwerveDriveKinematics) o; + return bitField0_ == other.bitField0_ + && (!hasModules() || modules.equals(other.modules)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + for (int i = 0; i < modules.length(); i++) { + output.writeRawByte((byte) 10); + output.writeMessageNoTag(modules.get(i)); + } + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += (1 * modules.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(modules); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufSwerveDriveKinematics mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 10: { + // modules + tag = input.readRepeatedMessage(modules, tag); + bitField0_ |= 0x00000001; + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeRepeatedMessage(FieldNames.modules, modules); + } + output.endObject(); + } + + @Override + public ProtobufSwerveDriveKinematics mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 1227433863: { + if (input.isAtField(FieldNames.modules)) { + if (!input.trySkipNullValue()) { + input.readRepeatedMessage(modules); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufSwerveDriveKinematics clone() { + return new ProtobufSwerveDriveKinematics().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufSwerveDriveKinematics parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufSwerveDriveKinematics(), data).checkInitialized(); + } + + public static ProtobufSwerveDriveKinematics parseFrom(final ProtoSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufSwerveDriveKinematics(), input).checkInitialized(); + } + + public static ProtobufSwerveDriveKinematics parseFrom(final JsonSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufSwerveDriveKinematics(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufSwerveDriveKinematics messages + */ + public static MessageFactory getFactory() { + return ProtobufSwerveDriveKinematicsFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Kinematics.wpi_proto_ProtobufSwerveDriveKinematics_descriptor; + } + + private enum ProtobufSwerveDriveKinematicsFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufSwerveDriveKinematics create() { + return ProtobufSwerveDriveKinematics.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName modules = FieldName.forField("modules"); + } + } + + /** + * Protobuf type {@code ProtobufSwerveModulePosition} + */ + public static final class ProtobufSwerveModulePosition extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double distance = 1; + */ + private double distance; + + /** + * optional .wpi.proto.ProtobufRotation2d angle = 2; + */ + private final Geometry2D.ProtobufRotation2d angle = Geometry2D.ProtobufRotation2d.newInstance(); + + private ProtobufSwerveModulePosition() { + } + + /** + * @return a new empty instance of {@code ProtobufSwerveModulePosition} + */ + public static ProtobufSwerveModulePosition newInstance() { + return new ProtobufSwerveModulePosition(); + } + + /** + * optional double distance = 1; + * @return whether the distance field is set + */ + public boolean hasDistance() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double distance = 1; + * @return this + */ + public ProtobufSwerveModulePosition clearDistance() { + bitField0_ &= ~0x00000001; + distance = 0D; + return this; + } + + /** + * optional double distance = 1; + * @return the distance + */ + public double getDistance() { + return distance; + } + + /** + * optional double distance = 1; + * @param value the distance to set + * @return this + */ + public ProtobufSwerveModulePosition setDistance(final double value) { + bitField0_ |= 0x00000001; + distance = value; + return this; + } + + /** + * optional .wpi.proto.ProtobufRotation2d angle = 2; + * @return whether the angle field is set + */ + public boolean hasAngle() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional .wpi.proto.ProtobufRotation2d angle = 2; + * @return this + */ + public ProtobufSwerveModulePosition clearAngle() { + bitField0_ &= ~0x00000002; + angle.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufRotation2d angle = 2; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableAngle()} if you want to modify it. + * + * @return internal storage object for reading + */ + public Geometry2D.ProtobufRotation2d getAngle() { + return angle; + } + + /** + * optional .wpi.proto.ProtobufRotation2d angle = 2; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public Geometry2D.ProtobufRotation2d getMutableAngle() { + bitField0_ |= 0x00000002; + return angle; + } + + /** + * optional .wpi.proto.ProtobufRotation2d angle = 2; + * @param value the angle to set + * @return this + */ + public ProtobufSwerveModulePosition setAngle(final Geometry2D.ProtobufRotation2d value) { + bitField0_ |= 0x00000002; + angle.copyFrom(value); + return this; + } + + @Override + public ProtobufSwerveModulePosition copyFrom(final ProtobufSwerveModulePosition other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + distance = other.distance; + angle.copyFrom(other.angle); + } + return this; + } + + @Override + public ProtobufSwerveModulePosition mergeFrom(final ProtobufSwerveModulePosition other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasDistance()) { + setDistance(other.distance); + } + if (other.hasAngle()) { + getMutableAngle().mergeFrom(other.angle); + } + return this; + } + + @Override + public ProtobufSwerveModulePosition clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + distance = 0D; + angle.clear(); + return this; + } + + @Override + public ProtobufSwerveModulePosition clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + angle.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufSwerveModulePosition)) { + return false; + } + ProtobufSwerveModulePosition other = (ProtobufSwerveModulePosition) o; + return bitField0_ == other.bitField0_ + && (!hasDistance() || ProtoUtil.isEqual(distance, other.distance)) + && (!hasAngle() || angle.equals(other.angle)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(distance); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 18); + output.writeMessageNoTag(angle); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(angle); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufSwerveModulePosition mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // distance + distance = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 18) { + break; + } + } + case 18: { + // angle + input.readMessage(angle); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.distance, distance); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeMessage(FieldNames.angle, angle); + } + output.endObject(); + } + + @Override + public ProtobufSwerveModulePosition mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 288459765: { + if (input.isAtField(FieldNames.distance)) { + if (!input.trySkipNullValue()) { + distance = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 92960979: { + if (input.isAtField(FieldNames.angle)) { + if (!input.trySkipNullValue()) { + input.readMessage(angle); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufSwerveModulePosition clone() { + return new ProtobufSwerveModulePosition().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufSwerveModulePosition parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufSwerveModulePosition(), data).checkInitialized(); + } + + public static ProtobufSwerveModulePosition parseFrom(final ProtoSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufSwerveModulePosition(), input).checkInitialized(); + } + + public static ProtobufSwerveModulePosition parseFrom(final JsonSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufSwerveModulePosition(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufSwerveModulePosition messages + */ + public static MessageFactory getFactory() { + return ProtobufSwerveModulePositionFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Kinematics.wpi_proto_ProtobufSwerveModulePosition_descriptor; + } + + private enum ProtobufSwerveModulePositionFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufSwerveModulePosition create() { + return ProtobufSwerveModulePosition.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName distance = FieldName.forField("distance"); + + static final FieldName angle = FieldName.forField("angle"); + } + } + + /** + * Protobuf type {@code ProtobufSwerveModuleState} + */ + public static final class ProtobufSwerveModuleState extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double speed = 1; + */ + private double speed; + + /** + * optional .wpi.proto.ProtobufRotation2d angle = 2; + */ + private final Geometry2D.ProtobufRotation2d angle = Geometry2D.ProtobufRotation2d.newInstance(); + + private ProtobufSwerveModuleState() { + } + + /** + * @return a new empty instance of {@code ProtobufSwerveModuleState} + */ + public static ProtobufSwerveModuleState newInstance() { + return new ProtobufSwerveModuleState(); + } + + /** + * optional double speed = 1; + * @return whether the speed field is set + */ + public boolean hasSpeed() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double speed = 1; + * @return this + */ + public ProtobufSwerveModuleState clearSpeed() { + bitField0_ &= ~0x00000001; + speed = 0D; + return this; + } + + /** + * optional double speed = 1; + * @return the speed + */ + public double getSpeed() { + return speed; + } + + /** + * optional double speed = 1; + * @param value the speed to set + * @return this + */ + public ProtobufSwerveModuleState setSpeed(final double value) { + bitField0_ |= 0x00000001; + speed = value; + return this; + } + + /** + * optional .wpi.proto.ProtobufRotation2d angle = 2; + * @return whether the angle field is set + */ + public boolean hasAngle() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional .wpi.proto.ProtobufRotation2d angle = 2; + * @return this + */ + public ProtobufSwerveModuleState clearAngle() { + bitField0_ &= ~0x00000002; + angle.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufRotation2d angle = 2; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableAngle()} if you want to modify it. + * + * @return internal storage object for reading + */ + public Geometry2D.ProtobufRotation2d getAngle() { + return angle; + } + + /** + * optional .wpi.proto.ProtobufRotation2d angle = 2; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public Geometry2D.ProtobufRotation2d getMutableAngle() { + bitField0_ |= 0x00000002; + return angle; + } + + /** + * optional .wpi.proto.ProtobufRotation2d angle = 2; + * @param value the angle to set + * @return this + */ + public ProtobufSwerveModuleState setAngle(final Geometry2D.ProtobufRotation2d value) { + bitField0_ |= 0x00000002; + angle.copyFrom(value); + return this; + } + + @Override + public ProtobufSwerveModuleState copyFrom(final ProtobufSwerveModuleState other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + speed = other.speed; + angle.copyFrom(other.angle); + } + return this; + } + + @Override + public ProtobufSwerveModuleState mergeFrom(final ProtobufSwerveModuleState other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasSpeed()) { + setSpeed(other.speed); + } + if (other.hasAngle()) { + getMutableAngle().mergeFrom(other.angle); + } + return this; + } + + @Override + public ProtobufSwerveModuleState clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + speed = 0D; + angle.clear(); + return this; + } + + @Override + public ProtobufSwerveModuleState clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + angle.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufSwerveModuleState)) { + return false; + } + ProtobufSwerveModuleState other = (ProtobufSwerveModuleState) o; + return bitField0_ == other.bitField0_ + && (!hasSpeed() || ProtoUtil.isEqual(speed, other.speed)) + && (!hasAngle() || angle.equals(other.angle)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(speed); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 18); + output.writeMessageNoTag(angle); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(angle); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufSwerveModuleState mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // speed + speed = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 18) { + break; + } + } + case 18: { + // angle + input.readMessage(angle); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.speed, speed); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeMessage(FieldNames.angle, angle); + } + output.endObject(); + } + + @Override + public ProtobufSwerveModuleState mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 109641799: { + if (input.isAtField(FieldNames.speed)) { + if (!input.trySkipNullValue()) { + speed = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 92960979: { + if (input.isAtField(FieldNames.angle)) { + if (!input.trySkipNullValue()) { + input.readMessage(angle); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufSwerveModuleState clone() { + return new ProtobufSwerveModuleState().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufSwerveModuleState parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufSwerveModuleState(), data).checkInitialized(); + } + + public static ProtobufSwerveModuleState parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufSwerveModuleState(), input).checkInitialized(); + } + + public static ProtobufSwerveModuleState parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufSwerveModuleState(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufSwerveModuleState messages + */ + public static MessageFactory getFactory() { + return ProtobufSwerveModuleStateFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Kinematics.wpi_proto_ProtobufSwerveModuleState_descriptor; + } + + private enum ProtobufSwerveModuleStateFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufSwerveModuleState create() { + return ProtobufSwerveModuleState.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName speed = FieldName.forField("speed"); + + static final FieldName angle = FieldName.forField("angle"); + } + } +} diff --git a/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Plant.java b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Plant.java new file mode 100644 index 00000000000..61b758fd12f --- /dev/null +++ b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Plant.java @@ -0,0 +1,621 @@ +// 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. +// Code generated by protocol buffer compiler. Do not edit! +package edu.wpi.first.math.proto; + +import java.io.IOException; +import us.hebi.quickbuf.Descriptors; +import us.hebi.quickbuf.FieldName; +import us.hebi.quickbuf.InvalidProtocolBufferException; +import us.hebi.quickbuf.JsonSink; +import us.hebi.quickbuf.JsonSource; +import us.hebi.quickbuf.MessageFactory; +import us.hebi.quickbuf.ProtoMessage; +import us.hebi.quickbuf.ProtoSink; +import us.hebi.quickbuf.ProtoSource; +import us.hebi.quickbuf.ProtoUtil; +import us.hebi.quickbuf.RepeatedByte; + +public final class Plant { + private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(610, + "CgtwbGFudC5wcm90bxIJd3BpLnByb3RvIsQBCg9Qcm90b2J1ZkRDTW90b3ISJwoPbm9taW5hbF92b2x0" + + "YWdlGAEgASgBUg5ub21pbmFsVm9sdGFnZRIhCgxzdGFsbF90b3JxdWUYAiABKAFSC3N0YWxsVG9ycXVl" + + "EiMKDXN0YWxsX2N1cnJlbnQYAyABKAFSDHN0YWxsQ3VycmVudBIhCgxmcmVlX2N1cnJlbnQYBCABKAFS" + + "C2ZyZWVDdXJyZW50Eh0KCmZyZWVfc3BlZWQYBSABKAFSCWZyZWVTcGVlZEIaChhlZHUud3BpLmZpcnN0" + + "Lm1hdGgucHJvdG9K3AIKBhIEAAAMAQoICgEMEgMAABIKCAoBAhIDAgASCggKAQgSAwQAMQoJCgIIARID" + + "BAAxCgoKAgQAEgQGAAwBCgoKAwQAARIDBggXCgsKBAQAAgASAwcCHQoMCgUEAAIABRIDBwIICgwKBQQA" + + "AgABEgMHCRgKDAoFBAACAAMSAwcbHAoLCgQEAAIBEgMIAhoKDAoFBAACAQUSAwgCCAoMCgUEAAIBARID" + + "CAkVCgwKBQQAAgEDEgMIGBkKCwoEBAACAhIDCQIbCgwKBQQAAgIFEgMJAggKDAoFBAACAgESAwkJFgoM" + + "CgUEAAICAxIDCRkaCgsKBAQAAgMSAwoCGgoMCgUEAAIDBRIDCgIICgwKBQQAAgMBEgMKCRUKDAoFBAAC" + + "AwMSAwoYGQoLCgQEAAIEEgMLAhgKDAoFBAACBAUSAwsCCAoMCgUEAAIEARIDCwkTCgwKBQQAAgQDEgML" + + "FhdiBnByb3RvMw=="); + + static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("plant.proto", "wpi.proto", descriptorData); + + static final Descriptors.Descriptor wpi_proto_ProtobufDCMotor_descriptor = descriptor.internalContainedType(27, 196, "ProtobufDCMotor", "wpi.proto.ProtobufDCMotor"); + + /** + * @return this proto file's descriptor. + */ + public static Descriptors.FileDescriptor getDescriptor() { + return descriptor; + } + + /** + * Protobuf type {@code ProtobufDCMotor} + */ + public static final class ProtobufDCMotor extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double nominal_voltage = 1; + */ + private double nominalVoltage; + + /** + * optional double stall_torque = 2; + */ + private double stallTorque; + + /** + * optional double stall_current = 3; + */ + private double stallCurrent; + + /** + * optional double free_current = 4; + */ + private double freeCurrent; + + /** + * optional double free_speed = 5; + */ + private double freeSpeed; + + private ProtobufDCMotor() { + } + + /** + * @return a new empty instance of {@code ProtobufDCMotor} + */ + public static ProtobufDCMotor newInstance() { + return new ProtobufDCMotor(); + } + + /** + * optional double nominal_voltage = 1; + * @return whether the nominalVoltage field is set + */ + public boolean hasNominalVoltage() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double nominal_voltage = 1; + * @return this + */ + public ProtobufDCMotor clearNominalVoltage() { + bitField0_ &= ~0x00000001; + nominalVoltage = 0D; + return this; + } + + /** + * optional double nominal_voltage = 1; + * @return the nominalVoltage + */ + public double getNominalVoltage() { + return nominalVoltage; + } + + /** + * optional double nominal_voltage = 1; + * @param value the nominalVoltage to set + * @return this + */ + public ProtobufDCMotor setNominalVoltage(final double value) { + bitField0_ |= 0x00000001; + nominalVoltage = value; + return this; + } + + /** + * optional double stall_torque = 2; + * @return whether the stallTorque field is set + */ + public boolean hasStallTorque() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double stall_torque = 2; + * @return this + */ + public ProtobufDCMotor clearStallTorque() { + bitField0_ &= ~0x00000002; + stallTorque = 0D; + return this; + } + + /** + * optional double stall_torque = 2; + * @return the stallTorque + */ + public double getStallTorque() { + return stallTorque; + } + + /** + * optional double stall_torque = 2; + * @param value the stallTorque to set + * @return this + */ + public ProtobufDCMotor setStallTorque(final double value) { + bitField0_ |= 0x00000002; + stallTorque = value; + return this; + } + + /** + * optional double stall_current = 3; + * @return whether the stallCurrent field is set + */ + public boolean hasStallCurrent() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional double stall_current = 3; + * @return this + */ + public ProtobufDCMotor clearStallCurrent() { + bitField0_ &= ~0x00000004; + stallCurrent = 0D; + return this; + } + + /** + * optional double stall_current = 3; + * @return the stallCurrent + */ + public double getStallCurrent() { + return stallCurrent; + } + + /** + * optional double stall_current = 3; + * @param value the stallCurrent to set + * @return this + */ + public ProtobufDCMotor setStallCurrent(final double value) { + bitField0_ |= 0x00000004; + stallCurrent = value; + return this; + } + + /** + * optional double free_current = 4; + * @return whether the freeCurrent field is set + */ + public boolean hasFreeCurrent() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * optional double free_current = 4; + * @return this + */ + public ProtobufDCMotor clearFreeCurrent() { + bitField0_ &= ~0x00000008; + freeCurrent = 0D; + return this; + } + + /** + * optional double free_current = 4; + * @return the freeCurrent + */ + public double getFreeCurrent() { + return freeCurrent; + } + + /** + * optional double free_current = 4; + * @param value the freeCurrent to set + * @return this + */ + public ProtobufDCMotor setFreeCurrent(final double value) { + bitField0_ |= 0x00000008; + freeCurrent = value; + return this; + } + + /** + * optional double free_speed = 5; + * @return whether the freeSpeed field is set + */ + public boolean hasFreeSpeed() { + return (bitField0_ & 0x00000010) != 0; + } + + /** + * optional double free_speed = 5; + * @return this + */ + public ProtobufDCMotor clearFreeSpeed() { + bitField0_ &= ~0x00000010; + freeSpeed = 0D; + return this; + } + + /** + * optional double free_speed = 5; + * @return the freeSpeed + */ + public double getFreeSpeed() { + return freeSpeed; + } + + /** + * optional double free_speed = 5; + * @param value the freeSpeed to set + * @return this + */ + public ProtobufDCMotor setFreeSpeed(final double value) { + bitField0_ |= 0x00000010; + freeSpeed = value; + return this; + } + + @Override + public ProtobufDCMotor copyFrom(final ProtobufDCMotor other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + nominalVoltage = other.nominalVoltage; + stallTorque = other.stallTorque; + stallCurrent = other.stallCurrent; + freeCurrent = other.freeCurrent; + freeSpeed = other.freeSpeed; + } + return this; + } + + @Override + public ProtobufDCMotor mergeFrom(final ProtobufDCMotor other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasNominalVoltage()) { + setNominalVoltage(other.nominalVoltage); + } + if (other.hasStallTorque()) { + setStallTorque(other.stallTorque); + } + if (other.hasStallCurrent()) { + setStallCurrent(other.stallCurrent); + } + if (other.hasFreeCurrent()) { + setFreeCurrent(other.freeCurrent); + } + if (other.hasFreeSpeed()) { + setFreeSpeed(other.freeSpeed); + } + return this; + } + + @Override + public ProtobufDCMotor clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + nominalVoltage = 0D; + stallTorque = 0D; + stallCurrent = 0D; + freeCurrent = 0D; + freeSpeed = 0D; + return this; + } + + @Override + public ProtobufDCMotor clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufDCMotor)) { + return false; + } + ProtobufDCMotor other = (ProtobufDCMotor) o; + return bitField0_ == other.bitField0_ + && (!hasNominalVoltage() || ProtoUtil.isEqual(nominalVoltage, other.nominalVoltage)) + && (!hasStallTorque() || ProtoUtil.isEqual(stallTorque, other.stallTorque)) + && (!hasStallCurrent() || ProtoUtil.isEqual(stallCurrent, other.stallCurrent)) + && (!hasFreeCurrent() || ProtoUtil.isEqual(freeCurrent, other.freeCurrent)) + && (!hasFreeSpeed() || ProtoUtil.isEqual(freeSpeed, other.freeSpeed)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(nominalVoltage); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(stallTorque); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(stallCurrent); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRawByte((byte) 33); + output.writeDoubleNoTag(freeCurrent); + } + if ((bitField0_ & 0x00000010) != 0) { + output.writeRawByte((byte) 41); + output.writeDoubleNoTag(freeSpeed); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000004) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000008) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000010) != 0) { + size += 9; + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufDCMotor mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // nominalVoltage + nominalVoltage = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // stallTorque + stallTorque = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 25) { + break; + } + } + case 25: { + // stallCurrent + stallCurrent = input.readDouble(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 33) { + break; + } + } + case 33: { + // freeCurrent + freeCurrent = input.readDouble(); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 41) { + break; + } + } + case 41: { + // freeSpeed + freeSpeed = input.readDouble(); + bitField0_ |= 0x00000010; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.nominalVoltage, nominalVoltage); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.stallTorque, stallTorque); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeDouble(FieldNames.stallCurrent, stallCurrent); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeDouble(FieldNames.freeCurrent, freeCurrent); + } + if ((bitField0_ & 0x00000010) != 0) { + output.writeDouble(FieldNames.freeSpeed, freeSpeed); + } + output.endObject(); + } + + @Override + public ProtobufDCMotor mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 1374862050: + case 173092603: { + if (input.isAtField(FieldNames.nominalVoltage)) { + if (!input.trySkipNullValue()) { + nominalVoltage = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 2075810250: + case 1238615945: { + if (input.isAtField(FieldNames.stallTorque)) { + if (!input.trySkipNullValue()) { + stallTorque = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case -2105262663: + case 2006484954: { + if (input.isAtField(FieldNames.stallCurrent)) { + if (!input.trySkipNullValue()) { + stallCurrent = input.readDouble(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case 1024355693: + case 240406182: { + if (input.isAtField(FieldNames.freeCurrent)) { + if (!input.trySkipNullValue()) { + freeCurrent = input.readDouble(); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + case -444654277: + case -552732492: { + if (input.isAtField(FieldNames.freeSpeed)) { + if (!input.trySkipNullValue()) { + freeSpeed = input.readDouble(); + bitField0_ |= 0x00000010; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufDCMotor clone() { + return new ProtobufDCMotor().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufDCMotor parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufDCMotor(), data).checkInitialized(); + } + + public static ProtobufDCMotor parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufDCMotor(), input).checkInitialized(); + } + + public static ProtobufDCMotor parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufDCMotor(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufDCMotor messages + */ + public static MessageFactory getFactory() { + return ProtobufDCMotorFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Plant.wpi_proto_ProtobufDCMotor_descriptor; + } + + private enum ProtobufDCMotorFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufDCMotor create() { + return ProtobufDCMotor.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName nominalVoltage = FieldName.forField("nominalVoltage", "nominal_voltage"); + + static final FieldName stallTorque = FieldName.forField("stallTorque", "stall_torque"); + + static final FieldName stallCurrent = FieldName.forField("stallCurrent", "stall_current"); + + static final FieldName freeCurrent = FieldName.forField("freeCurrent", "free_current"); + + static final FieldName freeSpeed = FieldName.forField("freeSpeed", "free_speed"); + } + } +} diff --git a/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Spline.java b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Spline.java new file mode 100644 index 00000000000..accdecb07a7 --- /dev/null +++ b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Spline.java @@ -0,0 +1,1367 @@ +// 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. +// Code generated by protocol buffer compiler. Do not edit! +package edu.wpi.first.math.proto; + +import java.io.IOException; +import us.hebi.quickbuf.Descriptors; +import us.hebi.quickbuf.FieldName; +import us.hebi.quickbuf.InvalidProtocolBufferException; +import us.hebi.quickbuf.JsonSink; +import us.hebi.quickbuf.JsonSource; +import us.hebi.quickbuf.MessageFactory; +import us.hebi.quickbuf.ProtoMessage; +import us.hebi.quickbuf.ProtoSink; +import us.hebi.quickbuf.ProtoSource; +import us.hebi.quickbuf.ProtoUtil; +import us.hebi.quickbuf.RepeatedByte; +import us.hebi.quickbuf.RepeatedDouble; + +public final class Spline { + private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(993, + "CgxzcGxpbmUucHJvdG8SCXdwaS5wcm90byKIAQoaUHJvdG9idWZDdWJpY0hlcm1pdGVTcGxpbmUSGwoJ" + + "eF9pbml0aWFsGAEgAygBUgh4SW5pdGlhbBIXCgd4X2ZpbmFsGAIgAygBUgZ4RmluYWwSGwoJeV9pbml0" + + "aWFsGAMgAygBUgh5SW5pdGlhbBIXCgd5X2ZpbmFsGAQgAygBUgZ5RmluYWwiigEKHFByb3RvYnVmUXVp" + + "bnRpY0hlcm1pdGVTcGxpbmUSGwoJeF9pbml0aWFsGAEgAygBUgh4SW5pdGlhbBIXCgd4X2ZpbmFsGAIg" + + "AygBUgZ4RmluYWwSGwoJeV9pbml0aWFsGAMgAygBUgh5SW5pdGlhbBIXCgd5X2ZpbmFsGAQgAygBUgZ5" + + "RmluYWxCGgoYZWR1LndwaS5maXJzdC5tYXRoLnByb3RvSokFCgYSBAAAEgEKCAoBDBIDAAASCggKAQIS" + + "AwIAEgoICgEIEgMEADEKCQoCCAESAwQAMQoKCgIEABIEBgALAQoKCgMEAAESAwYIIgoLCgQEAAIAEgMH" + + "AiAKDAoFBAACAAQSAwcCCgoMCgUEAAIABRIDBwsRCgwKBQQAAgABEgMHEhsKDAoFBAACAAMSAwceHwoL" + + "CgQEAAIBEgMIAh4KDAoFBAACAQQSAwgCCgoMCgUEAAIBBRIDCAsRCgwKBQQAAgEBEgMIEhkKDAoFBAAC" + + "AQMSAwgcHQoLCgQEAAICEgMJAiAKDAoFBAACAgQSAwkCCgoMCgUEAAICBRIDCQsRCgwKBQQAAgIBEgMJ" + + "EhsKDAoFBAACAgMSAwkeHwoLCgQEAAIDEgMKAh4KDAoFBAACAwQSAwoCCgoMCgUEAAIDBRIDCgsRCgwK" + + "BQQAAgMBEgMKEhkKDAoFBAACAwMSAwocHQoKCgIEARIEDQASAQoKCgMEAQESAw0IJAoLCgQEAQIAEgMO" + + "AiAKDAoFBAECAAQSAw4CCgoMCgUEAQIABRIDDgsRCgwKBQQBAgABEgMOEhsKDAoFBAECAAMSAw4eHwoL" + + "CgQEAQIBEgMPAh4KDAoFBAECAQQSAw8CCgoMCgUEAQIBBRIDDwsRCgwKBQQBAgEBEgMPEhkKDAoFBAEC" + + "AQMSAw8cHQoLCgQEAQICEgMQAiAKDAoFBAECAgQSAxACCgoMCgUEAQICBRIDEAsRCgwKBQQBAgIBEgMQ" + + "EhsKDAoFBAECAgMSAxAeHwoLCgQEAQIDEgMRAh4KDAoFBAECAwQSAxECCgoMCgUEAQIDBRIDEQsRCgwK" + + "BQQBAgMBEgMREhkKDAoFBAECAwMSAxEcHWIGcHJvdG8z"); + + static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("spline.proto", "wpi.proto", descriptorData); + + static final Descriptors.Descriptor wpi_proto_ProtobufCubicHermiteSpline_descriptor = descriptor.internalContainedType(28, 136, "ProtobufCubicHermiteSpline", "wpi.proto.ProtobufCubicHermiteSpline"); + + static final Descriptors.Descriptor wpi_proto_ProtobufQuinticHermiteSpline_descriptor = descriptor.internalContainedType(167, 138, "ProtobufQuinticHermiteSpline", "wpi.proto.ProtobufQuinticHermiteSpline"); + + /** + * @return this proto file's descriptor. + */ + public static Descriptors.FileDescriptor getDescriptor() { + return descriptor; + } + + /** + * Protobuf type {@code ProtobufCubicHermiteSpline} + */ + public static final class ProtobufCubicHermiteSpline extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * repeated double x_initial = 1; + */ + private final RepeatedDouble xInitial = RepeatedDouble.newEmptyInstance(); + + /** + * repeated double x_final = 2; + */ + private final RepeatedDouble xFinal = RepeatedDouble.newEmptyInstance(); + + /** + * repeated double y_initial = 3; + */ + private final RepeatedDouble yInitial = RepeatedDouble.newEmptyInstance(); + + /** + * repeated double y_final = 4; + */ + private final RepeatedDouble yFinal = RepeatedDouble.newEmptyInstance(); + + private ProtobufCubicHermiteSpline() { + } + + /** + * @return a new empty instance of {@code ProtobufCubicHermiteSpline} + */ + public static ProtobufCubicHermiteSpline newInstance() { + return new ProtobufCubicHermiteSpline(); + } + + /** + * repeated double x_initial = 1; + * @return whether the xInitial field is set + */ + public boolean hasXInitial() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * repeated double x_initial = 1; + * @return this + */ + public ProtobufCubicHermiteSpline clearXInitial() { + bitField0_ &= ~0x00000001; + xInitial.clear(); + return this; + } + + /** + * repeated double x_initial = 1; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableXInitial()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedDouble getXInitial() { + return xInitial; + } + + /** + * repeated double x_initial = 1; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedDouble getMutableXInitial() { + bitField0_ |= 0x00000001; + return xInitial; + } + + /** + * repeated double x_initial = 1; + * @param value the xInitial to add + * @return this + */ + public ProtobufCubicHermiteSpline addXInitial(final double value) { + bitField0_ |= 0x00000001; + xInitial.add(value); + return this; + } + + /** + * repeated double x_initial = 1; + * @param values the xInitial to add + * @return this + */ + public ProtobufCubicHermiteSpline addAllXInitial(final double... values) { + bitField0_ |= 0x00000001; + xInitial.addAll(values); + return this; + } + + /** + * repeated double x_final = 2; + * @return whether the xFinal field is set + */ + public boolean hasXFinal() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * repeated double x_final = 2; + * @return this + */ + public ProtobufCubicHermiteSpline clearXFinal() { + bitField0_ &= ~0x00000002; + xFinal.clear(); + return this; + } + + /** + * repeated double x_final = 2; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableXFinal()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedDouble getXFinal() { + return xFinal; + } + + /** + * repeated double x_final = 2; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedDouble getMutableXFinal() { + bitField0_ |= 0x00000002; + return xFinal; + } + + /** + * repeated double x_final = 2; + * @param value the xFinal to add + * @return this + */ + public ProtobufCubicHermiteSpline addXFinal(final double value) { + bitField0_ |= 0x00000002; + xFinal.add(value); + return this; + } + + /** + * repeated double x_final = 2; + * @param values the xFinal to add + * @return this + */ + public ProtobufCubicHermiteSpline addAllXFinal(final double... values) { + bitField0_ |= 0x00000002; + xFinal.addAll(values); + return this; + } + + /** + * repeated double y_initial = 3; + * @return whether the yInitial field is set + */ + public boolean hasYInitial() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * repeated double y_initial = 3; + * @return this + */ + public ProtobufCubicHermiteSpline clearYInitial() { + bitField0_ &= ~0x00000004; + yInitial.clear(); + return this; + } + + /** + * repeated double y_initial = 3; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableYInitial()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedDouble getYInitial() { + return yInitial; + } + + /** + * repeated double y_initial = 3; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedDouble getMutableYInitial() { + bitField0_ |= 0x00000004; + return yInitial; + } + + /** + * repeated double y_initial = 3; + * @param value the yInitial to add + * @return this + */ + public ProtobufCubicHermiteSpline addYInitial(final double value) { + bitField0_ |= 0x00000004; + yInitial.add(value); + return this; + } + + /** + * repeated double y_initial = 3; + * @param values the yInitial to add + * @return this + */ + public ProtobufCubicHermiteSpline addAllYInitial(final double... values) { + bitField0_ |= 0x00000004; + yInitial.addAll(values); + return this; + } + + /** + * repeated double y_final = 4; + * @return whether the yFinal field is set + */ + public boolean hasYFinal() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * repeated double y_final = 4; + * @return this + */ + public ProtobufCubicHermiteSpline clearYFinal() { + bitField0_ &= ~0x00000008; + yFinal.clear(); + return this; + } + + /** + * repeated double y_final = 4; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableYFinal()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedDouble getYFinal() { + return yFinal; + } + + /** + * repeated double y_final = 4; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedDouble getMutableYFinal() { + bitField0_ |= 0x00000008; + return yFinal; + } + + /** + * repeated double y_final = 4; + * @param value the yFinal to add + * @return this + */ + public ProtobufCubicHermiteSpline addYFinal(final double value) { + bitField0_ |= 0x00000008; + yFinal.add(value); + return this; + } + + /** + * repeated double y_final = 4; + * @param values the yFinal to add + * @return this + */ + public ProtobufCubicHermiteSpline addAllYFinal(final double... values) { + bitField0_ |= 0x00000008; + yFinal.addAll(values); + return this; + } + + @Override + public ProtobufCubicHermiteSpline copyFrom(final ProtobufCubicHermiteSpline other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + xInitial.copyFrom(other.xInitial); + xFinal.copyFrom(other.xFinal); + yInitial.copyFrom(other.yInitial); + yFinal.copyFrom(other.yFinal); + } + return this; + } + + @Override + public ProtobufCubicHermiteSpline mergeFrom(final ProtobufCubicHermiteSpline other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasXInitial()) { + getMutableXInitial().addAll(other.xInitial); + } + if (other.hasXFinal()) { + getMutableXFinal().addAll(other.xFinal); + } + if (other.hasYInitial()) { + getMutableYInitial().addAll(other.yInitial); + } + if (other.hasYFinal()) { + getMutableYFinal().addAll(other.yFinal); + } + return this; + } + + @Override + public ProtobufCubicHermiteSpline clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + xInitial.clear(); + xFinal.clear(); + yInitial.clear(); + yFinal.clear(); + return this; + } + + @Override + public ProtobufCubicHermiteSpline clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + xInitial.clear(); + xFinal.clear(); + yInitial.clear(); + yFinal.clear(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufCubicHermiteSpline)) { + return false; + } + ProtobufCubicHermiteSpline other = (ProtobufCubicHermiteSpline) o; + return bitField0_ == other.bitField0_ + && (!hasXInitial() || xInitial.equals(other.xInitial)) + && (!hasXFinal() || xFinal.equals(other.xFinal)) + && (!hasYInitial() || yInitial.equals(other.yInitial)) + && (!hasYFinal() || yFinal.equals(other.yFinal)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + for (int i = 0; i < xInitial.length(); i++) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(xInitial.array()[i]); + } + } + if ((bitField0_ & 0x00000002) != 0) { + for (int i = 0; i < xFinal.length(); i++) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(xFinal.array()[i]); + } + } + if ((bitField0_ & 0x00000004) != 0) { + for (int i = 0; i < yInitial.length(); i++) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(yInitial.array()[i]); + } + } + if ((bitField0_ & 0x00000008) != 0) { + for (int i = 0; i < yFinal.length(); i++) { + output.writeRawByte((byte) 33); + output.writeDoubleNoTag(yFinal.array()[i]); + } + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += (1 + 8) * xInitial.length(); + } + if ((bitField0_ & 0x00000002) != 0) { + size += (1 + 8) * xFinal.length(); + } + if ((bitField0_ & 0x00000004) != 0) { + size += (1 + 8) * yInitial.length(); + } + if ((bitField0_ & 0x00000008) != 0) { + size += (1 + 8) * yFinal.length(); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufCubicHermiteSpline mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 10: { + // xInitial [packed=true] + input.readPackedDouble(xInitial); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 18) { + break; + } + } + case 18: { + // xFinal [packed=true] + input.readPackedDouble(xFinal); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 26) { + break; + } + } + case 26: { + // yInitial [packed=true] + input.readPackedDouble(yInitial); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 34) { + break; + } + } + case 34: { + // yFinal [packed=true] + input.readPackedDouble(yFinal); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + case 9: { + // xInitial [packed=false] + tag = input.readRepeatedDouble(xInitial, tag); + bitField0_ |= 0x00000001; + break; + } + case 17: { + // xFinal [packed=false] + tag = input.readRepeatedDouble(xFinal, tag); + bitField0_ |= 0x00000002; + break; + } + case 25: { + // yInitial [packed=false] + tag = input.readRepeatedDouble(yInitial, tag); + bitField0_ |= 0x00000004; + break; + } + case 33: { + // yFinal [packed=false] + tag = input.readRepeatedDouble(yFinal, tag); + bitField0_ |= 0x00000008; + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeRepeatedDouble(FieldNames.xInitial, xInitial); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRepeatedDouble(FieldNames.xFinal, xFinal); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRepeatedDouble(FieldNames.yInitial, yInitial); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRepeatedDouble(FieldNames.yFinal, yFinal); + } + output.endObject(); + } + + @Override + public ProtobufCubicHermiteSpline mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case -1998129236: + case -2134571395: { + if (input.isAtField(FieldNames.xInitial)) { + if (!input.trySkipNullValue()) { + input.readRepeatedDouble(xInitial); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case -791585826: + case 1943464687: { + if (input.isAtField(FieldNames.xFinal)) { + if (!input.trySkipNullValue()) { + input.readRepeatedDouble(xFinal); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case -255318901: + case 352941438: { + if (input.isAtField(FieldNames.yInitial)) { + if (!input.trySkipNullValue()) { + input.readRepeatedDouble(yInitial); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case -762956675: + case -1463998928: { + if (input.isAtField(FieldNames.yFinal)) { + if (!input.trySkipNullValue()) { + input.readRepeatedDouble(yFinal); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufCubicHermiteSpline clone() { + return new ProtobufCubicHermiteSpline().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufCubicHermiteSpline parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufCubicHermiteSpline(), data).checkInitialized(); + } + + public static ProtobufCubicHermiteSpline parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufCubicHermiteSpline(), input).checkInitialized(); + } + + public static ProtobufCubicHermiteSpline parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufCubicHermiteSpline(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufCubicHermiteSpline messages + */ + public static MessageFactory getFactory() { + return ProtobufCubicHermiteSplineFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Spline.wpi_proto_ProtobufCubicHermiteSpline_descriptor; + } + + private enum ProtobufCubicHermiteSplineFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufCubicHermiteSpline create() { + return ProtobufCubicHermiteSpline.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName xInitial = FieldName.forField("xInitial", "x_initial"); + + static final FieldName xFinal = FieldName.forField("xFinal", "x_final"); + + static final FieldName yInitial = FieldName.forField("yInitial", "y_initial"); + + static final FieldName yFinal = FieldName.forField("yFinal", "y_final"); + } + } + + /** + * Protobuf type {@code ProtobufQuinticHermiteSpline} + */ + public static final class ProtobufQuinticHermiteSpline extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * repeated double x_initial = 1; + */ + private final RepeatedDouble xInitial = RepeatedDouble.newEmptyInstance(); + + /** + * repeated double x_final = 2; + */ + private final RepeatedDouble xFinal = RepeatedDouble.newEmptyInstance(); + + /** + * repeated double y_initial = 3; + */ + private final RepeatedDouble yInitial = RepeatedDouble.newEmptyInstance(); + + /** + * repeated double y_final = 4; + */ + private final RepeatedDouble yFinal = RepeatedDouble.newEmptyInstance(); + + private ProtobufQuinticHermiteSpline() { + } + + /** + * @return a new empty instance of {@code ProtobufQuinticHermiteSpline} + */ + public static ProtobufQuinticHermiteSpline newInstance() { + return new ProtobufQuinticHermiteSpline(); + } + + /** + * repeated double x_initial = 1; + * @return whether the xInitial field is set + */ + public boolean hasXInitial() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * repeated double x_initial = 1; + * @return this + */ + public ProtobufQuinticHermiteSpline clearXInitial() { + bitField0_ &= ~0x00000001; + xInitial.clear(); + return this; + } + + /** + * repeated double x_initial = 1; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableXInitial()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedDouble getXInitial() { + return xInitial; + } + + /** + * repeated double x_initial = 1; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedDouble getMutableXInitial() { + bitField0_ |= 0x00000001; + return xInitial; + } + + /** + * repeated double x_initial = 1; + * @param value the xInitial to add + * @return this + */ + public ProtobufQuinticHermiteSpline addXInitial(final double value) { + bitField0_ |= 0x00000001; + xInitial.add(value); + return this; + } + + /** + * repeated double x_initial = 1; + * @param values the xInitial to add + * @return this + */ + public ProtobufQuinticHermiteSpline addAllXInitial(final double... values) { + bitField0_ |= 0x00000001; + xInitial.addAll(values); + return this; + } + + /** + * repeated double x_final = 2; + * @return whether the xFinal field is set + */ + public boolean hasXFinal() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * repeated double x_final = 2; + * @return this + */ + public ProtobufQuinticHermiteSpline clearXFinal() { + bitField0_ &= ~0x00000002; + xFinal.clear(); + return this; + } + + /** + * repeated double x_final = 2; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableXFinal()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedDouble getXFinal() { + return xFinal; + } + + /** + * repeated double x_final = 2; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedDouble getMutableXFinal() { + bitField0_ |= 0x00000002; + return xFinal; + } + + /** + * repeated double x_final = 2; + * @param value the xFinal to add + * @return this + */ + public ProtobufQuinticHermiteSpline addXFinal(final double value) { + bitField0_ |= 0x00000002; + xFinal.add(value); + return this; + } + + /** + * repeated double x_final = 2; + * @param values the xFinal to add + * @return this + */ + public ProtobufQuinticHermiteSpline addAllXFinal(final double... values) { + bitField0_ |= 0x00000002; + xFinal.addAll(values); + return this; + } + + /** + * repeated double y_initial = 3; + * @return whether the yInitial field is set + */ + public boolean hasYInitial() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * repeated double y_initial = 3; + * @return this + */ + public ProtobufQuinticHermiteSpline clearYInitial() { + bitField0_ &= ~0x00000004; + yInitial.clear(); + return this; + } + + /** + * repeated double y_initial = 3; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableYInitial()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedDouble getYInitial() { + return yInitial; + } + + /** + * repeated double y_initial = 3; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedDouble getMutableYInitial() { + bitField0_ |= 0x00000004; + return yInitial; + } + + /** + * repeated double y_initial = 3; + * @param value the yInitial to add + * @return this + */ + public ProtobufQuinticHermiteSpline addYInitial(final double value) { + bitField0_ |= 0x00000004; + yInitial.add(value); + return this; + } + + /** + * repeated double y_initial = 3; + * @param values the yInitial to add + * @return this + */ + public ProtobufQuinticHermiteSpline addAllYInitial(final double... values) { + bitField0_ |= 0x00000004; + yInitial.addAll(values); + return this; + } + + /** + * repeated double y_final = 4; + * @return whether the yFinal field is set + */ + public boolean hasYFinal() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * repeated double y_final = 4; + * @return this + */ + public ProtobufQuinticHermiteSpline clearYFinal() { + bitField0_ &= ~0x00000008; + yFinal.clear(); + return this; + } + + /** + * repeated double y_final = 4; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableYFinal()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedDouble getYFinal() { + return yFinal; + } + + /** + * repeated double y_final = 4; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedDouble getMutableYFinal() { + bitField0_ |= 0x00000008; + return yFinal; + } + + /** + * repeated double y_final = 4; + * @param value the yFinal to add + * @return this + */ + public ProtobufQuinticHermiteSpline addYFinal(final double value) { + bitField0_ |= 0x00000008; + yFinal.add(value); + return this; + } + + /** + * repeated double y_final = 4; + * @param values the yFinal to add + * @return this + */ + public ProtobufQuinticHermiteSpline addAllYFinal(final double... values) { + bitField0_ |= 0x00000008; + yFinal.addAll(values); + return this; + } + + @Override + public ProtobufQuinticHermiteSpline copyFrom(final ProtobufQuinticHermiteSpline other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + xInitial.copyFrom(other.xInitial); + xFinal.copyFrom(other.xFinal); + yInitial.copyFrom(other.yInitial); + yFinal.copyFrom(other.yFinal); + } + return this; + } + + @Override + public ProtobufQuinticHermiteSpline mergeFrom(final ProtobufQuinticHermiteSpline other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasXInitial()) { + getMutableXInitial().addAll(other.xInitial); + } + if (other.hasXFinal()) { + getMutableXFinal().addAll(other.xFinal); + } + if (other.hasYInitial()) { + getMutableYInitial().addAll(other.yInitial); + } + if (other.hasYFinal()) { + getMutableYFinal().addAll(other.yFinal); + } + return this; + } + + @Override + public ProtobufQuinticHermiteSpline clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + xInitial.clear(); + xFinal.clear(); + yInitial.clear(); + yFinal.clear(); + return this; + } + + @Override + public ProtobufQuinticHermiteSpline clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + xInitial.clear(); + xFinal.clear(); + yInitial.clear(); + yFinal.clear(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufQuinticHermiteSpline)) { + return false; + } + ProtobufQuinticHermiteSpline other = (ProtobufQuinticHermiteSpline) o; + return bitField0_ == other.bitField0_ + && (!hasXInitial() || xInitial.equals(other.xInitial)) + && (!hasXFinal() || xFinal.equals(other.xFinal)) + && (!hasYInitial() || yInitial.equals(other.yInitial)) + && (!hasYFinal() || yFinal.equals(other.yFinal)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + for (int i = 0; i < xInitial.length(); i++) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(xInitial.array()[i]); + } + } + if ((bitField0_ & 0x00000002) != 0) { + for (int i = 0; i < xFinal.length(); i++) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(xFinal.array()[i]); + } + } + if ((bitField0_ & 0x00000004) != 0) { + for (int i = 0; i < yInitial.length(); i++) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(yInitial.array()[i]); + } + } + if ((bitField0_ & 0x00000008) != 0) { + for (int i = 0; i < yFinal.length(); i++) { + output.writeRawByte((byte) 33); + output.writeDoubleNoTag(yFinal.array()[i]); + } + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += (1 + 8) * xInitial.length(); + } + if ((bitField0_ & 0x00000002) != 0) { + size += (1 + 8) * xFinal.length(); + } + if ((bitField0_ & 0x00000004) != 0) { + size += (1 + 8) * yInitial.length(); + } + if ((bitField0_ & 0x00000008) != 0) { + size += (1 + 8) * yFinal.length(); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufQuinticHermiteSpline mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 10: { + // xInitial [packed=true] + input.readPackedDouble(xInitial); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 18) { + break; + } + } + case 18: { + // xFinal [packed=true] + input.readPackedDouble(xFinal); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 26) { + break; + } + } + case 26: { + // yInitial [packed=true] + input.readPackedDouble(yInitial); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 34) { + break; + } + } + case 34: { + // yFinal [packed=true] + input.readPackedDouble(yFinal); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + case 9: { + // xInitial [packed=false] + tag = input.readRepeatedDouble(xInitial, tag); + bitField0_ |= 0x00000001; + break; + } + case 17: { + // xFinal [packed=false] + tag = input.readRepeatedDouble(xFinal, tag); + bitField0_ |= 0x00000002; + break; + } + case 25: { + // yInitial [packed=false] + tag = input.readRepeatedDouble(yInitial, tag); + bitField0_ |= 0x00000004; + break; + } + case 33: { + // yFinal [packed=false] + tag = input.readRepeatedDouble(yFinal, tag); + bitField0_ |= 0x00000008; + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeRepeatedDouble(FieldNames.xInitial, xInitial); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRepeatedDouble(FieldNames.xFinal, xFinal); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRepeatedDouble(FieldNames.yInitial, yInitial); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRepeatedDouble(FieldNames.yFinal, yFinal); + } + output.endObject(); + } + + @Override + public ProtobufQuinticHermiteSpline mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case -1998129236: + case -2134571395: { + if (input.isAtField(FieldNames.xInitial)) { + if (!input.trySkipNullValue()) { + input.readRepeatedDouble(xInitial); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case -791585826: + case 1943464687: { + if (input.isAtField(FieldNames.xFinal)) { + if (!input.trySkipNullValue()) { + input.readRepeatedDouble(xFinal); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case -255318901: + case 352941438: { + if (input.isAtField(FieldNames.yInitial)) { + if (!input.trySkipNullValue()) { + input.readRepeatedDouble(yInitial); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case -762956675: + case -1463998928: { + if (input.isAtField(FieldNames.yFinal)) { + if (!input.trySkipNullValue()) { + input.readRepeatedDouble(yFinal); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufQuinticHermiteSpline clone() { + return new ProtobufQuinticHermiteSpline().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufQuinticHermiteSpline parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufQuinticHermiteSpline(), data).checkInitialized(); + } + + public static ProtobufQuinticHermiteSpline parseFrom(final ProtoSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufQuinticHermiteSpline(), input).checkInitialized(); + } + + public static ProtobufQuinticHermiteSpline parseFrom(final JsonSource input) throws + IOException { + return ProtoMessage.mergeFrom(new ProtobufQuinticHermiteSpline(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufQuinticHermiteSpline messages + */ + public static MessageFactory getFactory() { + return ProtobufQuinticHermiteSplineFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Spline.wpi_proto_ProtobufQuinticHermiteSpline_descriptor; + } + + private enum ProtobufQuinticHermiteSplineFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufQuinticHermiteSpline create() { + return ProtobufQuinticHermiteSpline.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName xInitial = FieldName.forField("xInitial", "x_initial"); + + static final FieldName xFinal = FieldName.forField("xFinal", "x_final"); + + static final FieldName yInitial = FieldName.forField("yInitial", "y_initial"); + + static final FieldName yFinal = FieldName.forField("yFinal", "y_final"); + } + } +} diff --git a/wpimath/src/generated/main/java/edu/wpi/first/math/proto/System.java b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/System.java new file mode 100644 index 00000000000..09ea3b529d9 --- /dev/null +++ b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/System.java @@ -0,0 +1,866 @@ +// 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. +// Code generated by protocol buffer compiler. Do not edit! +package edu.wpi.first.math.proto; + +import java.io.IOException; +import us.hebi.quickbuf.Descriptors; +import us.hebi.quickbuf.FieldName; +import us.hebi.quickbuf.InvalidProtocolBufferException; +import us.hebi.quickbuf.JsonSink; +import us.hebi.quickbuf.JsonSource; +import us.hebi.quickbuf.MessageFactory; +import us.hebi.quickbuf.ProtoMessage; +import us.hebi.quickbuf.ProtoSink; +import us.hebi.quickbuf.ProtoSource; +import us.hebi.quickbuf.ProtoUtil; +import us.hebi.quickbuf.RepeatedByte; + +public final class System { + private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(832, + "CgxzeXN0ZW0ucHJvdG8SCXdwaS5wcm90bxoNd3BpbWF0aC5wcm90byKZAgoUUHJvdG9idWZMaW5lYXJT" + + "eXN0ZW0SHQoKbnVtX3N0YXRlcxgBIAEoDVIJbnVtU3RhdGVzEh0KCm51bV9pbnB1dHMYAiABKA1SCW51" + + "bUlucHV0cxIfCgtudW1fb3V0cHV0cxgDIAEoDVIKbnVtT3V0cHV0cxInCgFhGAQgASgLMhkud3BpLnBy" + + "b3RvLlByb3RvYnVmTWF0cml4UgFhEicKAWIYBSABKAsyGS53cGkucHJvdG8uUHJvdG9idWZNYXRyaXhS" + + "AWISJwoBYxgGIAEoCzIZLndwaS5wcm90by5Qcm90b2J1Zk1hdHJpeFIBYxInCgFkGAcgASgLMhkud3Bp" + + "LnByb3RvLlByb3RvYnVmTWF0cml4UgFkQhoKGGVkdS53cGkuZmlyc3QubWF0aC5wcm90b0rVAwoGEgQA" + + "ABABCggKAQwSAwAAEgoICgECEgMCABIKCQoCAwASAwQAFwoICgEIEgMGADEKCQoCCAESAwYAMQoKCgIE" + + "ABIECAAQAQoKCgMEAAESAwgIHAoLCgQEAAIAEgMJAhgKDAoFBAACAAUSAwkCCAoMCgUEAAIAARIDCQkT" + + "CgwKBQQAAgADEgMJFhcKCwoEBAACARIDCgIYCgwKBQQAAgEFEgMKAggKDAoFBAACAQESAwoJEwoMCgUE" + + "AAIBAxIDChYXCgsKBAQAAgISAwsCGQoMCgUEAAICBRIDCwIICgwKBQQAAgIBEgMLCRQKDAoFBAACAgMS" + + "AwsXGAoLCgQEAAIDEgMMAhcKDAoFBAACAwYSAwwCEAoMCgUEAAIDARIDDBESCgwKBQQAAgMDEgMMFRYK" + + "CwoEBAACBBIDDQIXCgwKBQQAAgQGEgMNAhAKDAoFBAACBAESAw0REgoMCgUEAAIEAxIDDRUWCgsKBAQA" + + "AgUSAw4CFwoMCgUEAAIFBhIDDgIQCgwKBQQAAgUBEgMOERIKDAoFBAACBQMSAw4VFgoLCgQEAAIGEgMP" + + "AhcKDAoFBAACBgYSAw8CEAoMCgUEAAIGARIDDxESCgwKBQQAAgYDEgMPFRZiBnByb3RvMw=="); + + static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("system.proto", "wpi.proto", descriptorData, Wpimath.getDescriptor()); + + static final Descriptors.Descriptor wpi_proto_ProtobufLinearSystem_descriptor = descriptor.internalContainedType(43, 281, "ProtobufLinearSystem", "wpi.proto.ProtobufLinearSystem"); + + /** + * @return this proto file's descriptor. + */ + public static Descriptors.FileDescriptor getDescriptor() { + return descriptor; + } + + /** + * Protobuf type {@code ProtobufLinearSystem} + */ + public static final class ProtobufLinearSystem extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional uint32 num_states = 1; + */ + private int numStates; + + /** + * optional uint32 num_inputs = 2; + */ + private int numInputs; + + /** + * optional uint32 num_outputs = 3; + */ + private int numOutputs; + + /** + * optional .wpi.proto.ProtobufMatrix a = 4; + */ + private final Wpimath.ProtobufMatrix a = Wpimath.ProtobufMatrix.newInstance(); + + /** + * optional .wpi.proto.ProtobufMatrix b = 5; + */ + private final Wpimath.ProtobufMatrix b = Wpimath.ProtobufMatrix.newInstance(); + + /** + * optional .wpi.proto.ProtobufMatrix c = 6; + */ + private final Wpimath.ProtobufMatrix c = Wpimath.ProtobufMatrix.newInstance(); + + /** + * optional .wpi.proto.ProtobufMatrix d = 7; + */ + private final Wpimath.ProtobufMatrix d = Wpimath.ProtobufMatrix.newInstance(); + + private ProtobufLinearSystem() { + } + + /** + * @return a new empty instance of {@code ProtobufLinearSystem} + */ + public static ProtobufLinearSystem newInstance() { + return new ProtobufLinearSystem(); + } + + /** + * optional uint32 num_states = 1; + * @return whether the numStates field is set + */ + public boolean hasNumStates() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional uint32 num_states = 1; + * @return this + */ + public ProtobufLinearSystem clearNumStates() { + bitField0_ &= ~0x00000001; + numStates = 0; + return this; + } + + /** + * optional uint32 num_states = 1; + * @return the numStates + */ + public int getNumStates() { + return numStates; + } + + /** + * optional uint32 num_states = 1; + * @param value the numStates to set + * @return this + */ + public ProtobufLinearSystem setNumStates(final int value) { + bitField0_ |= 0x00000001; + numStates = value; + return this; + } + + /** + * optional uint32 num_inputs = 2; + * @return whether the numInputs field is set + */ + public boolean hasNumInputs() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional uint32 num_inputs = 2; + * @return this + */ + public ProtobufLinearSystem clearNumInputs() { + bitField0_ &= ~0x00000002; + numInputs = 0; + return this; + } + + /** + * optional uint32 num_inputs = 2; + * @return the numInputs + */ + public int getNumInputs() { + return numInputs; + } + + /** + * optional uint32 num_inputs = 2; + * @param value the numInputs to set + * @return this + */ + public ProtobufLinearSystem setNumInputs(final int value) { + bitField0_ |= 0x00000002; + numInputs = value; + return this; + } + + /** + * optional uint32 num_outputs = 3; + * @return whether the numOutputs field is set + */ + public boolean hasNumOutputs() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional uint32 num_outputs = 3; + * @return this + */ + public ProtobufLinearSystem clearNumOutputs() { + bitField0_ &= ~0x00000004; + numOutputs = 0; + return this; + } + + /** + * optional uint32 num_outputs = 3; + * @return the numOutputs + */ + public int getNumOutputs() { + return numOutputs; + } + + /** + * optional uint32 num_outputs = 3; + * @param value the numOutputs to set + * @return this + */ + public ProtobufLinearSystem setNumOutputs(final int value) { + bitField0_ |= 0x00000004; + numOutputs = value; + return this; + } + + /** + * optional .wpi.proto.ProtobufMatrix a = 4; + * @return whether the a field is set + */ + public boolean hasA() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * optional .wpi.proto.ProtobufMatrix a = 4; + * @return this + */ + public ProtobufLinearSystem clearA() { + bitField0_ &= ~0x00000008; + a.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufMatrix a = 4; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableA()} if you want to modify it. + * + * @return internal storage object for reading + */ + public Wpimath.ProtobufMatrix getA() { + return a; + } + + /** + * optional .wpi.proto.ProtobufMatrix a = 4; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public Wpimath.ProtobufMatrix getMutableA() { + bitField0_ |= 0x00000008; + return a; + } + + /** + * optional .wpi.proto.ProtobufMatrix a = 4; + * @param value the a to set + * @return this + */ + public ProtobufLinearSystem setA(final Wpimath.ProtobufMatrix value) { + bitField0_ |= 0x00000008; + a.copyFrom(value); + return this; + } + + /** + * optional .wpi.proto.ProtobufMatrix b = 5; + * @return whether the b field is set + */ + public boolean hasB() { + return (bitField0_ & 0x00000010) != 0; + } + + /** + * optional .wpi.proto.ProtobufMatrix b = 5; + * @return this + */ + public ProtobufLinearSystem clearB() { + bitField0_ &= ~0x00000010; + b.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufMatrix b = 5; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableB()} if you want to modify it. + * + * @return internal storage object for reading + */ + public Wpimath.ProtobufMatrix getB() { + return b; + } + + /** + * optional .wpi.proto.ProtobufMatrix b = 5; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public Wpimath.ProtobufMatrix getMutableB() { + bitField0_ |= 0x00000010; + return b; + } + + /** + * optional .wpi.proto.ProtobufMatrix b = 5; + * @param value the b to set + * @return this + */ + public ProtobufLinearSystem setB(final Wpimath.ProtobufMatrix value) { + bitField0_ |= 0x00000010; + b.copyFrom(value); + return this; + } + + /** + * optional .wpi.proto.ProtobufMatrix c = 6; + * @return whether the c field is set + */ + public boolean hasC() { + return (bitField0_ & 0x00000020) != 0; + } + + /** + * optional .wpi.proto.ProtobufMatrix c = 6; + * @return this + */ + public ProtobufLinearSystem clearC() { + bitField0_ &= ~0x00000020; + c.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufMatrix c = 6; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableC()} if you want to modify it. + * + * @return internal storage object for reading + */ + public Wpimath.ProtobufMatrix getC() { + return c; + } + + /** + * optional .wpi.proto.ProtobufMatrix c = 6; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public Wpimath.ProtobufMatrix getMutableC() { + bitField0_ |= 0x00000020; + return c; + } + + /** + * optional .wpi.proto.ProtobufMatrix c = 6; + * @param value the c to set + * @return this + */ + public ProtobufLinearSystem setC(final Wpimath.ProtobufMatrix value) { + bitField0_ |= 0x00000020; + c.copyFrom(value); + return this; + } + + /** + * optional .wpi.proto.ProtobufMatrix d = 7; + * @return whether the d field is set + */ + public boolean hasD() { + return (bitField0_ & 0x00000040) != 0; + } + + /** + * optional .wpi.proto.ProtobufMatrix d = 7; + * @return this + */ + public ProtobufLinearSystem clearD() { + bitField0_ &= ~0x00000040; + d.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufMatrix d = 7; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableD()} if you want to modify it. + * + * @return internal storage object for reading + */ + public Wpimath.ProtobufMatrix getD() { + return d; + } + + /** + * optional .wpi.proto.ProtobufMatrix d = 7; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public Wpimath.ProtobufMatrix getMutableD() { + bitField0_ |= 0x00000040; + return d; + } + + /** + * optional .wpi.proto.ProtobufMatrix d = 7; + * @param value the d to set + * @return this + */ + public ProtobufLinearSystem setD(final Wpimath.ProtobufMatrix value) { + bitField0_ |= 0x00000040; + d.copyFrom(value); + return this; + } + + @Override + public ProtobufLinearSystem copyFrom(final ProtobufLinearSystem other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + numStates = other.numStates; + numInputs = other.numInputs; + numOutputs = other.numOutputs; + a.copyFrom(other.a); + b.copyFrom(other.b); + c.copyFrom(other.c); + d.copyFrom(other.d); + } + return this; + } + + @Override + public ProtobufLinearSystem mergeFrom(final ProtobufLinearSystem other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasNumStates()) { + setNumStates(other.numStates); + } + if (other.hasNumInputs()) { + setNumInputs(other.numInputs); + } + if (other.hasNumOutputs()) { + setNumOutputs(other.numOutputs); + } + if (other.hasA()) { + getMutableA().mergeFrom(other.a); + } + if (other.hasB()) { + getMutableB().mergeFrom(other.b); + } + if (other.hasC()) { + getMutableC().mergeFrom(other.c); + } + if (other.hasD()) { + getMutableD().mergeFrom(other.d); + } + return this; + } + + @Override + public ProtobufLinearSystem clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + numStates = 0; + numInputs = 0; + numOutputs = 0; + a.clear(); + b.clear(); + c.clear(); + d.clear(); + return this; + } + + @Override + public ProtobufLinearSystem clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + a.clearQuick(); + b.clearQuick(); + c.clearQuick(); + d.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufLinearSystem)) { + return false; + } + ProtobufLinearSystem other = (ProtobufLinearSystem) o; + return bitField0_ == other.bitField0_ + && (!hasNumStates() || numStates == other.numStates) + && (!hasNumInputs() || numInputs == other.numInputs) + && (!hasNumOutputs() || numOutputs == other.numOutputs) + && (!hasA() || a.equals(other.a)) + && (!hasB() || b.equals(other.b)) + && (!hasC() || c.equals(other.c)) + && (!hasD() || d.equals(other.d)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 8); + output.writeUInt32NoTag(numStates); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 16); + output.writeUInt32NoTag(numInputs); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 24); + output.writeUInt32NoTag(numOutputs); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRawByte((byte) 34); + output.writeMessageNoTag(a); + } + if ((bitField0_ & 0x00000010) != 0) { + output.writeRawByte((byte) 42); + output.writeMessageNoTag(b); + } + if ((bitField0_ & 0x00000020) != 0) { + output.writeRawByte((byte) 50); + output.writeMessageNoTag(c); + } + if ((bitField0_ & 0x00000040) != 0) { + output.writeRawByte((byte) 58); + output.writeMessageNoTag(d); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 1 + ProtoSink.computeUInt32SizeNoTag(numStates); + } + if ((bitField0_ & 0x00000002) != 0) { + size += 1 + ProtoSink.computeUInt32SizeNoTag(numInputs); + } + if ((bitField0_ & 0x00000004) != 0) { + size += 1 + ProtoSink.computeUInt32SizeNoTag(numOutputs); + } + if ((bitField0_ & 0x00000008) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(a); + } + if ((bitField0_ & 0x00000010) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(b); + } + if ((bitField0_ & 0x00000020) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(c); + } + if ((bitField0_ & 0x00000040) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(d); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufLinearSystem mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 8: { + // numStates + numStates = input.readUInt32(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 16) { + break; + } + } + case 16: { + // numInputs + numInputs = input.readUInt32(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 24) { + break; + } + } + case 24: { + // numOutputs + numOutputs = input.readUInt32(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 34) { + break; + } + } + case 34: { + // a + input.readMessage(a); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 42) { + break; + } + } + case 42: { + // b + input.readMessage(b); + bitField0_ |= 0x00000010; + tag = input.readTag(); + if (tag != 50) { + break; + } + } + case 50: { + // c + input.readMessage(c); + bitField0_ |= 0x00000020; + tag = input.readTag(); + if (tag != 58) { + break; + } + } + case 58: { + // d + input.readMessage(d); + bitField0_ |= 0x00000040; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeUInt32(FieldNames.numStates, numStates); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeUInt32(FieldNames.numInputs, numInputs); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeUInt32(FieldNames.numOutputs, numOutputs); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeMessage(FieldNames.a, a); + } + if ((bitField0_ & 0x00000010) != 0) { + output.writeMessage(FieldNames.b, b); + } + if ((bitField0_ & 0x00000020) != 0) { + output.writeMessage(FieldNames.c, c); + } + if ((bitField0_ & 0x00000040) != 0) { + output.writeMessage(FieldNames.d, d); + } + output.endObject(); + } + + @Override + public ProtobufLinearSystem mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 1233856808: + case 1643330779: { + if (input.isAtField(FieldNames.numStates)) { + if (!input.trySkipNullValue()) { + numStates = input.readUInt32(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 942472463: + case 1351946434: { + if (input.isAtField(FieldNames.numInputs)) { + if (!input.trySkipNullValue()) { + numInputs = input.readUInt32(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case 385880364: + case 194671577: { + if (input.isAtField(FieldNames.numOutputs)) { + if (!input.trySkipNullValue()) { + numOutputs = input.readUInt32(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case 97: { + if (input.isAtField(FieldNames.a)) { + if (!input.trySkipNullValue()) { + input.readMessage(a); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + case 98: { + if (input.isAtField(FieldNames.b)) { + if (!input.trySkipNullValue()) { + input.readMessage(b); + bitField0_ |= 0x00000010; + } + } else { + input.skipUnknownField(); + } + break; + } + case 99: { + if (input.isAtField(FieldNames.c)) { + if (!input.trySkipNullValue()) { + input.readMessage(c); + bitField0_ |= 0x00000020; + } + } else { + input.skipUnknownField(); + } + break; + } + case 100: { + if (input.isAtField(FieldNames.d)) { + if (!input.trySkipNullValue()) { + input.readMessage(d); + bitField0_ |= 0x00000040; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufLinearSystem clone() { + return new ProtobufLinearSystem().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufLinearSystem parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufLinearSystem(), data).checkInitialized(); + } + + public static ProtobufLinearSystem parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufLinearSystem(), input).checkInitialized(); + } + + public static ProtobufLinearSystem parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufLinearSystem(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufLinearSystem messages + */ + public static MessageFactory getFactory() { + return ProtobufLinearSystemFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return System.wpi_proto_ProtobufLinearSystem_descriptor; + } + + private enum ProtobufLinearSystemFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufLinearSystem create() { + return ProtobufLinearSystem.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName numStates = FieldName.forField("numStates", "num_states"); + + static final FieldName numInputs = FieldName.forField("numInputs", "num_inputs"); + + static final FieldName numOutputs = FieldName.forField("numOutputs", "num_outputs"); + + static final FieldName a = FieldName.forField("a"); + + static final FieldName b = FieldName.forField("b"); + + static final FieldName c = FieldName.forField("c"); + + static final FieldName d = FieldName.forField("d"); + } + } +} diff --git a/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Trajectory.java b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Trajectory.java new file mode 100644 index 00000000000..3ec96f82760 --- /dev/null +++ b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Trajectory.java @@ -0,0 +1,928 @@ +// 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. +// Code generated by protocol buffer compiler. Do not edit! +package edu.wpi.first.math.proto; + +import java.io.IOException; +import us.hebi.quickbuf.Descriptors; +import us.hebi.quickbuf.FieldName; +import us.hebi.quickbuf.InvalidProtocolBufferException; +import us.hebi.quickbuf.JsonSink; +import us.hebi.quickbuf.JsonSource; +import us.hebi.quickbuf.MessageFactory; +import us.hebi.quickbuf.ProtoMessage; +import us.hebi.quickbuf.ProtoSink; +import us.hebi.quickbuf.ProtoSource; +import us.hebi.quickbuf.ProtoUtil; +import us.hebi.quickbuf.RepeatedByte; +import us.hebi.quickbuf.RepeatedMessage; + +public final class Trajectory { + private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(809, + "ChB0cmFqZWN0b3J5LnByb3RvEgl3cGkucHJvdG8aEGdlb21ldHJ5MmQucHJvdG8iugEKF1Byb3RvYnVm" + + "VHJhamVjdG9yeVN0YXRlEhIKBHRpbWUYASABKAFSBHRpbWUSGgoIdmVsb2NpdHkYAiABKAFSCHZlbG9j" + + "aXR5EiIKDGFjY2VsZXJhdGlvbhgDIAEoAVIMYWNjZWxlcmF0aW9uEi0KBHBvc2UYBCABKAsyGS53cGku" + + "cHJvdG8uUHJvdG9idWZQb3NlMmRSBHBvc2USHAoJY3VydmF0dXJlGAUgASgBUgljdXJ2YXR1cmUiUAoS" + + "UHJvdG9idWZUcmFqZWN0b3J5EjoKBnN0YXRlcxgCIAMoCzIiLndwaS5wcm90by5Qcm90b2J1ZlRyYWpl" + + "Y3RvcnlTdGF0ZVIGc3RhdGVzQhoKGGVkdS53cGkuZmlyc3QubWF0aC5wcm90b0rEAwoGEgQAABIBCggK" + + "AQwSAwAAEgoICgECEgMCABIKCQoCAwASAwQAGgoICgEIEgMGADEKCQoCCAESAwYAMQoKCgIEABIECAAO" + + "AQoKCgMEAAESAwgIHwoLCgQEAAIAEgMJAhIKDAoFBAACAAUSAwkCCAoMCgUEAAIAARIDCQkNCgwKBQQA" + + "AgADEgMJEBEKCwoEBAACARIDCgIWCgwKBQQAAgEFEgMKAggKDAoFBAACAQESAwoJEQoMCgUEAAIBAxID" + + "ChQVCgsKBAQAAgISAwsCGgoMCgUEAAICBRIDCwIICgwKBQQAAgIBEgMLCRUKDAoFBAACAgMSAwsYGQoL" + + "CgQEAAIDEgMMAhoKDAoFBAACAwYSAwwCEAoMCgUEAAIDARIDDBEVCgwKBQQAAgMDEgMMGBkKCwoEBAAC" + + "BBIDDQIXCgwKBQQAAgQFEgMNAggKDAoFBAACBAESAw0JEgoMCgUEAAIEAxIDDRUWCgoKAgQBEgQQABIB" + + "CgoKAwQBARIDEAgaCgsKBAQBAgASAxECLgoMCgUEAQIABBIDEQIKCgwKBQQBAgAGEgMRCyIKDAoFBAEC" + + "AAESAxEjKQoMCgUEAQIAAxIDESwtYgZwcm90bzM="); + + static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("trajectory.proto", "wpi.proto", descriptorData, Geometry2D.getDescriptor()); + + static final Descriptors.Descriptor wpi_proto_ProtobufTrajectoryState_descriptor = descriptor.internalContainedType(50, 186, "ProtobufTrajectoryState", "wpi.proto.ProtobufTrajectoryState"); + + static final Descriptors.Descriptor wpi_proto_ProtobufTrajectory_descriptor = descriptor.internalContainedType(238, 80, "ProtobufTrajectory", "wpi.proto.ProtobufTrajectory"); + + /** + * @return this proto file's descriptor. + */ + public static Descriptors.FileDescriptor getDescriptor() { + return descriptor; + } + + /** + * Protobuf type {@code ProtobufTrajectoryState} + */ + public static final class ProtobufTrajectoryState extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional double time = 1; + */ + private double time; + + /** + * optional double velocity = 2; + */ + private double velocity; + + /** + * optional double acceleration = 3; + */ + private double acceleration; + + /** + * optional double curvature = 5; + */ + private double curvature; + + /** + * optional .wpi.proto.ProtobufPose2d pose = 4; + */ + private final Geometry2D.ProtobufPose2d pose = Geometry2D.ProtobufPose2d.newInstance(); + + private ProtobufTrajectoryState() { + } + + /** + * @return a new empty instance of {@code ProtobufTrajectoryState} + */ + public static ProtobufTrajectoryState newInstance() { + return new ProtobufTrajectoryState(); + } + + /** + * optional double time = 1; + * @return whether the time field is set + */ + public boolean hasTime() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional double time = 1; + * @return this + */ + public ProtobufTrajectoryState clearTime() { + bitField0_ &= ~0x00000001; + time = 0D; + return this; + } + + /** + * optional double time = 1; + * @return the time + */ + public double getTime() { + return time; + } + + /** + * optional double time = 1; + * @param value the time to set + * @return this + */ + public ProtobufTrajectoryState setTime(final double value) { + bitField0_ |= 0x00000001; + time = value; + return this; + } + + /** + * optional double velocity = 2; + * @return whether the velocity field is set + */ + public boolean hasVelocity() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional double velocity = 2; + * @return this + */ + public ProtobufTrajectoryState clearVelocity() { + bitField0_ &= ~0x00000002; + velocity = 0D; + return this; + } + + /** + * optional double velocity = 2; + * @return the velocity + */ + public double getVelocity() { + return velocity; + } + + /** + * optional double velocity = 2; + * @param value the velocity to set + * @return this + */ + public ProtobufTrajectoryState setVelocity(final double value) { + bitField0_ |= 0x00000002; + velocity = value; + return this; + } + + /** + * optional double acceleration = 3; + * @return whether the acceleration field is set + */ + public boolean hasAcceleration() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * optional double acceleration = 3; + * @return this + */ + public ProtobufTrajectoryState clearAcceleration() { + bitField0_ &= ~0x00000004; + acceleration = 0D; + return this; + } + + /** + * optional double acceleration = 3; + * @return the acceleration + */ + public double getAcceleration() { + return acceleration; + } + + /** + * optional double acceleration = 3; + * @param value the acceleration to set + * @return this + */ + public ProtobufTrajectoryState setAcceleration(final double value) { + bitField0_ |= 0x00000004; + acceleration = value; + return this; + } + + /** + * optional double curvature = 5; + * @return whether the curvature field is set + */ + public boolean hasCurvature() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * optional double curvature = 5; + * @return this + */ + public ProtobufTrajectoryState clearCurvature() { + bitField0_ &= ~0x00000008; + curvature = 0D; + return this; + } + + /** + * optional double curvature = 5; + * @return the curvature + */ + public double getCurvature() { + return curvature; + } + + /** + * optional double curvature = 5; + * @param value the curvature to set + * @return this + */ + public ProtobufTrajectoryState setCurvature(final double value) { + bitField0_ |= 0x00000008; + curvature = value; + return this; + } + + /** + * optional .wpi.proto.ProtobufPose2d pose = 4; + * @return whether the pose field is set + */ + public boolean hasPose() { + return (bitField0_ & 0x00000010) != 0; + } + + /** + * optional .wpi.proto.ProtobufPose2d pose = 4; + * @return this + */ + public ProtobufTrajectoryState clearPose() { + bitField0_ &= ~0x00000010; + pose.clear(); + return this; + } + + /** + * optional .wpi.proto.ProtobufPose2d pose = 4; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutablePose()} if you want to modify it. + * + * @return internal storage object for reading + */ + public Geometry2D.ProtobufPose2d getPose() { + return pose; + } + + /** + * optional .wpi.proto.ProtobufPose2d pose = 4; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public Geometry2D.ProtobufPose2d getMutablePose() { + bitField0_ |= 0x00000010; + return pose; + } + + /** + * optional .wpi.proto.ProtobufPose2d pose = 4; + * @param value the pose to set + * @return this + */ + public ProtobufTrajectoryState setPose(final Geometry2D.ProtobufPose2d value) { + bitField0_ |= 0x00000010; + pose.copyFrom(value); + return this; + } + + @Override + public ProtobufTrajectoryState copyFrom(final ProtobufTrajectoryState other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + time = other.time; + velocity = other.velocity; + acceleration = other.acceleration; + curvature = other.curvature; + pose.copyFrom(other.pose); + } + return this; + } + + @Override + public ProtobufTrajectoryState mergeFrom(final ProtobufTrajectoryState other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasTime()) { + setTime(other.time); + } + if (other.hasVelocity()) { + setVelocity(other.velocity); + } + if (other.hasAcceleration()) { + setAcceleration(other.acceleration); + } + if (other.hasCurvature()) { + setCurvature(other.curvature); + } + if (other.hasPose()) { + getMutablePose().mergeFrom(other.pose); + } + return this; + } + + @Override + public ProtobufTrajectoryState clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + time = 0D; + velocity = 0D; + acceleration = 0D; + curvature = 0D; + pose.clear(); + return this; + } + + @Override + public ProtobufTrajectoryState clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + pose.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufTrajectoryState)) { + return false; + } + ProtobufTrajectoryState other = (ProtobufTrajectoryState) o; + return bitField0_ == other.bitField0_ + && (!hasTime() || ProtoUtil.isEqual(time, other.time)) + && (!hasVelocity() || ProtoUtil.isEqual(velocity, other.velocity)) + && (!hasAcceleration() || ProtoUtil.isEqual(acceleration, other.acceleration)) + && (!hasCurvature() || ProtoUtil.isEqual(curvature, other.curvature)) + && (!hasPose() || pose.equals(other.pose)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(time); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 17); + output.writeDoubleNoTag(velocity); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(acceleration); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRawByte((byte) 41); + output.writeDoubleNoTag(curvature); + } + if ((bitField0_ & 0x00000010) != 0) { + output.writeRawByte((byte) 34); + output.writeMessageNoTag(pose); + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000002) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000004) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000008) != 0) { + size += 9; + } + if ((bitField0_ & 0x00000010) != 0) { + size += 1 + ProtoSink.computeMessageSizeNoTag(pose); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufTrajectoryState mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 9: { + // time + time = input.readDouble(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 17) { + break; + } + } + case 17: { + // velocity + velocity = input.readDouble(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 25) { + break; + } + } + case 25: { + // acceleration + acceleration = input.readDouble(); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 41) { + break; + } + } + case 41: { + // curvature + curvature = input.readDouble(); + bitField0_ |= 0x00000008; + tag = input.readTag(); + if (tag != 34) { + break; + } + } + case 34: { + // pose + input.readMessage(pose); + bitField0_ |= 0x00000010; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeDouble(FieldNames.time, time); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeDouble(FieldNames.velocity, velocity); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeDouble(FieldNames.acceleration, acceleration); + } + if ((bitField0_ & 0x00000008) != 0) { + output.writeDouble(FieldNames.curvature, curvature); + } + if ((bitField0_ & 0x00000010) != 0) { + output.writeMessage(FieldNames.pose, pose); + } + output.endObject(); + } + + @Override + public ProtobufTrajectoryState mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 3560141: { + if (input.isAtField(FieldNames.time)) { + if (!input.trySkipNullValue()) { + time = input.readDouble(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case 2134260957: { + if (input.isAtField(FieldNames.velocity)) { + if (!input.trySkipNullValue()) { + velocity = input.readDouble(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case -267299712: { + if (input.isAtField(FieldNames.acceleration)) { + if (!input.trySkipNullValue()) { + acceleration = input.readDouble(); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + case 768611295: { + if (input.isAtField(FieldNames.curvature)) { + if (!input.trySkipNullValue()) { + curvature = input.readDouble(); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3446929: { + if (input.isAtField(FieldNames.pose)) { + if (!input.trySkipNullValue()) { + input.readMessage(pose); + bitField0_ |= 0x00000010; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufTrajectoryState clone() { + return new ProtobufTrajectoryState().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufTrajectoryState parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufTrajectoryState(), data).checkInitialized(); + } + + public static ProtobufTrajectoryState parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTrajectoryState(), input).checkInitialized(); + } + + public static ProtobufTrajectoryState parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTrajectoryState(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufTrajectoryState messages + */ + public static MessageFactory getFactory() { + return ProtobufTrajectoryStateFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Trajectory.wpi_proto_ProtobufTrajectoryState_descriptor; + } + + private enum ProtobufTrajectoryStateFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufTrajectoryState create() { + return ProtobufTrajectoryState.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName time = FieldName.forField("time"); + + static final FieldName velocity = FieldName.forField("velocity"); + + static final FieldName acceleration = FieldName.forField("acceleration"); + + static final FieldName curvature = FieldName.forField("curvature"); + + static final FieldName pose = FieldName.forField("pose"); + } + } + + /** + * Protobuf type {@code ProtobufTrajectory} + */ + public static final class ProtobufTrajectory extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * repeated .wpi.proto.ProtobufTrajectoryState states = 2; + */ + private final RepeatedMessage states = RepeatedMessage.newEmptyInstance(ProtobufTrajectoryState.getFactory()); + + private ProtobufTrajectory() { + } + + /** + * @return a new empty instance of {@code ProtobufTrajectory} + */ + public static ProtobufTrajectory newInstance() { + return new ProtobufTrajectory(); + } + + /** + * repeated .wpi.proto.ProtobufTrajectoryState states = 2; + * @return whether the states field is set + */ + public boolean hasStates() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * repeated .wpi.proto.ProtobufTrajectoryState states = 2; + * @return this + */ + public ProtobufTrajectory clearStates() { + bitField0_ &= ~0x00000001; + states.clear(); + return this; + } + + /** + * repeated .wpi.proto.ProtobufTrajectoryState states = 2; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableStates()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedMessage getStates() { + return states; + } + + /** + * repeated .wpi.proto.ProtobufTrajectoryState states = 2; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedMessage getMutableStates() { + bitField0_ |= 0x00000001; + return states; + } + + /** + * repeated .wpi.proto.ProtobufTrajectoryState states = 2; + * @param value the states to add + * @return this + */ + public ProtobufTrajectory addStates(final ProtobufTrajectoryState value) { + bitField0_ |= 0x00000001; + states.add(value); + return this; + } + + /** + * repeated .wpi.proto.ProtobufTrajectoryState states = 2; + * @param values the states to add + * @return this + */ + public ProtobufTrajectory addAllStates(final ProtobufTrajectoryState... values) { + bitField0_ |= 0x00000001; + states.addAll(values); + return this; + } + + @Override + public ProtobufTrajectory copyFrom(final ProtobufTrajectory other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + states.copyFrom(other.states); + } + return this; + } + + @Override + public ProtobufTrajectory mergeFrom(final ProtobufTrajectory other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasStates()) { + getMutableStates().addAll(other.states); + } + return this; + } + + @Override + public ProtobufTrajectory clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + states.clear(); + return this; + } + + @Override + public ProtobufTrajectory clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + states.clearQuick(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufTrajectory)) { + return false; + } + ProtobufTrajectory other = (ProtobufTrajectory) o; + return bitField0_ == other.bitField0_ + && (!hasStates() || states.equals(other.states)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + for (int i = 0; i < states.length(); i++) { + output.writeRawByte((byte) 18); + output.writeMessageNoTag(states.get(i)); + } + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += (1 * states.length()) + ProtoSink.computeRepeatedMessageSizeNoTag(states); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufTrajectory mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 18: { + // states + tag = input.readRepeatedMessage(states, tag); + bitField0_ |= 0x00000001; + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeRepeatedMessage(FieldNames.states, states); + } + output.endObject(); + } + + @Override + public ProtobufTrajectory mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case -892482046: { + if (input.isAtField(FieldNames.states)) { + if (!input.trySkipNullValue()) { + input.readRepeatedMessage(states); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufTrajectory clone() { + return new ProtobufTrajectory().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufTrajectory parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufTrajectory(), data).checkInitialized(); + } + + public static ProtobufTrajectory parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTrajectory(), input).checkInitialized(); + } + + public static ProtobufTrajectory parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufTrajectory(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufTrajectory messages + */ + public static MessageFactory getFactory() { + return ProtobufTrajectoryFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Trajectory.wpi_proto_ProtobufTrajectory_descriptor; + } + + private enum ProtobufTrajectoryFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufTrajectory create() { + return ProtobufTrajectory.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName states = FieldName.forField("states"); + } + } +} diff --git a/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Wpimath.java b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Wpimath.java new file mode 100644 index 00000000000..ce964a2795c --- /dev/null +++ b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Wpimath.java @@ -0,0 +1,791 @@ +// 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. +// Code generated by protocol buffer compiler. Do not edit! +package edu.wpi.first.math.proto; + +import java.io.IOException; +import us.hebi.quickbuf.Descriptors; +import us.hebi.quickbuf.FieldName; +import us.hebi.quickbuf.InvalidProtocolBufferException; +import us.hebi.quickbuf.JsonSink; +import us.hebi.quickbuf.JsonSource; +import us.hebi.quickbuf.MessageFactory; +import us.hebi.quickbuf.ProtoMessage; +import us.hebi.quickbuf.ProtoSink; +import us.hebi.quickbuf.ProtoSource; +import us.hebi.quickbuf.ProtoUtil; +import us.hebi.quickbuf.RepeatedByte; +import us.hebi.quickbuf.RepeatedDouble; + +public final class Wpimath { + private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(540, + "Cg13cGltYXRoLnByb3RvEgl3cGkucHJvdG8iWgoOUHJvdG9idWZNYXRyaXgSGQoIbnVtX3Jvd3MYASAB" + + "KA1SB251bVJvd3MSGQoIbnVtX2NvbHMYAiABKA1SB251bUNvbHMSEgoEZGF0YRgDIAMoAVIEZGF0YSIk" + + "Cg5Qcm90b2J1ZlZlY3RvchISCgRyb3dzGAEgAygBUgRyb3dzQhoKGGVkdS53cGkuZmlyc3QubWF0aC5w" + + "cm90b0rZAgoGEgQAAA4BCggKAQwSAwAAEgoICgECEgMCABIKCAoBCBIDBAAxCgkKAggBEgMEADEKCgoC" + + "BAASBAYACgEKCgoDBAABEgMGCBYKCwoEBAACABIDBwIWCgwKBQQAAgAFEgMHAggKDAoFBAACAAESAwcJ" + + "EQoMCgUEAAIAAxIDBxQVCgsKBAQAAgESAwgCFgoMCgUEAAIBBRIDCAIICgwKBQQAAgEBEgMICREKDAoF" + + "BAACAQMSAwgUFQoLCgQEAAICEgMJAhsKDAoFBAACAgQSAwkCCgoMCgUEAAICBRIDCQsRCgwKBQQAAgIB" + + "EgMJEhYKDAoFBAACAgMSAwkZGgoKCgIEARIEDAAOAQoKCgMEAQESAwwIFgoLCgQEAQIAEgMNAhsKDAoF" + + "BAECAAQSAw0CCgoMCgUEAQIABRIDDQsRCgwKBQQBAgABEgMNEhYKDAoFBAECAAMSAw0ZGmIGcHJvdG8z"); + + static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("wpimath.proto", "wpi.proto", descriptorData); + + static final Descriptors.Descriptor wpi_proto_ProtobufMatrix_descriptor = descriptor.internalContainedType(28, 90, "ProtobufMatrix", "wpi.proto.ProtobufMatrix"); + + static final Descriptors.Descriptor wpi_proto_ProtobufVector_descriptor = descriptor.internalContainedType(120, 36, "ProtobufVector", "wpi.proto.ProtobufVector"); + + /** + * @return this proto file's descriptor. + */ + public static Descriptors.FileDescriptor getDescriptor() { + return descriptor; + } + + /** + * Protobuf type {@code ProtobufMatrix} + */ + public static final class ProtobufMatrix extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * optional uint32 num_rows = 1; + */ + private int numRows; + + /** + * optional uint32 num_cols = 2; + */ + private int numCols; + + /** + * repeated double data = 3; + */ + private final RepeatedDouble data = RepeatedDouble.newEmptyInstance(); + + private ProtobufMatrix() { + } + + /** + * @return a new empty instance of {@code ProtobufMatrix} + */ + public static ProtobufMatrix newInstance() { + return new ProtobufMatrix(); + } + + /** + * optional uint32 num_rows = 1; + * @return whether the numRows field is set + */ + public boolean hasNumRows() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * optional uint32 num_rows = 1; + * @return this + */ + public ProtobufMatrix clearNumRows() { + bitField0_ &= ~0x00000001; + numRows = 0; + return this; + } + + /** + * optional uint32 num_rows = 1; + * @return the numRows + */ + public int getNumRows() { + return numRows; + } + + /** + * optional uint32 num_rows = 1; + * @param value the numRows to set + * @return this + */ + public ProtobufMatrix setNumRows(final int value) { + bitField0_ |= 0x00000001; + numRows = value; + return this; + } + + /** + * optional uint32 num_cols = 2; + * @return whether the numCols field is set + */ + public boolean hasNumCols() { + return (bitField0_ & 0x00000002) != 0; + } + + /** + * optional uint32 num_cols = 2; + * @return this + */ + public ProtobufMatrix clearNumCols() { + bitField0_ &= ~0x00000002; + numCols = 0; + return this; + } + + /** + * optional uint32 num_cols = 2; + * @return the numCols + */ + public int getNumCols() { + return numCols; + } + + /** + * optional uint32 num_cols = 2; + * @param value the numCols to set + * @return this + */ + public ProtobufMatrix setNumCols(final int value) { + bitField0_ |= 0x00000002; + numCols = value; + return this; + } + + /** + * repeated double data = 3; + * @return whether the data field is set + */ + public boolean hasData() { + return (bitField0_ & 0x00000004) != 0; + } + + /** + * repeated double data = 3; + * @return this + */ + public ProtobufMatrix clearData() { + bitField0_ &= ~0x00000004; + data.clear(); + return this; + } + + /** + * repeated double data = 3; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableData()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedDouble getData() { + return data; + } + + /** + * repeated double data = 3; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedDouble getMutableData() { + bitField0_ |= 0x00000004; + return data; + } + + /** + * repeated double data = 3; + * @param value the data to add + * @return this + */ + public ProtobufMatrix addData(final double value) { + bitField0_ |= 0x00000004; + data.add(value); + return this; + } + + /** + * repeated double data = 3; + * @param values the data to add + * @return this + */ + public ProtobufMatrix addAllData(final double... values) { + bitField0_ |= 0x00000004; + data.addAll(values); + return this; + } + + @Override + public ProtobufMatrix copyFrom(final ProtobufMatrix other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + numRows = other.numRows; + numCols = other.numCols; + data.copyFrom(other.data); + } + return this; + } + + @Override + public ProtobufMatrix mergeFrom(final ProtobufMatrix other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasNumRows()) { + setNumRows(other.numRows); + } + if (other.hasNumCols()) { + setNumCols(other.numCols); + } + if (other.hasData()) { + getMutableData().addAll(other.data); + } + return this; + } + + @Override + public ProtobufMatrix clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + numRows = 0; + numCols = 0; + data.clear(); + return this; + } + + @Override + public ProtobufMatrix clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + data.clear(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufMatrix)) { + return false; + } + ProtobufMatrix other = (ProtobufMatrix) o; + return bitField0_ == other.bitField0_ + && (!hasNumRows() || numRows == other.numRows) + && (!hasNumCols() || numCols == other.numCols) + && (!hasData() || data.equals(other.data)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + output.writeRawByte((byte) 8); + output.writeUInt32NoTag(numRows); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeRawByte((byte) 16); + output.writeUInt32NoTag(numCols); + } + if ((bitField0_ & 0x00000004) != 0) { + for (int i = 0; i < data.length(); i++) { + output.writeRawByte((byte) 25); + output.writeDoubleNoTag(data.array()[i]); + } + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += 1 + ProtoSink.computeUInt32SizeNoTag(numRows); + } + if ((bitField0_ & 0x00000002) != 0) { + size += 1 + ProtoSink.computeUInt32SizeNoTag(numCols); + } + if ((bitField0_ & 0x00000004) != 0) { + size += (1 + 8) * data.length(); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufMatrix mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 8: { + // numRows + numRows = input.readUInt32(); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 16) { + break; + } + } + case 16: { + // numCols + numCols = input.readUInt32(); + bitField0_ |= 0x00000002; + tag = input.readTag(); + if (tag != 26) { + break; + } + } + case 26: { + // data [packed=true] + input.readPackedDouble(data); + bitField0_ |= 0x00000004; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + case 25: { + // data [packed=false] + tag = input.readRepeatedDouble(data, tag); + bitField0_ |= 0x00000004; + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeUInt32(FieldNames.numRows, numRows); + } + if ((bitField0_ & 0x00000002) != 0) { + output.writeUInt32(FieldNames.numCols, numCols); + } + if ((bitField0_ & 0x00000004) != 0) { + output.writeRepeatedDouble(FieldNames.data, data); + } + output.endObject(); + } + + @Override + public ProtobufMatrix mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case -2000982401: + case -1888824590: { + if (input.isAtField(FieldNames.numRows)) { + if (!input.trySkipNullValue()) { + numRows = input.readUInt32(); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + case -2001429607: + case -1889271796: { + if (input.isAtField(FieldNames.numCols)) { + if (!input.trySkipNullValue()) { + numCols = input.readUInt32(); + bitField0_ |= 0x00000002; + } + } else { + input.skipUnknownField(); + } + break; + } + case 3076010: { + if (input.isAtField(FieldNames.data)) { + if (!input.trySkipNullValue()) { + input.readRepeatedDouble(data); + bitField0_ |= 0x00000004; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufMatrix clone() { + return new ProtobufMatrix().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufMatrix parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufMatrix(), data).checkInitialized(); + } + + public static ProtobufMatrix parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufMatrix(), input).checkInitialized(); + } + + public static ProtobufMatrix parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufMatrix(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufMatrix messages + */ + public static MessageFactory getFactory() { + return ProtobufMatrixFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Wpimath.wpi_proto_ProtobufMatrix_descriptor; + } + + private enum ProtobufMatrixFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufMatrix create() { + return ProtobufMatrix.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName numRows = FieldName.forField("numRows", "num_rows"); + + static final FieldName numCols = FieldName.forField("numCols", "num_cols"); + + static final FieldName data = FieldName.forField("data"); + } + } + + /** + * Protobuf type {@code ProtobufVector} + */ + public static final class ProtobufVector extends ProtoMessage implements Cloneable { + private static final long serialVersionUID = 0L; + + /** + * repeated double rows = 1; + */ + private final RepeatedDouble rows = RepeatedDouble.newEmptyInstance(); + + private ProtobufVector() { + } + + /** + * @return a new empty instance of {@code ProtobufVector} + */ + public static ProtobufVector newInstance() { + return new ProtobufVector(); + } + + /** + * repeated double rows = 1; + * @return whether the rows field is set + */ + public boolean hasRows() { + return (bitField0_ & 0x00000001) != 0; + } + + /** + * repeated double rows = 1; + * @return this + */ + public ProtobufVector clearRows() { + bitField0_ &= ~0x00000001; + rows.clear(); + return this; + } + + /** + * repeated double rows = 1; + * + * This method returns the internal storage object without modifying any has state. + * The returned object should not be modified and be treated as read-only. + * + * Use {@link #getMutableRows()} if you want to modify it. + * + * @return internal storage object for reading + */ + public RepeatedDouble getRows() { + return rows; + } + + /** + * repeated double rows = 1; + * + * This method returns the internal storage object and sets the corresponding + * has state. The returned object will become part of this message and its + * contents may be modified as long as the has state is not cleared. + * + * @return internal storage object for modifications + */ + public RepeatedDouble getMutableRows() { + bitField0_ |= 0x00000001; + return rows; + } + + /** + * repeated double rows = 1; + * @param value the rows to add + * @return this + */ + public ProtobufVector addRows(final double value) { + bitField0_ |= 0x00000001; + rows.add(value); + return this; + } + + /** + * repeated double rows = 1; + * @param values the rows to add + * @return this + */ + public ProtobufVector addAllRows(final double... values) { + bitField0_ |= 0x00000001; + rows.addAll(values); + return this; + } + + @Override + public ProtobufVector copyFrom(final ProtobufVector other) { + cachedSize = other.cachedSize; + if ((bitField0_ | other.bitField0_) != 0) { + bitField0_ = other.bitField0_; + rows.copyFrom(other.rows); + } + return this; + } + + @Override + public ProtobufVector mergeFrom(final ProtobufVector other) { + if (other.isEmpty()) { + return this; + } + cachedSize = -1; + if (other.hasRows()) { + getMutableRows().addAll(other.rows); + } + return this; + } + + @Override + public ProtobufVector clear() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + rows.clear(); + return this; + } + + @Override + public ProtobufVector clearQuick() { + if (isEmpty()) { + return this; + } + cachedSize = -1; + bitField0_ = 0; + rows.clear(); + return this; + } + + @Override + public boolean equals(Object o) { + if (o == this) { + return true; + } + if (!(o instanceof ProtobufVector)) { + return false; + } + ProtobufVector other = (ProtobufVector) o; + return bitField0_ == other.bitField0_ + && (!hasRows() || rows.equals(other.rows)); + } + + @Override + public void writeTo(final ProtoSink output) throws IOException { + if ((bitField0_ & 0x00000001) != 0) { + for (int i = 0; i < rows.length(); i++) { + output.writeRawByte((byte) 9); + output.writeDoubleNoTag(rows.array()[i]); + } + } + } + + @Override + protected int computeSerializedSize() { + int size = 0; + if ((bitField0_ & 0x00000001) != 0) { + size += (1 + 8) * rows.length(); + } + return size; + } + + @Override + @SuppressWarnings("fallthrough") + public ProtobufVector mergeFrom(final ProtoSource input) throws IOException { + // Enabled Fall-Through Optimization (QuickBuffers) + int tag = input.readTag(); + while (true) { + switch (tag) { + case 10: { + // rows [packed=true] + input.readPackedDouble(rows); + bitField0_ |= 0x00000001; + tag = input.readTag(); + if (tag != 0) { + break; + } + } + case 0: { + return this; + } + default: { + if (!input.skipField(tag)) { + return this; + } + tag = input.readTag(); + break; + } + case 9: { + // rows [packed=false] + tag = input.readRepeatedDouble(rows, tag); + bitField0_ |= 0x00000001; + break; + } + } + } + } + + @Override + public void writeTo(final JsonSink output) throws IOException { + output.beginObject(); + if ((bitField0_ & 0x00000001) != 0) { + output.writeRepeatedDouble(FieldNames.rows, rows); + } + output.endObject(); + } + + @Override + public ProtobufVector mergeFrom(final JsonSource input) throws IOException { + if (!input.beginObject()) { + return this; + } + while (!input.isAtEnd()) { + switch (input.readFieldHash()) { + case 3506649: { + if (input.isAtField(FieldNames.rows)) { + if (!input.trySkipNullValue()) { + input.readRepeatedDouble(rows); + bitField0_ |= 0x00000001; + } + } else { + input.skipUnknownField(); + } + break; + } + default: { + input.skipUnknownField(); + break; + } + } + } + input.endObject(); + return this; + } + + @Override + public ProtobufVector clone() { + return new ProtobufVector().copyFrom(this); + } + + @Override + public boolean isEmpty() { + return ((bitField0_) == 0); + } + + public static ProtobufVector parseFrom(final byte[] data) throws + InvalidProtocolBufferException { + return ProtoMessage.mergeFrom(new ProtobufVector(), data).checkInitialized(); + } + + public static ProtobufVector parseFrom(final ProtoSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufVector(), input).checkInitialized(); + } + + public static ProtobufVector parseFrom(final JsonSource input) throws IOException { + return ProtoMessage.mergeFrom(new ProtobufVector(), input).checkInitialized(); + } + + /** + * @return factory for creating ProtobufVector messages + */ + public static MessageFactory getFactory() { + return ProtobufVectorFactory.INSTANCE; + } + + /** + * @return this type's descriptor. + */ + public static Descriptors.Descriptor getDescriptor() { + return Wpimath.wpi_proto_ProtobufVector_descriptor; + } + + private enum ProtobufVectorFactory implements MessageFactory { + INSTANCE; + + @Override + public ProtobufVector create() { + return ProtobufVector.newInstance(); + } + } + + /** + * Contains name constants used for serializing JSON + */ + static class FieldNames { + static final FieldName rows = FieldName.forField("rows"); + } + } +} From 9d11544c185b66aa9d4552f1555b932e4369f8be Mon Sep 17 00:00:00 2001 From: "Ashray._.g" <43589795+Ashray-g@users.noreply.github.com> Date: Tue, 5 Dec 2023 23:21:28 -0800 Subject: [PATCH 7/9] [wpimath] Rotate traveling salesman solution so input and solution have same initial pose (#6015) --- .../wpi/first/math/path/TravelingSalesman.java | 8 +++++++- .../native/include/frc/path/TravelingSalesman.h | 16 ++++++++++++++-- .../first/math/path/TravelingSalesmanTest.java | 10 ++-------- .../native/cpp/path/TravelingSalesmanTest.cpp | 11 ++--------- 4 files changed, 25 insertions(+), 20 deletions(-) diff --git a/wpimath/src/main/java/edu/wpi/first/math/path/TravelingSalesman.java b/wpimath/src/main/java/edu/wpi/first/math/path/TravelingSalesman.java index 1b885fb7cfb..83dd93ef0bc 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/path/TravelingSalesman.java +++ b/wpimath/src/main/java/edu/wpi/first/math/path/TravelingSalesman.java @@ -8,6 +8,8 @@ import edu.wpi.first.math.Vector; import edu.wpi.first.math.geometry.Pose2d; import edu.wpi.first.math.optimization.SimulatedAnnealing; +import java.util.Arrays; +import java.util.Collections; import java.util.function.ToDoubleBiFunction; /** @@ -40,7 +42,8 @@ public TravelingSalesman(ToDoubleBiFunction cost) { } /** - * Finds the path through every pose that minimizes the cost. + * Finds the path through every pose that minimizes the cost. The first pose in the returned array + * is the first pose that was passed in. * * @param A Num defining the length of the path and the number of poses. * @param poses An array of Pose2ds the path must pass through. @@ -76,6 +79,9 @@ public Pose2d[] solve(Pose2d[] poses, int iterations) { solution[i] = poses[(int) indices.get(i, 0)]; } + // Rotate solution list until solution[0] = poses[0] + Collections.rotate(Arrays.asList(solution), -Arrays.asList(solution).indexOf(poses[0])); + return solution; } diff --git a/wpimath/src/main/native/include/frc/path/TravelingSalesman.h b/wpimath/src/main/native/include/frc/path/TravelingSalesman.h index 696e0d86da9..d45f6203f8e 100644 --- a/wpimath/src/main/native/include/frc/path/TravelingSalesman.h +++ b/wpimath/src/main/native/include/frc/path/TravelingSalesman.h @@ -44,7 +44,8 @@ class TravelingSalesman { : m_cost{std::move(cost)} {} /** - * Finds the path through every pose that minimizes the cost. + * Finds the path through every pose that minimizes the cost. The first pose + * in the returned array is the first pose that was passed in. * * This overload supports a statically-sized list of poses. * @@ -81,11 +82,17 @@ class TravelingSalesman { solution[i] = poses[static_cast(indices[i])]; } + // Rotate solution list until solution[0] = poses[0] + std::rotate(solution.begin(), + std::find(solution.begin(), solution.end(), poses[0]), + solution.end()); + return solution; } /** - * Finds the path through every pose that minimizes the cost. + * Finds the path through every pose that minimizes the cost. The first pose + * in the returned array is the first pose that was passed in. * * This overload supports a dynamically-sized list of poses for Python to use. * @@ -119,6 +126,11 @@ class TravelingSalesman { solution.emplace_back(poses[static_cast(indices[i])]); } + // Rotate solution list until solution[0] = poses[0] + std::rotate(solution.begin(), + std::find(solution.begin(), solution.end(), poses[0]), + solution.end()); + return solution; } diff --git a/wpimath/src/test/java/edu/wpi/first/math/path/TravelingSalesmanTest.java b/wpimath/src/test/java/edu/wpi/first/math/path/TravelingSalesmanTest.java index ef3f9409540..cf4317721d8 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/path/TravelingSalesmanTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/path/TravelingSalesmanTest.java @@ -22,16 +22,10 @@ class TravelingSalesmanTest { private boolean isMatchingCycle(Pose2d[] expected, Pose2d[] actual) { assertEquals(expected.length, actual.length); - // Find first element in actual that matches expected - int actualStart = 0; - while (!actual[actualStart].equals(expected[0])) { - ++actualStart; - } - // Check actual has expected cycle (forward) var actualBufferForward = new CircularBuffer(actual.length); for (int i = 0; i < actual.length; ++i) { - actualBufferForward.addLast(actual[(actualStart + i) % actual.length]); + actualBufferForward.addLast(actual[i % actual.length]); } boolean matchesExpectedForward = true; for (int i = 0; i < expected.length; ++i) { @@ -41,7 +35,7 @@ private boolean isMatchingCycle(Pose2d[] expected, Pose2d[] actual) { // Check actual has expected cycle (reverse) var actualBufferReverse = new CircularBuffer(actual.length); for (int i = 0; i < actual.length; ++i) { - actualBufferReverse.addFirst(actual[(actualStart + 1 + i) % actual.length]); + actualBufferReverse.addFirst(actual[(1 + i) % actual.length]); } boolean matchesExpectedReverse = true; diff --git a/wpimath/src/test/native/cpp/path/TravelingSalesmanTest.cpp b/wpimath/src/test/native/cpp/path/TravelingSalesmanTest.cpp index b8b622afdf5..f46eb2040fb 100644 --- a/wpimath/src/test/native/cpp/path/TravelingSalesmanTest.cpp +++ b/wpimath/src/test/native/cpp/path/TravelingSalesmanTest.cpp @@ -25,16 +25,10 @@ bool IsMatchingCycle(std::span expected, std::span actual) { assert(expected.size() == actual.size()); - // Find first element in actual that matches expected - size_t actualStart = 0; - while (actual[actualStart] != expected[0]) { - ++actualStart; - } - // Check actual has expected cycle (forward) wpi::circular_buffer actualBufferForward{expected.size()}; for (size_t i = 0; i < actual.size(); ++i) { - actualBufferForward.push_back(actual[(actualStart + i) % actual.size()]); + actualBufferForward.push_back(actual[i % actual.size()]); } bool matchesExpectedForward = true; for (size_t i = 0; i < expected.size(); ++i) { @@ -44,8 +38,7 @@ bool IsMatchingCycle(std::span expected, // Check actual has expected cycle (reverse) wpi::circular_buffer actualBufferReverse{expected.size()}; for (size_t i = 0; i < actual.size(); ++i) { - actualBufferReverse.push_front( - actual[(actualStart + 1 + i) % actual.size()]); + actualBufferReverse.push_front(actual[(1 + i) % actual.size()]); } bool matchesExpectedReverse = true; for (size_t i = 0; i < expected.size(); ++i) { From 38bf024c96cc5a57258568a4e8e54fd4f7a0a5fb Mon Sep 17 00:00:00 2001 From: Isaac Turner Date: Thu, 7 Dec 2023 01:29:41 +0800 Subject: [PATCH 8/9] [build] Update to Gradle 8.5 (#6007) --- build.gradle | 2 +- gradle/wrapper/gradle-wrapper.jar | Bin 63721 -> 43462 bytes gradle/wrapper/gradle-wrapper.properties | 2 +- 3 files changed, 2 insertions(+), 2 deletions(-) diff --git a/build.gradle b/build.gradle index b1c3ca2e6df..f1d2a522bed 100644 --- a/build.gradle +++ b/build.gradle @@ -171,5 +171,5 @@ ext.getCurrentArch = { } wrapper { - gradleVersion = '8.4' + gradleVersion = '8.5' } diff --git a/gradle/wrapper/gradle-wrapper.jar b/gradle/wrapper/gradle-wrapper.jar index 7f93135c49b765f8051ef9d0a6055ff8e46073d8..d64cd4917707c1f8861d8cb53dd15194d4248596 100644 GIT binary patch literal 43462 zcma&NWl&^owk(X(xVyW%ySuwf;qI=D6|RlDJ2cR^yEKh!@I- zp9QeisK*rlxC>+~7Dk4IxIRsKBHqdR9b3+fyL=ynHmIDe&|>O*VlvO+%z5;9Z$|DJ zb4dO}-R=MKr^6EKJiOrJdLnCJn>np?~vU-1sSFgPu;pthGwf}bG z(1db%xwr#x)r+`4AGu$j7~u2MpVs3VpLp|mx&;>`0p0vH6kF+D2CY0fVdQOZ@h;A` z{infNyvmFUiu*XG}RNMNwXrbec_*a3N=2zJ|Wh5z* z5rAX$JJR{#zP>KY**>xHTuw?|-Rg|o24V)74HcfVT;WtQHXlE+_4iPE8QE#DUm%x0 zEKr75ur~W%w#-My3Tj`hH6EuEW+8K-^5P62$7Sc5OK+22qj&Pd1;)1#4tKihi=~8C zHiQSst0cpri6%OeaR`PY>HH_;CPaRNty%WTm4{wDK8V6gCZlG@U3$~JQZ;HPvDJcT1V{ z?>H@13MJcCNe#5z+MecYNi@VT5|&UiN1D4ATT+%M+h4c$t;C#UAs3O_q=GxK0}8%8 z8J(_M9bayxN}69ex4dzM_P3oh@ZGREjVvn%%r7=xjkqxJP4kj}5tlf;QosR=%4L5y zWhgejO=vao5oX%mOHbhJ8V+SG&K5dABn6!WiKl{|oPkq(9z8l&Mm%(=qGcFzI=eLu zWc_oCLyf;hVlB@dnwY98?75B20=n$>u3b|NB28H0u-6Rpl((%KWEBOfElVWJx+5yg z#SGqwza7f}$z;n~g%4HDU{;V{gXIhft*q2=4zSezGK~nBgu9-Q*rZ#2f=Q}i2|qOp z!!y4p)4o=LVUNhlkp#JL{tfkhXNbB=Ox>M=n6soptJw-IDI|_$is2w}(XY>a=H52d z3zE$tjPUhWWS+5h=KVH&uqQS=$v3nRs&p$%11b%5qtF}S2#Pc`IiyBIF4%A!;AVoI zXU8-Rpv!DQNcF~(qQnyyMy=-AN~U>#&X1j5BLDP{?K!%h!;hfJI>$mdLSvktEr*89 zdJHvby^$xEX0^l9g$xW-d?J;L0#(`UT~zpL&*cEh$L|HPAu=P8`OQZV!-}l`noSp_ zQ-1$q$R-gDL)?6YaM!=8H=QGW$NT2SeZlb8PKJdc=F-cT@j7Xags+Pr*jPtlHFnf- zh?q<6;)27IdPc^Wdy-mX%2s84C1xZq9Xms+==F4);O`VUASmu3(RlgE#0+#giLh-& zcxm3_e}n4{%|X zJp{G_j+%`j_q5}k{eW&TlP}J2wtZ2^<^E(O)4OQX8FDp6RJq!F{(6eHWSD3=f~(h} zJXCf7=r<16X{pHkm%yzYI_=VDP&9bmI1*)YXZeB}F? z(%QsB5fo*FUZxK$oX~X^69;x~j7ms8xlzpt-T15e9}$4T-pC z6PFg@;B-j|Ywajpe4~bk#S6(fO^|mm1hKOPfA%8-_iGCfICE|=P_~e;Wz6my&)h_~ zkv&_xSAw7AZ%ThYF(4jADW4vg=oEdJGVOs>FqamoL3Np8>?!W#!R-0%2Bg4h?kz5I zKV-rKN2n(vUL%D<4oj@|`eJ>0i#TmYBtYmfla;c!ATW%;xGQ0*TW@PTlGG><@dxUI zg>+3SiGdZ%?5N=8uoLA|$4isK$aJ%i{hECP$bK{J#0W2gQ3YEa zZQ50Stn6hqdfxJ*9#NuSLwKFCUGk@c=(igyVL;;2^wi4o30YXSIb2g_ud$ zgpCr@H0qWtk2hK8Q|&wx)}4+hTYlf;$a4#oUM=V@Cw#!$(nOFFpZ;0lc!qd=c$S}Z zGGI-0jg~S~cgVT=4Vo)b)|4phjStD49*EqC)IPwyeKBLcN;Wu@Aeph;emROAwJ-0< z_#>wVm$)ygH|qyxZaet&(Vf%pVdnvKWJn9`%DAxj3ot;v>S$I}jJ$FLBF*~iZ!ZXE zkvui&p}fI0Y=IDX)mm0@tAd|fEHl~J&K}ZX(Mm3cm1UAuwJ42+AO5@HwYfDH7ipIc zmI;1J;J@+aCNG1M`Btf>YT>~c&3j~Qi@Py5JT6;zjx$cvOQW@3oQ>|}GH?TW-E z1R;q^QFjm5W~7f}c3Ww|awg1BAJ^slEV~Pk`Kd`PS$7;SqJZNj->it4DW2l15}xP6 zoCl$kyEF%yJni0(L!Z&14m!1urXh6Btj_5JYt1{#+H8w?5QI%% zo-$KYWNMJVH?Hh@1n7OSu~QhSswL8x0=$<8QG_zepi_`y_79=nK=_ZP_`Em2UI*tyQoB+r{1QYZCpb?2OrgUw#oRH$?^Tj!Req>XiE#~B|~ z+%HB;=ic+R@px4Ld8mwpY;W^A%8%l8$@B@1m5n`TlKI6bz2mp*^^^1mK$COW$HOfp zUGTz-cN9?BGEp}5A!mDFjaiWa2_J2Iq8qj0mXzk; z66JBKRP{p%wN7XobR0YjhAuW9T1Gw3FDvR5dWJ8ElNYF94eF3ebu+QwKjtvVu4L zI9ip#mQ@4uqVdkl-TUQMb^XBJVLW(-$s;Nq;@5gr4`UfLgF$adIhd?rHOa%D);whv z=;krPp~@I+-Z|r#s3yCH+c1US?dnm+C*)r{m+86sTJusLdNu^sqLrfWed^ndHXH`m zd3#cOe3>w-ga(Dus_^ppG9AC>Iq{y%%CK+Cro_sqLCs{VLuK=dev>OL1dis4(PQ5R zcz)>DjEkfV+MO;~>VUlYF00SgfUo~@(&9$Iy2|G0T9BSP?&T22>K46D zL*~j#yJ?)^*%J3!16f)@Y2Z^kS*BzwfAQ7K96rFRIh>#$*$_Io;z>ux@}G98!fWR@ zGTFxv4r~v)Gsd|pF91*-eaZ3Qw1MH$K^7JhWIdX%o$2kCbvGDXy)a?@8T&1dY4`;L z4Kn+f%SSFWE_rpEpL9bnlmYq`D!6F%di<&Hh=+!VI~j)2mfil03T#jJ_s?}VV0_hp z7T9bWxc>Jm2Z0WMU?`Z$xE74Gu~%s{mW!d4uvKCx@WD+gPUQ zV0vQS(Ig++z=EHN)BR44*EDSWIyT~R4$FcF*VEY*8@l=218Q05D2$|fXKFhRgBIEE zdDFB}1dKkoO^7}{5crKX!p?dZWNz$m>1icsXG2N+((x0OIST9Zo^DW_tytvlwXGpn zs8?pJXjEG;T@qrZi%#h93?FP$!&P4JA(&H61tqQi=opRzNpm zkrG}$^t9&XduK*Qa1?355wd8G2CI6QEh@Ua>AsD;7oRUNLPb76m4HG3K?)wF~IyS3`fXuNM>${?wmB zpVz;?6_(Fiadfd{vUCBM*_kt$+F3J+IojI;9L(gc9n3{sEZyzR9o!_mOwFC#tQ{Q~ zP3-`#uK#tP3Q7~Q;4H|wjZHO8h7e4IuBxl&vz2w~D8)w=Wtg31zpZhz%+kzSzL*dV zwp@{WU4i;hJ7c2f1O;7Mz6qRKeASoIv0_bV=i@NMG*l<#+;INk-^`5w@}Dj~;k=|}qM1vq_P z|GpBGe_IKq|LNy9SJhKOQ$c=5L{Dv|Q_lZl=-ky*BFBJLW9&y_C|!vyM~rQx=!vun z?rZJQB5t}Dctmui5i31C_;_}CEn}_W%>oSXtt>@kE1=JW*4*v4tPp;O6 zmAk{)m!)}34pTWg8{i>($%NQ(Tl;QC@J@FfBoc%Gr&m560^kgSfodAFrIjF}aIw)X zoXZ`@IsMkc8_=w%-7`D6Y4e*CG8k%Ud=GXhsTR50jUnm+R*0A(O3UKFg0`K;qp1bl z7``HN=?39ic_kR|^R^~w-*pa?Vj#7|e9F1iRx{GN2?wK!xR1GW!qa=~pjJb-#u1K8 zeR?Y2i-pt}yJq;SCiVHODIvQJX|ZJaT8nO+(?HXbLefulKKgM^B(UIO1r+S=7;kLJ zcH}1J=Px2jsh3Tec&v8Jcbng8;V-`#*UHt?hB(pmOipKwf3Lz8rG$heEB30Sg*2rx zV<|KN86$soN(I!BwO`1n^^uF2*x&vJ$2d$>+`(romzHP|)K_KkO6Hc>_dwMW-M(#S zK(~SiXT1@fvc#U+?|?PniDRm01)f^#55;nhM|wi?oG>yBsa?~?^xTU|fX-R(sTA+5 zaq}-8Tx7zrOy#3*JLIIVsBmHYLdD}!0NP!+ITW+Thn0)8SS!$@)HXwB3tY!fMxc#1 zMp3H?q3eD?u&Njx4;KQ5G>32+GRp1Ee5qMO0lZjaRRu&{W<&~DoJNGkcYF<5(Ab+J zgO>VhBl{okDPn78<%&e2mR{jwVCz5Og;*Z;;3%VvoGo_;HaGLWYF7q#jDX=Z#Ml`H z858YVV$%J|e<1n`%6Vsvq7GmnAV0wW4$5qQ3uR@1i>tW{xrl|ExywIc?fNgYlA?C5 zh$ezAFb5{rQu6i7BSS5*J-|9DQ{6^BVQ{b*lq`xS@RyrsJN?-t=MTMPY;WYeKBCNg z^2|pN!Q^WPJuuO4!|P@jzt&tY1Y8d%FNK5xK(!@`jO2aEA*4 zkO6b|UVBipci?){-Ke=+1;mGlND8)6+P;8sq}UXw2hn;fc7nM>g}GSMWu&v&fqh

iViYT=fZ(|3Ox^$aWPp4a8h24tD<|8-!aK0lHgL$N7Efw}J zVIB!7=T$U`ao1?upi5V4Et*-lTG0XvExbf!ya{cua==$WJyVG(CmA6Of*8E@DSE%L z`V^$qz&RU$7G5mg;8;=#`@rRG`-uS18$0WPN@!v2d{H2sOqP|!(cQ@ zUHo!d>>yFArLPf1q`uBvY32miqShLT1B@gDL4XoVTK&@owOoD)OIHXrYK-a1d$B{v zF^}8D3Y^g%^cnvScOSJR5QNH+BI%d|;J;wWM3~l>${fb8DNPg)wrf|GBP8p%LNGN# z3EaIiItgwtGgT&iYCFy9-LG}bMI|4LdmmJt@V@% zb6B)1kc=T)(|L@0;wr<>=?r04N;E&ef+7C^`wPWtyQe(*pD1pI_&XHy|0gIGHMekd zF_*M4yi6J&Z4LQj65)S zXwdM{SwUo%3SbPwFsHgqF@V|6afT|R6?&S;lw=8% z3}@9B=#JI3@B*#4s!O))~z zc>2_4Q_#&+5V`GFd?88^;c1i7;Vv_I*qt!_Yx*n=;rj!82rrR2rQ8u5(Ejlo{15P% zs~!{%XJ>FmJ})H^I9bn^Re&38H{xA!0l3^89k(oU;bZWXM@kn$#aoS&Y4l^-WEn-fH39Jb9lA%s*WsKJQl?n9B7_~P z-XM&WL7Z!PcoF6_D>V@$CvUIEy=+Z&0kt{szMk=f1|M+r*a43^$$B^MidrT0J;RI` z(?f!O<8UZkm$_Ny$Hth1J#^4ni+im8M9mr&k|3cIgwvjAgjH z8`N&h25xV#v*d$qBX5jkI|xOhQn!>IYZK7l5#^P4M&twe9&Ey@@GxYMxBZq2e7?`q z$~Szs0!g{2fGcp9PZEt|rdQ6bhAgpcLHPz?f-vB?$dc*!9OL?Q8mn7->bFD2Si60* z!O%y)fCdMSV|lkF9w%x~J*A&srMyYY3{=&$}H zGQ4VG_?$2X(0|vT0{=;W$~icCI{b6W{B!Q8xdGhF|D{25G_5_+%s(46lhvNLkik~R z>nr(&C#5wwOzJZQo9m|U<;&Wk!_#q|V>fsmj1g<6%hB{jGoNUPjgJslld>xmODzGjYc?7JSuA?A_QzjDw5AsRgi@Y|Z0{F{!1=!NES-#*f^s4l0Hu zz468))2IY5dmD9pa*(yT5{EyP^G>@ZWumealS-*WeRcZ}B%gxq{MiJ|RyX-^C1V=0 z@iKdrGi1jTe8Ya^x7yyH$kBNvM4R~`fbPq$BzHum-3Zo8C6=KW@||>zsA8-Y9uV5V z#oq-f5L5}V<&wF4@X@<3^C%ptp6+Ce)~hGl`kwj)bsAjmo_GU^r940Z-|`<)oGnh7 zFF0Tde3>ui?8Yj{sF-Z@)yQd~CGZ*w-6p2U<8}JO-sRsVI5dBji`01W8A&3$?}lxBaC&vn0E$c5tW* zX>5(zzZ=qn&!J~KdsPl;P@bmA-Pr8T*)eh_+Dv5=Ma|XSle6t(k8qcgNyar{*ReQ8 zTXwi=8vr>!3Ywr+BhggHDw8ke==NTQVMCK`$69fhzEFB*4+H9LIvdt-#IbhZvpS}} zO3lz;P?zr0*0$%-Rq_y^k(?I{Mk}h@w}cZpMUp|ucs55bcloL2)($u%mXQw({Wzc~ z;6nu5MkjP)0C(@%6Q_I_vsWrfhl7Zpoxw#WoE~r&GOSCz;_ro6i(^hM>I$8y>`!wW z*U^@?B!MMmb89I}2(hcE4zN2G^kwyWCZp5JG>$Ez7zP~D=J^LMjSM)27_0B_X^C(M z`fFT+%DcKlu?^)FCK>QzSnV%IsXVcUFhFdBP!6~se&xxrIxsvySAWu++IrH;FbcY$ z2DWTvSBRfLwdhr0nMx+URA$j3i7_*6BWv#DXfym?ZRDcX9C?cY9sD3q)uBDR3uWg= z(lUIzB)G$Hr!){>E{s4Dew+tb9kvToZp-1&c?y2wn@Z~(VBhqz`cB;{E4(P3N2*nJ z_>~g@;UF2iG{Kt(<1PyePTKahF8<)pozZ*xH~U-kfoAayCwJViIrnqwqO}7{0pHw$ zs2Kx?s#vQr7XZ264>5RNKSL8|Ty^=PsIx^}QqOOcfpGUU4tRkUc|kc7-!Ae6!+B{o~7nFpm3|G5^=0#Bnm6`V}oSQlrX(u%OWnC zoLPy&Q;1Jui&7ST0~#+}I^&?vcE*t47~Xq#YwvA^6^} z`WkC)$AkNub|t@S!$8CBlwbV~?yp&@9h{D|3z-vJXgzRC5^nYm+PyPcgRzAnEi6Q^gslXYRv4nycsy-SJu?lMps-? zV`U*#WnFsdPLL)Q$AmD|0`UaC4ND07+&UmOu!eHruzV|OUox<+Jl|Mr@6~C`T@P%s zW7sgXLF2SSe9Fl^O(I*{9wsFSYb2l%-;&Pi^dpv!{)C3d0AlNY6!4fgmSgj_wQ*7Am7&$z;Jg&wgR-Ih;lUvWS|KTSg!&s_E9_bXBkZvGiC6bFKDWZxsD$*NZ#_8bl zG1P-#@?OQzED7@jlMJTH@V!6k;W>auvft)}g zhoV{7$q=*;=l{O>Q4a@ ziMjf_u*o^PsO)#BjC%0^h>Xp@;5$p{JSYDt)zbb}s{Kbt!T*I@Pk@X0zds6wsefuU zW$XY%yyRGC94=6mf?x+bbA5CDQ2AgW1T-jVAJbm7K(gp+;v6E0WI#kuACgV$r}6L? zd|Tj?^%^*N&b>Dd{Wr$FS2qI#Ucs1yd4N+RBUQiSZGujH`#I)mG&VKoDh=KKFl4=G z&MagXl6*<)$6P}*Tiebpz5L=oMaPrN+caUXRJ`D?=K9!e0f{@D&cZLKN?iNP@X0aF zE(^pl+;*T5qt?1jRC=5PMgV!XNITRLS_=9{CJExaQj;lt!&pdzpK?8p>%Mb+D z?yO*uSung=-`QQ@yX@Hyd4@CI^r{2oiu`%^bNkz+Nkk!IunjwNC|WcqvX~k=><-I3 zDQdbdb|!v+Iz01$w@aMl!R)koD77Xp;eZwzSl-AT zr@Vu{=xvgfq9akRrrM)}=!=xcs+U1JO}{t(avgz`6RqiiX<|hGG1pmop8k6Q+G_mv zJv|RfDheUp2L3=^C=4aCBMBn0aRCU(DQwX-W(RkRwmLeuJYF<0urcaf(=7)JPg<3P zQs!~G)9CT18o!J4{zX{_e}4eS)U-E)0FAt}wEI(c0%HkxgggW;(1E=>J17_hsH^sP z%lT0LGgbUXHx-K*CI-MCrP66UP0PvGqM$MkeLyqHdbgP|_Cm!7te~b8p+e6sQ_3k| zVcwTh6d83ltdnR>D^)BYQpDKlLk3g0Hdcgz2}%qUs9~~Rie)A-BV1mS&naYai#xcZ z(d{8=-LVpTp}2*y)|gR~;qc7fp26}lPcLZ#=JpYcn3AT9(UIdOyg+d(P5T7D&*P}# zQCYplZO5|7+r19%9e`v^vfSS1sbX1c%=w1;oyruXB%Kl$ACgKQ6=qNWLsc=28xJjg zwvsI5-%SGU|3p>&zXVl^vVtQT3o-#$UT9LI@Npz~6=4!>mc431VRNN8od&Ul^+G_kHC`G=6WVWM z%9eWNyy(FTO|A+@x}Ou3CH)oi;t#7rAxdIXfNFwOj_@Y&TGz6P_sqiB`Q6Lxy|Q{`|fgmRG(k+!#b*M+Z9zFce)f-7;?Km5O=LHV9f9_87; zF7%R2B+$?@sH&&-$@tzaPYkw0;=i|;vWdI|Wl3q_Zu>l;XdIw2FjV=;Mq5t1Q0|f< zs08j54Bp`3RzqE=2enlkZxmX6OF+@|2<)A^RNQpBd6o@OXl+i)zO%D4iGiQNuXd+zIR{_lb96{lc~bxsBveIw6umhShTX+3@ZJ=YHh@ zWY3(d0azg;7oHn>H<>?4@*RQbi>SmM=JrHvIG(~BrvI)#W(EAeO6fS+}mxxcc+X~W6&YVl86W9WFSS}Vz-f9vS?XUDBk)3TcF z8V?$4Q)`uKFq>xT=)Y9mMFVTUk*NIA!0$?RP6Ig0TBmUFrq*Q-Agq~DzxjStQyJ({ zBeZ;o5qUUKg=4Hypm|}>>L=XKsZ!F$yNTDO)jt4H0gdQ5$f|d&bnVCMMXhNh)~mN z@_UV6D7MVlsWz+zM+inZZp&P4fj=tm6fX)SG5H>OsQf_I8c~uGCig$GzuwViK54bcgL;VN|FnyQl>Ed7(@>=8$a_UKIz|V6CeVSd2(P z0Uu>A8A+muM%HLFJQ9UZ5c)BSAv_zH#1f02x?h9C}@pN@6{>UiAp>({Fn(T9Q8B z^`zB;kJ5b`>%dLm+Ol}ty!3;8f1XDSVX0AUe5P#@I+FQ-`$(a;zNgz)4x5hz$Hfbg z!Q(z26wHLXko(1`;(BAOg_wShpX0ixfWq3ponndY+u%1gyX)_h=v1zR#V}#q{au6; z!3K=7fQwnRfg6FXtNQmP>`<;!N137paFS%y?;lb1@BEdbvQHYC{976l`cLqn;b8lp zIDY>~m{gDj(wfnK!lpW6pli)HyLEiUrNc%eXTil|F2s(AY+LW5hkKb>TQ3|Q4S9rr zpDs4uK_co6XPsn_z$LeS{K4jFF`2>U`tbgKdyDne`xmR<@6AA+_hPNKCOR-Zqv;xk zu5!HsBUb^!4uJ7v0RuH-7?l?}b=w5lzzXJ~gZcxRKOovSk@|#V+MuX%Y+=;14i*%{)_gSW9(#4%)AV#3__kac1|qUy!uyP{>?U#5wYNq}y$S9pCc zFc~4mgSC*G~j0u#qqp9 z${>3HV~@->GqEhr_Xwoxq?Hjn#=s2;i~g^&Hn|aDKpA>Oc%HlW(KA1?BXqpxB;Ydx)w;2z^MpjJ(Qi(X!$5RC z*P{~%JGDQqojV>2JbEeCE*OEu!$XJ>bWA9Oa_Hd;y)F%MhBRi*LPcdqR8X`NQ&1L# z5#9L*@qxrx8n}LfeB^J{%-?SU{FCwiWyHp682F+|pa+CQa3ZLzBqN1{)h4d6+vBbV zC#NEbQLC;}me3eeYnOG*nXOJZEU$xLZ1<1Y=7r0(-U0P6-AqwMAM`a(Ed#7vJkn6plb4eI4?2y3yOTGmmDQ!z9`wzbf z_OY#0@5=bnep;MV0X_;;SJJWEf^E6Bd^tVJ9znWx&Ks8t*B>AM@?;D4oWUGc z!H*`6d7Cxo6VuyS4Eye&L1ZRhrRmN6Lr`{NL(wDbif|y&z)JN>Fl5#Wi&mMIr5i;x zBx}3YfF>>8EC(fYnmpu~)CYHuHCyr5*`ECap%t@y=jD>!_%3iiE|LN$mK9>- zHdtpy8fGZtkZF?%TW~29JIAfi2jZT8>OA7=h;8T{{k?c2`nCEx9$r zS+*&vt~2o^^J+}RDG@+9&M^K*z4p{5#IEVbz`1%`m5c2};aGt=V?~vIM}ZdPECDI)47|CWBCfDWUbxBCnmYivQ*0Nu_xb*C>~C9(VjHM zxe<*D<#dQ8TlpMX2c@M<9$w!RP$hpG4cs%AI){jp*Sj|*`m)5(Bw*A0$*i-(CA5#%>a)$+jI2C9r6|(>J8InryENI z$NohnxDUB;wAYDwrb*!N3noBTKPpPN}~09SEL18tkG zxgz(RYU_;DPT{l?Q$+eaZaxnsWCA^ds^0PVRkIM%bOd|G2IEBBiz{&^JtNsODs;5z zICt_Zj8wo^KT$7Bg4H+y!Df#3mbl%%?|EXe!&(Vmac1DJ*y~3+kRKAD=Ovde4^^%~ zw<9av18HLyrf*_>Slp;^i`Uy~`mvBjZ|?Ad63yQa#YK`4+c6;pW4?XIY9G1(Xh9WO8{F-Aju+nS9Vmv=$Ac0ienZ+p9*O%NG zMZKy5?%Z6TAJTE?o5vEr0r>f>hb#2w2U3DL64*au_@P!J!TL`oH2r*{>ffu6|A7tv zL4juf$DZ1MW5ZPsG!5)`k8d8c$J$o;%EIL0va9&GzWvkS%ZsGb#S(?{!UFOZ9<$a| zY|a+5kmD5N&{vRqkgY>aHsBT&`rg|&kezoD)gP0fsNYHsO#TRc_$n6Lf1Z{?+DLziXlHrq4sf(!>O{?Tj;Eh@%)+nRE_2VxbN&&%%caU#JDU%vL3}Cb zsb4AazPI{>8H&d=jUaZDS$-0^AxE@utGs;-Ez_F(qC9T=UZX=>ok2k2 ziTn{K?y~a5reD2A)P${NoI^>JXn>`IeArow(41c-Wm~)wiryEP(OS{YXWi7;%dG9v zI?mwu1MxD{yp_rrk!j^cKM)dc4@p4Ezyo%lRN|XyD}}>v=Xoib0gOcdXrQ^*61HNj z=NP|pd>@yfvr-=m{8$3A8TQGMTE7g=z!%yt`8`Bk-0MMwW~h^++;qyUP!J~ykh1GO z(FZ59xuFR$(WE;F@UUyE@Sp>`aVNjyj=Ty>_Vo}xf`e7`F;j-IgL5`1~-#70$9_=uBMq!2&1l zomRgpD58@)YYfvLtPW}{C5B35R;ZVvB<<#)x%srmc_S=A7F@DW8>QOEGwD6suhwCg z>Pa+YyULhmw%BA*4yjDp|2{!T98~<6Yfd(wo1mQ!KWwq0eg+6)o1>W~f~kL<-S+P@$wx*zeI|1t7z#Sxr5 zt6w+;YblPQNplq4Z#T$GLX#j6yldXAqj>4gAnnWtBICUnA&-dtnlh=t0Ho_vEKwV` z)DlJi#!@nkYV#$!)@>udAU*hF?V`2$Hf=V&6PP_|r#Iv*J$9)pF@X3`k;5})9^o4y z&)~?EjX5yX12O(BsFy-l6}nYeuKkiq`u9145&3Ssg^y{5G3Pse z9w(YVa0)N-fLaBq1`P!_#>SS(8fh_5!f{UrgZ~uEdeMJIz7DzI5!NHHqQtm~#CPij z?=N|J>nPR6_sL7!f4hD_|KH`vf8(Wpnj-(gPWH+ZvID}%?~68SwhPTC3u1_cB`otq z)U?6qo!ZLi5b>*KnYHWW=3F!p%h1;h{L&(Q&{qY6)_qxNfbP6E3yYpW!EO+IW3?@J z);4>g4gnl^8klu7uA>eGF6rIGSynacogr)KUwE_R4E5Xzi*Qir@b-jy55-JPC8c~( zo!W8y9OGZ&`xmc8;=4-U9=h{vCqfCNzYirONmGbRQlR`WWlgnY+1wCXbMz&NT~9*| z6@FrzP!LX&{no2!Ln_3|I==_4`@}V?4a;YZKTdw;vT<+K+z=uWbW(&bXEaWJ^W8Td z-3&1bY^Z*oM<=M}LVt>_j+p=2Iu7pZmbXrhQ_k)ysE9yXKygFNw$5hwDn(M>H+e1&9BM5!|81vd%r%vEm zqxY3?F@fb6O#5UunwgAHR9jp_W2zZ}NGp2%mTW@(hz7$^+a`A?mb8|_G*GNMJ) zjqegXQio=i@AINre&%ofexAr95aop5C+0MZ0m-l=MeO8m3epm7U%vZB8+I+C*iNFM z#T3l`gknX;D$-`2XT^Cg*vrv=RH+P;_dfF++cP?B_msQI4j+lt&rX2)3GaJx%W*Nn zkML%D{z5tpHH=dksQ*gzc|}gzW;lwAbxoR07VNgS*-c3d&8J|;@3t^ zVUz*J*&r7DFRuFVDCJDK8V9NN5hvpgGjwx+5n)qa;YCKe8TKtdnh{I7NU9BCN!0dq zczrBk8pE{{@vJa9ywR@mq*J=v+PG;?fwqlJVhijG!3VmIKs>9T6r7MJpC)m!Tc#>g zMtVsU>wbwFJEfwZ{vB|ZlttNe83)$iz`~#8UJ^r)lJ@HA&G#}W&ZH*;k{=TavpjWE z7hdyLZPf*X%Gm}i`Y{OGeeu^~nB8=`{r#TUrM-`;1cBvEd#d!kPqIgYySYhN-*1;L z^byj%Yi}Gx)Wnkosi337BKs}+5H5dth1JA{Ir-JKN$7zC)*}hqeoD(WfaUDPT>0`- z(6sa0AoIqASwF`>hP}^|)a_j2s^PQn*qVC{Q}htR z5-)duBFXT_V56-+UohKXlq~^6uf!6sA#ttk1o~*QEy_Y-S$gAvq47J9Vtk$5oA$Ct zYhYJ@8{hsC^98${!#Ho?4y5MCa7iGnfz}b9jE~h%EAAv~Qxu)_rAV;^cygV~5r_~?l=B`zObj7S=H=~$W zPtI_m%g$`kL_fVUk9J@>EiBH zOO&jtn~&`hIFMS5S`g8w94R4H40mdNUH4W@@XQk1sr17b{@y|JB*G9z1|CrQjd+GX z6+KyURG3;!*BQrentw{B2R&@2&`2}n(z-2&X7#r!{yg@Soy}cRD~j zj9@UBW+N|4HW4AWapy4wfUI- zZ`gSL6DUlgj*f1hSOGXG0IVH8HxK?o2|3HZ;KW{K+yPAlxtb)NV_2AwJm|E)FRs&& z=c^e7bvUsztY|+f^k7NXs$o1EUq>cR7C0$UKi6IooHWlK_#?IWDkvywnzg&ThWo^? z2O_N{5X39#?eV9l)xI(>@!vSB{DLt*oY!K1R8}_?%+0^C{d9a%N4 zoxHVT1&Lm|uDX%$QrBun5e-F`HJ^T$ zmzv)p@4ZHd_w9!%Hf9UYNvGCw2TTTbrj9pl+T9%-_-}L(tES>Or-}Z4F*{##n3~L~TuxjirGuIY#H7{%$E${?p{Q01 zi6T`n;rbK1yIB9jmQNycD~yZq&mbIsFWHo|ZAChSFPQa<(%d8mGw*V3fh|yFoxOOiWJd(qvVb!Z$b88cg->N=qO*4k~6;R==|9ihg&riu#P~s4Oap9O7f%crSr^rljeIfXDEg>wi)&v*a%7zpz<9w z*r!3q9J|390x`Zk;g$&OeN&ctp)VKRpDSV@kU2Q>jtok($Y-*x8_$2piTxun81@vt z!Vj?COa0fg2RPXMSIo26T=~0d`{oGP*eV+$!0I<(4azk&Vj3SiG=Q!6mX0p$z7I}; z9BJUFgT-K9MQQ-0@Z=^7R<{bn2Fm48endsSs`V7_@%8?Bxkqv>BDoVcj?K#dV#uUP zL1ND~?D-|VGKe3Rw_7-Idpht>H6XRLh*U7epS6byiGvJpr%d}XwfusjH9g;Z98H`x zyde%%5mhGOiL4wljCaWCk-&uE4_OOccb9c!ZaWt4B(wYl!?vyzl%7n~QepN&eFUrw zFIOl9c({``6~QD+43*_tzP{f2x41h(?b43^y6=iwyB)2os5hBE!@YUS5?N_tXd=h( z)WE286Fbd>R4M^P{!G)f;h<3Q>Fipuy+d2q-)!RyTgt;wr$(?9ox3;q+{E*ZQHhOn;lM`cjnu9 zXa48ks-v(~b*;MAI<>YZH(^NV8vjb34beE<_cwKlJoR;k6lJNSP6v}uiyRD?|0w+X@o1ONrH8a$fCxXpf? z?$DL0)7|X}Oc%h^zrMKWc-NS9I0Utu@>*j}b@tJ=ixQSJ={4@854wzW@E>VSL+Y{i z#0b=WpbCZS>kUCO_iQz)LoE>P5LIG-hv9E+oG}DtlIDF>$tJ1aw9^LuhLEHt?BCj& z(O4I8v1s#HUi5A>nIS-JK{v!7dJx)^Yg%XjNmlkWAq2*cv#tHgz`Y(bETc6CuO1VkN^L-L3j_x<4NqYb5rzrLC-7uOv z!5e`GZt%B782C5-fGnn*GhDF$%(qP<74Z}3xx+{$4cYKy2ikxI7B2N+2r07DN;|-T->nU&!=Cm#rZt%O_5c&1Z%nlWq3TKAW0w zQqemZw_ue--2uKQsx+niCUou?HjD`xhEjjQd3%rrBi82crq*~#uA4+>vR<_S{~5ce z-2EIl?~s z1=GVL{NxP1N3%=AOaC}j_Fv=ur&THz zyO!d9kHq|c73kpq`$+t+8Bw7MgeR5~`d7ChYyGCBWSteTB>8WAU(NPYt2Dk`@#+}= zI4SvLlyk#pBgVigEe`?NG*vl7V6m+<}%FwPV=~PvvA)=#ths==DRTDEYh4V5}Cf$z@#;< zyWfLY_5sP$gc3LLl2x+Ii)#b2nhNXJ{R~vk`s5U7Nyu^3yFg&D%Txwj6QezMX`V(x z=C`{76*mNb!qHHs)#GgGZ_7|vkt9izl_&PBrsu@}L`X{95-2jf99K)0=*N)VxBX2q z((vkpP2RneSIiIUEnGb?VqbMb=Zia+rF~+iqslydE34cSLJ&BJW^3knX@M;t*b=EA zNvGzv41Ld_T+WT#XjDB840vovUU^FtN_)G}7v)1lPetgpEK9YS^OWFkPoE{ovj^=@ zO9N$S=G$1ecndT_=5ehth2Lmd1II-PuT~C9`XVePw$y8J#dpZ?Tss<6wtVglm(Ok7 z3?^oi@pPio6l&!z8JY(pJvG=*pI?GIOu}e^EB6QYk$#FJQ%^AIK$I4epJ+9t?KjqA+bkj&PQ*|vLttme+`9G=L% ziadyMw_7-M)hS(3E$QGNCu|o23|%O+VN7;Qggp?PB3K-iSeBa2b}V4_wY`G1Jsfz4 z9|SdB^;|I8E8gWqHKx!vj_@SMY^hLEIbSMCuE?WKq=c2mJK z8LoG-pnY!uhqFv&L?yEuxo{dpMTsmCn)95xanqBrNPTgXP((H$9N${Ow~Is-FBg%h z53;|Y5$MUN)9W2HBe2TD`ct^LHI<(xWrw}$qSoei?}s)&w$;&!14w6B6>Yr6Y8b)S z0r71`WmAvJJ`1h&poLftLUS6Ir zC$bG9!Im_4Zjse)#K=oJM9mHW1{%l8sz$1o?ltdKlLTxWWPB>Vk22czVt|1%^wnN@*!l)}?EgtvhC>vlHm^t+ogpgHI1_$1ox9e;>0!+b(tBrmXRB`PY1vp-R**8N7 zGP|QqI$m(Rdu#=(?!(N}G9QhQ%o!aXE=aN{&wtGP8|_qh+7a_j_sU5|J^)vxq;# zjvzLn%_QPHZZIWu1&mRAj;Sa_97p_lLq_{~j!M9N^1yp3U_SxRqK&JnR%6VI#^E12 z>CdOVI^_9aPK2eZ4h&^{pQs}xsijXgFYRIxJ~N7&BB9jUR1fm!(xl)mvy|3e6-B3j zJn#ajL;bFTYJ2+Q)tDjx=3IklO@Q+FFM}6UJr6km7hj7th9n_&JR7fnqC!hTZoM~T zBeaVFp%)0cbPhejX<8pf5HyRUj2>aXnXBqDJe73~J%P(2C?-RT{c3NjE`)om! zl$uewSgWkE66$Kb34+QZZvRn`fob~Cl9=cRk@Es}KQm=?E~CE%spXaMO6YmrMl%9Q zlA3Q$3|L1QJ4?->UjT&CBd!~ru{Ih^in&JXO=|<6J!&qp zRe*OZ*cj5bHYlz!!~iEKcuE|;U4vN1rk$xq6>bUWD*u(V@8sG^7>kVuo(QL@Ki;yL zWC!FT(q{E8#on>%1iAS0HMZDJg{Z{^!De(vSIq&;1$+b)oRMwA3nc3mdTSG#3uYO_ z>+x;7p4I;uHz?ZB>dA-BKl+t-3IB!jBRgdvAbW!aJ(Q{aT>+iz?91`C-xbe)IBoND z9_Xth{6?(y3rddwY$GD65IT#f3<(0o#`di{sh2gm{dw*#-Vnc3r=4==&PU^hCv$qd zjw;>i&?L*Wq#TxG$mFIUf>eK+170KG;~+o&1;Tom9}}mKo23KwdEM6UonXgc z!6N(@k8q@HPw{O8O!lAyi{rZv|DpgfU{py+j(X_cwpKqcalcqKIr0kM^%Br3SdeD> zHSKV94Yxw;pjzDHo!Q?8^0bb%L|wC;4U^9I#pd5O&eexX+Im{ z?jKnCcsE|H?{uGMqVie_C~w7GX)kYGWAg%-?8|N_1#W-|4F)3YTDC+QSq1s!DnOML3@d`mG%o2YbYd#jww|jD$gotpa)kntakp#K;+yo-_ZF9qrNZw<%#C zuPE@#3RocLgPyiBZ+R_-FJ_$xP!RzWm|aN)S+{$LY9vvN+IW~Kf3TsEIvP+B9Mtm! zpfNNxObWQpLoaO&cJh5>%slZnHl_Q~(-Tfh!DMz(dTWld@LG1VRF`9`DYKhyNv z2pU|UZ$#_yUx_B_|MxUq^glT}O5Xt(Vm4Mr02><%C)@v;vPb@pT$*yzJ4aPc_FZ3z z3}PLoMBIM>q_9U2rl^sGhk1VUJ89=*?7|v`{!Z{6bqFMq(mYiA?%KbsI~JwuqVA9$H5vDE+VocjX+G^%bieqx->s;XWlKcuv(s%y%D5Xbc9+ zc(_2nYS1&^yL*ey664&4`IoOeDIig}y-E~_GS?m;D!xv5-xwz+G`5l6V+}CpeJDi^ z%4ed$qowm88=iYG+(`ld5Uh&>Dgs4uPHSJ^TngXP_V6fPyl~>2bhi20QB%lSd#yYn zO05?KT1z@?^-bqO8Cg`;ft>ilejsw@2%RR7;`$Vs;FmO(Yr3Fp`pHGr@P2hC%QcA|X&N2Dn zYf`MqXdHi%cGR@%y7Rg7?d3?an){s$zA{!H;Ie5exE#c~@NhQUFG8V=SQh%UxUeiV zd7#UcYqD=lk-}sEwlpu&H^T_V0{#G?lZMxL7ih_&{(g)MWBnCZxtXg znr#}>U^6!jA%e}@Gj49LWG@*&t0V>Cxc3?oO7LSG%~)Y5}f7vqUUnQ;STjdDU}P9IF9d9<$;=QaXc zL1^X7>fa^jHBu_}9}J~#-oz3Oq^JmGR#?GO7b9a(=R@fw@}Q{{@`Wy1vIQ#Bw?>@X z-_RGG@wt|%u`XUc%W{J z>iSeiz8C3H7@St3mOr_mU+&bL#Uif;+Xw-aZdNYUpdf>Rvu0i0t6k*}vwU`XNO2he z%miH|1tQ8~ZK!zmL&wa3E;l?!!XzgV#%PMVU!0xrDsNNZUWKlbiOjzH-1Uoxm8E#r`#2Sz;-o&qcqB zC-O_R{QGuynW14@)7&@yw1U}uP(1cov)twxeLus0s|7ayrtT8c#`&2~Fiu2=R;1_4bCaD=*E@cYI>7YSnt)nQc zohw5CsK%m?8Ack)qNx`W0_v$5S}nO|(V|RZKBD+btO?JXe|~^Qqur%@eO~<8-L^9d z=GA3-V14ng9L29~XJ>a5k~xT2152zLhM*@zlp2P5Eu}bywkcqR;ISbas&#T#;HZSf z2m69qTV(V@EkY(1Dk3`}j)JMo%ZVJ*5eB zYOjIisi+igK0#yW*gBGj?@I{~mUOvRFQR^pJbEbzFxTubnrw(Muk%}jI+vXmJ;{Q6 zrSobKD>T%}jV4Ub?L1+MGOD~0Ir%-`iTnWZN^~YPrcP5y3VMAzQ+&en^VzKEb$K!Q z<7Dbg&DNXuow*eD5yMr+#08nF!;%4vGrJI++5HdCFcGLfMW!KS*Oi@=7hFwDG!h2< zPunUEAF+HncQkbfFj&pbzp|MU*~60Z(|Ik%Tn{BXMN!hZOosNIseT?R;A`W?=d?5X zK(FB=9mZusYahp|K-wyb={rOpdn=@;4YI2W0EcbMKyo~-#^?h`BA9~o285%oY zfifCh5Lk$SY@|2A@a!T2V+{^!psQkx4?x0HSV`(w9{l75QxMk!)U52Lbhn{8ol?S) zCKo*7R(z!uk<6*qO=wh!Pul{(qq6g6xW;X68GI_CXp`XwO zxuSgPRAtM8K7}5E#-GM!*ydOOG_{A{)hkCII<|2=ma*71ci_-}VPARm3crFQjLYV! z9zbz82$|l01mv`$WahE2$=fAGWkd^X2kY(J7iz}WGS z@%MyBEO=A?HB9=^?nX`@nh;7;laAjs+fbo!|K^mE!tOB>$2a_O0y-*uaIn8k^6Y zSbuv;5~##*4Y~+y7Z5O*3w4qgI5V^17u*ZeupVGH^nM&$qmAk|anf*>r zWc5CV;-JY-Z@Uq1Irpb^O`L_7AGiqd*YpGUShb==os$uN3yYvb`wm6d=?T*it&pDk zo`vhw)RZX|91^^Wa_ti2zBFyWy4cJu#g)_S6~jT}CC{DJ_kKpT`$oAL%b^!2M;JgT zM3ZNbUB?}kP(*YYvXDIH8^7LUxz5oE%kMhF!rnPqv!GiY0o}NR$OD=ITDo9r%4E>E0Y^R(rS^~XjWyVI6 zMOR5rPXhTp*G*M&X#NTL`Hu*R+u*QNoiOKg4CtNPrjgH>c?Hi4MUG#I917fx**+pJfOo!zFM&*da&G_x)L(`k&TPI*t3e^{crd zX<4I$5nBQ8Ax_lmNRa~E*zS-R0sxkz`|>7q_?*e%7bxqNm3_eRG#1ae3gtV9!fQpY z+!^a38o4ZGy9!J5sylDxZTx$JmG!wg7;>&5H1)>f4dXj;B+@6tMlL=)cLl={jLMxY zbbf1ax3S4>bwB9-$;SN2?+GULu;UA-35;VY*^9Blx)Jwyb$=U!D>HhB&=jSsd^6yw zL)?a|>GxU!W}ocTC(?-%z3!IUhw^uzc`Vz_g>-tv)(XA#JK^)ZnC|l1`@CdX1@|!| z_9gQ)7uOf?cR@KDp97*>6X|;t@Y`k_N@)aH7gY27)COv^P3ya9I{4z~vUjLR9~z1Z z5=G{mVtKH*&$*t0@}-i_v|3B$AHHYale7>E+jP`ClqG%L{u;*ff_h@)al?RuL7tOO z->;I}>%WI{;vbLP3VIQ^iA$4wl6@0sDj|~112Y4OFjMs`13!$JGkp%b&E8QzJw_L5 zOnw9joc0^;O%OpF$Qp)W1HI!$4BaXX84`%@#^dk^hFp^pQ@rx4g(8Xjy#!X%+X5Jd@fs3amGT`}mhq#L97R>OwT5-m|h#yT_-v@(k$q7P*9X~T*3)LTdzP!*B} z+SldbVWrrwQo9wX*%FyK+sRXTa@O?WM^FGWOE?S`R(0P{<6p#f?0NJvnBia?k^fX2 zNQs7K-?EijgHJY}&zsr;qJ<*PCZUd*x|dD=IQPUK_nn)@X4KWtqoJNHkT?ZWL_hF? zS8lp2(q>;RXR|F;1O}EE#}gCrY~#n^O`_I&?&z5~7N;zL0)3Tup`%)oHMK-^r$NT% zbFg|o?b9w(q@)6w5V%si<$!U<#}s#x@0aX-hP>zwS#9*75VXA4K*%gUc>+yzupTDBOKH8WR4V0pM(HrfbQ&eJ79>HdCvE=F z|J>s;;iDLB^3(9}?biKbxf1$lI!*Z%*0&8UUq}wMyPs_hclyQQi4;NUY+x2qy|0J; zhn8;5)4ED1oHwg+VZF|80<4MrL97tGGXc5Sw$wAI#|2*cvQ=jB5+{AjMiDHmhUC*a zlmiZ`LAuAn_}hftXh;`Kq0zblDk8?O-`tnilIh|;3lZp@F_osJUV9`*R29M?7H{Fy z`nfVEIDIWXmU&YW;NjU8)EJpXhxe5t+scf|VXM!^bBlwNh)~7|3?fWwo_~ZFk(22% zTMesYw+LNx3J-_|DM~`v93yXe=jPD{q;li;5PD?Dyk+b? zo21|XpT@)$BM$%F=P9J19Vi&1#{jM3!^Y&fr&_`toi`XB1!n>sbL%U9I5<7!@?t)~ z;&H%z>bAaQ4f$wIzkjH70;<8tpUoxzKrPhn#IQfS%9l5=Iu))^XC<58D!-O z{B+o5R^Z21H0T9JQ5gNJnqh#qH^na|z92=hONIM~@_iuOi|F>jBh-?aA20}Qx~EpDGElELNn~|7WRXRFnw+Wdo`|# zBpU=Cz3z%cUJ0mx_1($X<40XEIYz(`noWeO+x#yb_pwj6)R(__%@_Cf>txOQ74wSJ z0#F3(zWWaR-jMEY$7C*3HJrohc79>MCUu26mfYN)f4M~4gD`}EX4e}A!U}QV8!S47 z6y-U-%+h`1n`*pQuKE%Av0@)+wBZr9mH}@vH@i{v(m-6QK7Ncf17x_D=)32`FOjjo zg|^VPf5c6-!FxN{25dvVh#fog=NNpXz zfB$o+0jbRkHH{!TKhE709f+jI^$3#v1Nmf80w`@7-5$1Iv_`)W^px8P-({xwb;D0y z7LKDAHgX<84?l!I*Dvi2#D@oAE^J|g$3!)x1Ua;_;<@#l1fD}lqU2_tS^6Ht$1Wl} zBESo7o^)9-Tjuz$8YQSGhfs{BQV6zW7dA?0b(Dbt=UnQs&4zHfe_sj{RJ4uS-vQpC zX;Bbsuju4%!o8?&m4UZU@~ZZjeFF6ex2ss5_60_JS_|iNc+R0GIjH1@Z z=rLT9%B|WWgOrR7IiIwr2=T;Ne?30M!@{%Qf8o`!>=s<2CBpCK_TWc(DX51>e^xh8 z&@$^b6CgOd7KXQV&Y4%}_#uN*mbanXq(2=Nj`L7H7*k(6F8s6{FOw@(DzU`4-*77{ zF+dxpv}%mFpYK?>N_2*#Y?oB*qEKB}VoQ@bzm>ptmVS_EC(#}Lxxx730trt0G)#$b zE=wVvtqOct1%*9}U{q<)2?{+0TzZzP0jgf9*)arV)*e!f`|jgT{7_9iS@e)recI#z zbzolURQ+TOzE!ymqvBY7+5NnAbWxvMLsLTwEbFqW=CPyCsmJ}P1^V30|D5E|p3BC5 z)3|qgw@ra7aXb-wsa|l^in~1_fm{7bS9jhVRkYVO#U{qMp z)Wce+|DJ}4<2gp8r0_xfZpMo#{Hl2MfjLcZdRB9(B(A(f;+4s*FxV{1F|4d`*sRNd zp4#@sEY|?^FIJ;tmH{@keZ$P(sLh5IdOk@k^0uB^BWr@pk6mHy$qf&~rI>P*a;h0C{%oA*i!VjWn&D~O#MxN&f@1Po# zKN+ zrGrkSjcr?^R#nGl<#Q722^wbYcgW@{+6CBS<1@%dPA8HC!~a`jTz<`g_l5N1M@9wn9GOAZ>nqNgq!yOCbZ@1z`U_N`Z>}+1HIZxk*5RDc&rd5{3qjRh8QmT$VyS;jK z;AF+r6XnnCp=wQYoG|rT2@8&IvKq*IB_WvS%nt%e{MCFm`&W*#LXc|HrD?nVBo=(8*=Aq?u$sDA_sC_RPDUiQ+wnIJET8vx$&fxkW~kP9qXKt zozR)@xGC!P)CTkjeWvXW5&@2?)qt)jiYWWBU?AUtzAN}{JE1I)dfz~7$;}~BmQF`k zpn11qmObXwRB8&rnEG*#4Xax3XBkKlw(;tb?Np^i+H8m(Wyz9k{~ogba@laiEk;2! zV*QV^6g6(QG%vX5Um#^sT&_e`B1pBW5yVth~xUs#0}nv?~C#l?W+9Lsb_5)!71rirGvY zTIJ$OPOY516Y|_014sNv+Z8cc5t_V=i>lWV=vNu#!58y9Zl&GsMEW#pPYPYGHQ|;vFvd*9eM==$_=vc7xnyz0~ zY}r??$<`wAO?JQk@?RGvkWVJlq2dk9vB(yV^vm{=NVI8dhsX<)O(#nr9YD?I?(VmQ z^r7VfUBn<~p3()8yOBjm$#KWx!5hRW)5Jl7wY@ky9lNM^jaT##8QGVsYeaVywmpv>X|Xj7gWE1Ezai&wVLt3p)k4w~yrskT-!PR!kiyQlaxl(( zXhF%Q9x}1TMt3~u@|#wWm-Vq?ZerK={8@~&@9r5JW}r#45#rWii};t`{5#&3$W)|@ zbAf2yDNe0q}NEUvq_Quq3cTjcw z@H_;$hu&xllCI9CFDLuScEMg|x{S7GdV8<&Mq=ezDnRZAyX-8gv97YTm0bg=d)(>N z+B2FcqvI9>jGtnK%eO%y zoBPkJTk%y`8TLf4)IXPBn`U|9>O~WL2C~C$z~9|0m*YH<-vg2CD^SX#&)B4ngOSG$ zV^wmy_iQk>dfN@Pv(ckfy&#ak@MLC7&Q6Ro#!ezM*VEh`+b3Jt%m(^T&p&WJ2Oqvj zs-4nq0TW6cv~(YI$n0UkfwN}kg3_fp?(ijSV#tR9L0}l2qjc7W?i*q01=St0eZ=4h zyGQbEw`9OEH>NMuIe)hVwYHsGERWOD;JxEiO7cQv%pFCeR+IyhwQ|y@&^24k+|8fD zLiOWFNJ2&vu2&`Jv96_z-Cd5RLgmeY3*4rDOQo?Jm`;I_(+ejsPM03!ly!*Cu}Cco zrQSrEDHNyzT(D5s1rZq!8#?f6@v6dB7a-aWs(Qk>N?UGAo{gytlh$%_IhyL7h?DLXDGx zgxGEBQoCAWo-$LRvM=F5MTle`M})t3vVv;2j0HZY&G z22^iGhV@uaJh(XyyY%} zd4iH_UfdV#T=3n}(Lj^|n;O4|$;xhu*8T3hR1mc_A}fK}jfZ7LX~*n5+`8N2q#rI$ z@<_2VANlYF$vIH$ zl<)+*tIWW78IIINA7Rr7i{<;#^yzxoLNkXL)eSs=%|P>$YQIh+ea_3k z_s7r4%j7%&*NHSl?R4k%1>Z=M9o#zxY!n8sL5>BO-ZP;T3Gut>iLS@U%IBrX6BA3k z)&@q}V8a{X<5B}K5s(c(LQ=%v1ocr`t$EqqY0EqVjr65usa=0bkf|O#ky{j3)WBR(((L^wmyHRzoWuL2~WTC=`yZ zn%VX`L=|Ok0v7?s>IHg?yArBcync5rG#^+u)>a%qjES%dRZoIyA8gQ;StH z1Ao7{<&}6U=5}4v<)1T7t!J_CL%U}CKNs-0xWoTTeqj{5{?Be$L0_tk>M9o8 zo371}S#30rKZFM{`H_(L`EM9DGp+Mifk&IP|C2Zu_)Ghr4Qtpmkm1osCf@%Z$%t+7 zYH$Cr)Ro@3-QDeQJ8m+x6%;?YYT;k6Z0E-?kr>x33`H%*ueBD7Zx~3&HtWn0?2Wt} zTG}*|v?{$ajzt}xPzV%lL1t-URi8*Zn)YljXNGDb>;!905Td|mpa@mHjIH%VIiGx- zd@MqhpYFu4_?y5N4xiHn3vX&|e6r~Xt> zZG`aGq|yTNjv;9E+Txuoa@A(9V7g?1_T5FzRI;!=NP1Kqou1z5?%X~Wwb{trRfd>i z8&y^H)8YnKyA_Fyx>}RNmQIczT?w2J4SNvI{5J&}Wto|8FR(W;Qw#b1G<1%#tmYzQ zQ2mZA-PAdi%RQOhkHy9Ea#TPSw?WxwL@H@cbkZwIq0B!@ns}niALidmn&W?!Vd4Gj zO7FiuV4*6Mr^2xlFSvM;Cp_#r8UaqIzHJQg_z^rEJw&OMm_8NGAY2)rKvki|o1bH~ z$2IbfVeY2L(^*rMRU1lM5Y_sgrDS`Z??nR2lX;zyR=c%UyGb*%TC-Dil?SihkjrQy~TMv6;BMs7P8il`H7DmpVm@rJ;b)hW)BL)GjS154b*xq-NXq2cwE z^;VP7ua2pxvCmxrnqUYQMH%a%nHmwmI33nJM(>4LznvY*k&C0{8f*%?zggpDgkuz&JBx{9mfb@wegEl2v!=}Sq2Gaty0<)UrOT0{MZtZ~j5y&w zXlYa_jY)I_+VA-^#mEox#+G>UgvM!Ac8zI<%JRXM_73Q!#i3O|)lOP*qBeJG#BST0 zqohi)O!|$|2SeJQo(w6w7%*92S})XfnhrH_Z8qe!G5>CglP=nI7JAOW?(Z29;pXJ9 zR9`KzQ=WEhy*)WH>$;7Cdz|>*i>=##0bB)oU0OR>>N<21e4rMCHDemNi2LD>Nc$;& zQRFthpWniC1J6@Zh~iJCoLOxN`oCKD5Q4r%ynwgUKPlIEd#?QViIqovY|czyK8>6B zSP%{2-<;%;1`#0mG^B(8KbtXF;Nf>K#Di72UWE4gQ%(_26Koiad)q$xRL~?pN71ZZ zujaaCx~jXjygw;rI!WB=xrOJO6HJ!!w}7eiivtCg5K|F6$EXa)=xUC za^JXSX98W`7g-tm@uo|BKj39Dl;sg5ta;4qjo^pCh~{-HdLl6qI9Ix6f$+qiZ$}s= zNguKrU;u+T@ko(Vr1>)Q%h$?UKXCY>3se%&;h2osl2D zE4A9bd7_|^njDd)6cI*FupHpE3){4NQ*$k*cOWZ_?CZ>Z4_fl@n(mMnYK62Q1d@+I zr&O))G4hMihgBqRIAJkLdk(p(D~X{-oBUA+If@B}j& zsHbeJ3RzTq96lB7d($h$xTeZ^gP0c{t!Y0c)aQE;$FY2!mACg!GDEMKXFOPI^)nHZ z`aSPJpvV0|bbrzhWWkuPURlDeN%VT8tndV8?d)eN*i4I@u zVKl^6{?}A?P)Fsy?3oi#clf}L18t;TjNI2>eI&(ezDK7RyqFxcv%>?oxUlonv(px) z$vnPzRH`y5A(x!yOIfL0bmgeMQB$H5wenx~!ujQK*nUBW;@Em&6Xv2%s(~H5WcU2R z;%Nw<$tI)a`Ve!>x+qegJnQsN2N7HaKzrFqM>`6R*gvh%O*-%THt zrB$Nk;lE;z{s{r^PPm5qz(&lM{sO*g+W{sK+m3M_z=4=&CC>T`{X}1Vg2PEfSj2x_ zmT*(x;ov%3F?qoEeeM>dUn$a*?SIGyO8m806J1W1o+4HRhc2`9$s6hM#qAm zChQ87b~GEw{ADfs+5}FJ8+|bIlIv(jT$Ap#hSHoXdd9#w<#cA<1Rkq^*EEkknUd4& zoIWIY)sAswy6fSERVm&!SO~#iN$OgOX*{9@_BWFyJTvC%S++ilSfCrO(?u=Dc?CXZ zzCG&0yVR{Z`|ZF0eEApWEo#s9osV>F{uK{QA@BES#&;#KsScf>y zvs?vIbI>VrT<*!;XmQS=bhq%46-aambZ(8KU-wOO2=en~D}MCToB_u;Yz{)1ySrPZ z@=$}EvjTdzTWU7c0ZI6L8=yP+YRD_eMMos}b5vY^S*~VZysrkq<`cK3>>v%uy7jgq z0ilW9KjVDHLv0b<1K_`1IkbTOINs0=m-22c%M~l=^S}%hbli-3?BnNq?b`hx^HX2J zIe6ECljRL0uBWb`%{EA=%!i^4sMcj+U_TaTZRb+~GOk z^ZW!nky0n*Wb*r+Q|9H@ml@Z5gU&W`(z4-j!OzC1wOke`TRAYGZVl$PmQ16{3196( zO*?`--I}Qf(2HIwb2&1FB^!faPA2=sLg(@6P4mN)>Dc3i(B0;@O-y2;lM4akD>@^v z=u>*|!s&9zem70g7zfw9FXl1bpJW(C#5w#uy5!V?Q(U35A~$dR%LDVnq@}kQm13{} zd53q3N(s$Eu{R}k2esbftfjfOITCL;jWa$}(mmm}d(&7JZ6d3%IABCapFFYjdEjdK z&4Edqf$G^MNAtL=uCDRs&Fu@FXRgX{*0<(@c3|PNHa>L%zvxWS={L8%qw`STm+=Rd zA}FLspESSIpE_^41~#5yI2bJ=9`oc;GIL!JuW&7YetZ?0H}$$%8rW@*J37L-~Rsx!)8($nI4 zZhcZ2^=Y+p4YPl%j!nFJA|*M^gc(0o$i3nlphe+~-_m}jVkRN{spFs(o0ajW@f3K{ zDV!#BwL322CET$}Y}^0ixYj2w>&Xh12|R8&yEw|wLDvF!lZ#dOTHM9pK6@Nm-@9Lnng4ZHBgBSrr7KI8YCC9DX5Kg|`HsiwJHg2(7#nS;A{b3tVO?Z% za{m5b3rFV6EpX;=;n#wltDv1LE*|g5pQ+OY&*6qCJZc5oDS6Z6JD#6F)bWxZSF@q% z+1WV;m!lRB!n^PC>RgQCI#D1br_o^#iPk>;K2hB~0^<~)?p}LG%kigm@moD#q3PE+ zA^Qca)(xnqw6x>XFhV6ku9r$E>bWNrVH9fum0?4s?Rn2LG{Vm_+QJHse6xa%nzQ?k zKug4PW~#Gtb;#5+9!QBgyB@q=sk9=$S{4T>wjFICStOM?__fr+Kei1 z3j~xPqW;W@YkiUM;HngG!;>@AITg}vAE`M2Pj9Irl4w1fo4w<|Bu!%rh%a(Ai^Zhi zs92>v5;@Y(Zi#RI*ua*h`d_7;byQSa*v9E{2x$<-_=5Z<7{%)}4XExANcz@rK69T0x3%H<@frW>RA8^swA+^a(FxK| zFl3LD*ImHN=XDUkrRhp6RY5$rQ{bRgSO*(vEHYV)3Mo6Jy3puiLmU&g82p{qr0F?ohmbz)f2r{X2|T2 z$4fdQ=>0BeKbiVM!e-lIIs8wVTuC_m7}y4A_%ikI;Wm5$9j(^Y z(cD%U%k)X>_>9~t8;pGzL6L-fmQO@K; zo&vQzMlgY95;1BSkngY)e{`n0!NfVgf}2mB3t}D9@*N;FQ{HZ3Pb%BK6;5#-O|WI( zb6h@qTLU~AbVW#_6?c!?Dj65Now7*pU{h!1+eCV^KCuPAGs28~3k@ueL5+u|Z-7}t z9|lskE`4B7W8wMs@xJa{#bsCGDFoRSNSnmNYB&U7 zVGKWe%+kFB6kb)e;TyHfqtU6~fRg)f|>=5(N36)0+C z`hv65J<$B}WUc!wFAb^QtY31yNleq4dzmG`1wHTj=c*=hay9iD071Hc?oYoUk|M*_ zU1GihAMBsM@5rUJ(qS?9ZYJ6@{bNqJ`2Mr+5#hKf?doa?F|+^IR!8lq9)wS3tF_9n zW_?hm)G(M+MYb?V9YoX^_mu5h-LP^TL^!Q9Z7|@sO(rg_4+@=PdI)WL(B7`!K^ND- z-uIuVDCVEdH_C@c71YGYT^_Scf_dhB8Z2Xy6vGtBSlYud9vggOqv^L~F{BraSE_t} zIkP+Hp2&nH^-MNEs}^`oMLy11`PQW$T|K(`Bu*(f@)mv1-qY(_YG&J2M2<7k;;RK~ zL{Fqj9yCz8(S{}@c)S!65aF<=&eLI{hAMErCx&>i7OeDN>okvegO87OaG{Jmi<|}D zaT@b|0X{d@OIJ7zvT>r+eTzgLq~|Dpu)Z&db-P4z*`M$UL51lf>FLlq6rfG)%doyp z)3kk_YIM!03eQ8Vu_2fg{+osaEJPtJ-s36R+5_AEG12`NG)IQ#TF9c@$99%0iye+ zUzZ57=m2)$D(5Nx!n)=5Au&O0BBgwxIBaeI(mro$#&UGCr<;C{UjJVAbVi%|+WP(a zL$U@TYCxJ=1{Z~}rnW;7UVb7+ZnzgmrogDxhjLGo>c~MiJAWs&&;AGg@%U?Y^0JhL ze(x6Z74JG6FlOFK(T}SXQfhr}RIFl@QXKnIcXYF)5|V~e-}suHILKT-k|<*~Ij|VF zC;t@=uj=hot~*!C68G8hTA%8SzOfETOXQ|3FSaIEjvBJp(A)7SWUi5!Eu#yWgY+;n zlm<$+UDou*V+246_o#V4kMdto8hF%%Lki#zPh}KYXmMf?hrN0;>Mv%`@{0Qn`Ujp) z=lZe+13>^Q!9zT);H<(#bIeRWz%#*}sgUX9P|9($kexOyKIOc`dLux}c$7It4u|Rl z6SSkY*V~g_B-hMPo_ak>>z@AVQ(_N)VY2kB3IZ0G(iDUYw+2d7W^~(Jq}KY=JnWS( z#rzEa&0uNhJ>QE8iiyz;n2H|SV#Og+wEZv=f2%1ELX!SX-(d3tEj$5$1}70Mp<&eI zCkfbByL7af=qQE@5vDVxx1}FSGt_a1DoE3SDI+G)mBAna)KBG4p8Epxl9QZ4BfdAN zFnF|Y(umr;gRgG6NLQ$?ZWgllEeeq~z^ZS7L?<(~O&$5|y)Al^iMKy}&W+eMm1W z7EMU)u^ke(A1#XCV>CZ71}P}0x)4wtHO8#JRG3MA-6g=`ZM!FcICCZ{IEw8Dm2&LQ z1|r)BUG^0GzI6f946RrBlfB1Vs)~8toZf~7)+G;pv&XiUO(%5bm)pl=p>nV^o*;&T z;}@oZSibzto$arQgfkp|z4Z($P>dTXE{4O=vY0!)kDO* zGF8a4wq#VaFpLfK!iELy@?-SeRrdz%F*}hjKcA*y@mj~VD3!it9lhRhX}5YOaR9$} z3mS%$2Be7{l(+MVx3 z(4?h;P!jnRmX9J9sYN#7i=iyj_5q7n#X(!cdqI2lnr8T$IfOW<_v`eB!d9xY1P=2q&WtOXY=D9QYteP)De?S4}FK6#6Ma z=E*V+#s8>L;8aVroK^6iKo=MH{4yEZ_>N-N z`(|;aOATba1^asjxlILk<4}f~`39dBFlxj>Dw(hMYKPO3EEt1@S`1lxFNM+J@uB7T zZ8WKjz7HF1-5&2=l=fqF-*@>n5J}jIxdDwpT?oKM3s8Nr`x8JnN-kCE?~aM1H!hAE z%%w(3kHfGwMnMmNj(SU(w42OrC-euI>Dsjk&jz3ts}WHqmMpzQ3vZrsXrZ|}+MHA7 z068obeXZTsO*6RS@o3x80E4ok``rV^Y3hr&C1;|ZZ0|*EKO`$lECUYG2gVFtUTw)R z4Um<0ZzlON`zTdvVdL#KFoMFQX*a5wM0Czp%wTtfK4Sjs)P**RW&?lP$(<}q%r68Z zS53Y!d@&~ne9O)A^tNrXHhXBkj~$8j%pT1%%mypa9AW5E&s9)rjF4@O3ytH{0z6riz|@< zB~UPh*wRFg2^7EbQrHf0y?E~dHlkOxof_a?M{LqQ^C!i2dawHTPYUE=X@2(3<=OOxs8qn_(y>pU>u^}3y&df{JarR0@VJn0f+U%UiF=$Wyq zQvnVHESil@d|8&R<%}uidGh7@u^(%?$#|&J$pvFC-n8&A>utA=n3#)yMkz+qnG3wd zP7xCnF|$9Dif@N~L)Vde3hW8W!UY0BgT2v(wzp;tlLmyk2%N|0jfG$%<;A&IVrOI< z!L)o>j>;dFaqA3pL}b-Je(bB@VJ4%!JeX@3x!i{yIeIso^=n?fDX`3bU=eG7sTc%g%ye8$v8P@yKE^XD=NYxTb zbf!Mk=h|otpqjFaA-vs5YOF-*GwWPc7VbaOW&stlANnCN8iftFMMrUdYNJ_Bnn5Vt zxfz@Ah|+4&P;reZxp;MmEI7C|FOv8NKUm8njF7Wb6Gi7DeODLl&G~}G4be&*Hi0Qw z5}77vL0P+7-B%UL@3n1&JPxW^d@vVwp?u#gVcJqY9#@-3X{ok#UfW3<1fb%FT`|)V~ggq z(3AUoUS-;7)^hCjdT0Kf{i}h)mBg4qhtHHBti=~h^n^OTH5U*XMgDLIR@sre`AaB$ zg)IGBET_4??m@cx&c~bA80O7B8CHR7(LX7%HThkeC*@vi{-pL%e)yXp!B2InafbDF zjPXf1mko3h59{lT6EEbxKO1Z5GF71)WwowO6kY|6tjSVSWdQ}NsK2x{>i|MKZK8%Q zfu&_0D;CO-Jg0#YmyfctyJ!mRJp)e#@O0mYdp|8x;G1%OZQ3Q847YWTyy|%^cpA;m zze0(5p{tMu^lDkpe?HynyO?a1$_LJl2L&mpeKu%8YvgRNr=%2z${%WThHG=vrWY@4 zsA`OP#O&)TetZ>s%h!=+CE15lOOls&nvC~$Qz0Ph7tHiP;O$i|eDwpT{cp>+)0-|; zY$|bB+Gbel>5aRN3>c0x)4U=|X+z+{ zn*_p*EQoquRL+=+p;=lm`d71&1NqBz&_ph)MXu(Nv6&XE7(RsS)^MGj5Q?Fwude-(sq zjJ>aOq!7!EN>@(fK7EE#;i_BGvli`5U;r!YA{JRodLBc6-`n8K+Fjgwb%sX;j=qHQ z7&Tr!)!{HXoO<2BQrV9Sw?JRaLXV8HrsNevvnf>Y-6|{T!pYLl7jp$-nEE z#X!4G4L#K0qG_4Z;Cj6=;b|Be$hi4JvMH!-voxqx^@8cXp`B??eFBz2lLD8RRaRGh zn7kUfy!YV~p(R|p7iC1Rdgt$_24i0cd-S8HpG|`@my70g^y`gu%#Tf_L21-k?sRRZHK&at(*ED0P8iw{7?R$9~OF$Ko;Iu5)ur5<->x!m93Eb zFYpIx60s=Wxxw=`$aS-O&dCO_9?b1yKiPCQmSQb>T)963`*U+Ydj5kI(B(B?HNP8r z*bfSBpSu)w(Z3j7HQoRjUG(+d=IaE~tv}y14zHHs|0UcN52fT8V_<@2ep_ee{QgZG zmgp8iv4V{k;~8@I%M3<#B;2R>Ef(Gg_cQM7%}0s*^)SK6!Ym+~P^58*wnwV1BW@eG z4sZLqsUvBbFsr#8u7S1r4teQ;t)Y@jnn_m5jS$CsW1um!p&PqAcc8!zyiXHVta9QC zY~wCwCF0U%xiQPD_INKtTb;A|Zf29(mu9NI;E zc-e>*1%(LSXB`g}kd`#}O;veb<(sk~RWL|f3ljxCnEZDdNSTDV6#Td({6l&y4IjKF z^}lIUq*ZUqgTPumD)RrCN{M^jhY>E~1pn|KOZ5((%F)G|*ZQ|r4zIbrEiV%42hJV8 z3xS)=!X1+=olbdGJ=yZil?oXLct8FM{(6ikLL3E%=q#O6(H$p~gQu6T8N!plf!96| z&Q3=`L~>U0zZh;z(pGR2^S^{#PrPxTRHD1RQOON&f)Siaf`GLj#UOk&(|@0?zm;Sx ztsGt8=29-MZs5CSf1l1jNFtNt5rFNZxJPvkNu~2}7*9468TWm>nN9TP&^!;J{-h)_ z7WsHH9|F%I`Pb!>KAS3jQWKfGivTVkMJLO-HUGM_a4UQ_%RgL6WZvrW+Z4ujZn;y@ zz9$=oO!7qVTaQAA^BhX&ZxS*|5dj803M=k&2%QrXda`-Q#IoZL6E(g+tN!6CA!CP* zCpWtCujIea)ENl0liwVfj)Nc<9mV%+e@=d`haoZ*`B7+PNjEbXBkv=B+Pi^~L#EO$D$ZqTiD8f<5$eyb54-(=3 zh)6i8i|jp(@OnRrY5B8t|LFXFQVQ895n*P16cEKTrT*~yLH6Z4e*bZ5otpRDri&+A zfNbK1D5@O=sm`fN=WzWyse!za5n%^+6dHPGX#8DyIK>?9qyX}2XvBWVqbP%%D)7$= z=#$WulZlZR<{m#gU7lwqK4WS1Ne$#_P{b17qe$~UOXCl>5b|6WVh;5vVnR<%d+Lnp z$uEmML38}U4vaW8>shm6CzB(Wei3s#NAWE3)a2)z@i{4jTn;;aQS)O@l{rUM`J@K& l00vQ5JBs~;vo!vr%%-k{2_Fq1Mn4QF81S)AQ99zk{{c4yR+0b! literal 63721 zcmb5Wb9gP!wgnp7wrv|bwr$&XvSZt}Z6`anZSUAlc9NHKf9JdJ;NJVr`=eI(_pMp0 zy1VAAG3FfAOI`{X1O)&90s;U4K;XLp008~hCjbEC_fbYfS%6kTR+JtXK>nW$ZR+`W ze|#J8f4A@M|F5BpfUJb5h>|j$jOe}0oE!`Zf6fM>CR?!y@zU(cL8NsKk`a z6tx5mAkdjD;J=LcJ;;Aw8p!v#ouk>mUDZF@ zK>yvw%+bKu+T{Nk@LZ;zkYy0HBKw06_IWcMHo*0HKpTsEFZhn5qCHH9j z)|XpN&{`!0a>Vl+PmdQc)Yg4A(AG-z!+@Q#eHr&g<9D?7E)_aEB?s_rx>UE9TUq|? z;(ggJt>9l?C|zoO@5)tu?EV0x_7T17q4fF-q3{yZ^ipUbKcRZ4Qftd!xO(#UGhb2y>?*@{xq%`(-`2T^vc=#< zx!+@4pRdk&*1ht2OWk^Z5IAQ0YTAXLkL{(D*$gENaD)7A%^XXrCchN&z2x+*>o2FwPFjWpeaL=!tzv#JOW#( z$B)Nel<+$bkH1KZv3&-}=SiG~w2sbDbAWarg%5>YbC|}*d9hBjBkR(@tyM0T)FO$# zPtRXukGPnOd)~z=?avu+4Co@wF}1T)-uh5jI<1$HLtyDrVak{gw`mcH@Q-@wg{v^c zRzu}hMKFHV<8w}o*yg6p@Sq%=gkd~;`_VGTS?L@yVu`xuGy+dH6YOwcP6ZE`_0rK% zAx5!FjDuss`FQ3eF|mhrWkjux(Pny^k$u_)dyCSEbAsecHsq#8B3n3kDU(zW5yE|( zgc>sFQywFj5}U*qtF9Y(bi*;>B7WJykcAXF86@)z|0-Vm@jt!EPoLA6>r)?@DIobIZ5Sx zsc@OC{b|3%vaMbyeM|O^UxEYlEMHK4r)V-{r)_yz`w1*xV0|lh-LQOP`OP`Pk1aW( z8DSlGN>Ts|n*xj+%If~+E_BxK)~5T#w6Q1WEKt{!Xtbd`J;`2a>8boRo;7u2M&iOop4qcy<)z023=oghSFV zST;?S;ye+dRQe>ygiJ6HCv4;~3DHtJ({fWeE~$H@mKn@Oh6Z(_sO>01JwH5oA4nvK zr5Sr^g+LC zLt(i&ecdmqsIJGNOSUyUpglvhhrY8lGkzO=0USEKNL%8zHshS>Qziu|`eyWP^5xL4 zRP122_dCJl>hZc~?58w~>`P_s18VoU|7(|Eit0-lZRgLTZKNq5{k zE?V=`7=R&ro(X%LTS*f+#H-mGo_j3dm@F_krAYegDLk6UV{`UKE;{YSsn$ z(yz{v1@p|p!0>g04!eRSrSVb>MQYPr8_MA|MpoGzqyd*$@4j|)cD_%^Hrd>SorF>@ zBX+V<@vEB5PRLGR(uP9&U&5=(HVc?6B58NJT_igiAH*q~Wb`dDZpJSKfy5#Aag4IX zj~uv74EQ_Q_1qaXWI!7Vf@ZrdUhZFE;L&P_Xr8l@GMkhc#=plV0+g(ki>+7fO%?Jb zl+bTy7q{w^pTb{>(Xf2q1BVdq?#f=!geqssXp z4pMu*q;iiHmA*IjOj4`4S&|8@gSw*^{|PT}Aw~}ZXU`6=vZB=GGeMm}V6W46|pU&58~P+?LUs%n@J}CSrICkeng6YJ^M? zS(W?K4nOtoBe4tvBXs@@`i?4G$S2W&;$z8VBSM;Mn9 zxcaEiQ9=vS|bIJ>*tf9AH~m&U%2+Dim<)E=}KORp+cZ^!@wI`h1NVBXu{@%hB2Cq(dXx_aQ9x3mr*fwL5!ZryQqi|KFJuzvP zK1)nrKZ7U+B{1ZmJub?4)Ln^J6k!i0t~VO#=q1{?T)%OV?MN}k5M{}vjyZu#M0_*u z8jwZKJ#Df~1jcLXZL7bnCEhB6IzQZ-GcoQJ!16I*39iazoVGugcKA{lhiHg4Ta2fD zk1Utyc5%QzZ$s3;p0N+N8VX{sd!~l*Ta3|t>lhI&G`sr6L~G5Lul`>m z{!^INm?J|&7X=;{XveF!(b*=?9NAp4y&r&N3(GKcW4rS(Ejk|Lzs1PrxPI_owB-`H zg3(Rruh^&)`TKA6+_!n>RdI6pw>Vt1_j&+bKIaMTYLiqhZ#y_=J8`TK{Jd<7l9&sY z^^`hmi7^14s16B6)1O;vJWOF$=$B5ONW;;2&|pUvJlmeUS&F;DbSHCrEb0QBDR|my zIs+pE0Y^`qJTyH-_mP=)Y+u^LHcuZhsM3+P||?+W#V!_6E-8boP#R-*na4!o-Q1 zVthtYhK{mDhF(&7Okzo9dTi03X(AE{8cH$JIg%MEQca`S zy@8{Fjft~~BdzWC(di#X{ny;!yYGK9b@=b|zcKZ{vv4D8i+`ilOPl;PJl{!&5-0!w z^fOl#|}vVg%=n)@_e1BrP)`A zKPgs`O0EO}Y2KWLuo`iGaKu1k#YR6BMySxQf2V++Wo{6EHmK>A~Q5o73yM z-RbxC7Qdh0Cz!nG+7BRZE>~FLI-?&W_rJUl-8FDIaXoNBL)@1hwKa^wOr1($*5h~T zF;%f^%<$p8Y_yu(JEg=c_O!aZ#)Gjh$n(hfJAp$C2he555W5zdrBqjFmo|VY+el;o z=*D_w|GXG|p0**hQ7~9-n|y5k%B}TAF0iarDM!q-jYbR^us(>&y;n^2l0C%@2B}KM zyeRT9)oMt97Agvc4sEKUEy%MpXr2vz*lb zh*L}}iG>-pqDRw7ud{=FvTD?}xjD)w{`KzjNom-$jS^;iw0+7nXSnt1R@G|VqoRhE%12nm+PH?9`(4rM0kfrZzIK9JU=^$YNyLvAIoxl#Q)xxDz!^0@zZ zSCs$nfcxK_vRYM34O<1}QHZ|hp4`ioX3x8(UV(FU$J@o%tw3t4k1QPmlEpZa2IujG&(roX_q*%e`Hq|);0;@k z0z=fZiFckp#JzW0p+2A+D$PC~IsakhJJkG(c;CqAgFfU0Z`u$PzG~-9I1oPHrCw&)@s^Dc~^)#HPW0Ra}J^=|h7Fs*<8|b13ZzG6MP*Q1dkoZ6&A^!}|hbjM{2HpqlSXv_UUg1U4gn z3Q)2VjU^ti1myodv+tjhSZp%D978m~p& z43uZUrraHs80Mq&vcetqfQpQP?m!CFj)44t8Z}k`E798wxg&~aCm+DBoI+nKq}&j^ zlPY3W$)K;KtEajks1`G?-@me7C>{PiiBu+41#yU_c(dITaqE?IQ(DBu+c^Ux!>pCj zLC|HJGU*v+!it1(;3e`6igkH(VA)-S+k(*yqxMgUah3$@C zz`7hEM47xr>j8^g`%*f=6S5n>z%Bt_Fg{Tvmr+MIsCx=0gsu_sF`q2hlkEmisz#Fy zj_0;zUWr;Gz}$BS%Y`meb(=$d%@Crs(OoJ|}m#<7=-A~PQbyN$x%2iXP2@e*nO0b7AwfH8cCUa*Wfu@b)D_>I*%uE4O3 z(lfnB`-Xf*LfC)E}e?%X2kK7DItK6Tf<+M^mX0Ijf_!IP>7c8IZX%8_#0060P{QMuV^B9i<^E`_Qf0pv9(P%_s8D`qvDE9LK9u-jB}J2S`(mCO&XHTS04Z5Ez*vl^T%!^$~EH8M-UdwhegL>3IQ*)(MtuH2Xt1p!fS4o~*rR?WLxlA!sjc2(O znjJn~wQ!Fp9s2e^IWP1C<4%sFF}T4omr}7+4asciyo3DntTgWIzhQpQirM$9{EbQd z3jz9vS@{aOqTQHI|l#aUV@2Q^Wko4T0T04Me4!2nsdrA8QY1%fnAYb~d2GDz@lAtfcHq(P7 zaMBAGo}+NcE-K*@9y;Vt3*(aCaMKXBB*BJcD_Qnxpt75r?GeAQ}*|>pYJE=uZb73 zC>sv)18)q#EGrTG6io*}JLuB_jP3AU1Uiu$D7r|2_zlIGb9 zjhst#ni)Y`$)!fc#reM*$~iaYoz~_Cy7J3ZTiPm)E?%`fbk`3Tu-F#`{i!l5pNEn5 zO-Tw-=TojYhzT{J=?SZj=Z8#|eoF>434b-DXiUsignxXNaR3 zm_}4iWU$gt2Mw5NvZ5(VpF`?X*f2UZDs1TEa1oZCif?Jdgr{>O~7}-$|BZ7I(IKW`{f;@|IZFX*R8&iT= zoWstN8&R;}@2Ka%d3vrLtR|O??ben;k8QbS-WB0VgiCz;<$pBmIZdN!aalyCSEm)crpS9dcD^Y@XT1a3+zpi-`D}e#HV<} z$Y(G&o~PvL-xSVD5D?JqF3?B9rxGWeb=oEGJ3vRp5xfBPlngh1O$yI95EL+T8{GC@ z98i1H9KhZGFl|;`)_=QpM6H?eDPpw~^(aFQWwyXZ8_EEE4#@QeT_URray*mEOGsGc z6|sdXtq!hVZo=d#+9^@lm&L5|q&-GDCyUx#YQiccq;spOBe3V+VKdjJA=IL=Zn%P} zNk=_8u}VhzFf{UYZV0`lUwcD&)9AFx0@Fc6LD9A6Rd1=ga>Mi0)_QxM2ddCVRmZ0d z+J=uXc(?5JLX3=)e)Jm$HS2yF`44IKhwRnm2*669_J=2LlwuF5$1tAo@ROSU@-y+;Foy2IEl2^V1N;fk~YR z?&EP8#t&m0B=?aJeuz~lHjAzRBX>&x=A;gIvb>MD{XEV zV%l-+9N-)i;YH%nKP?>f`=?#`>B(`*t`aiPLoQM(a6(qs4p5KFjDBN?8JGrf3z8>= zi7sD)c)Nm~x{e<^jy4nTx${P~cwz_*a>%0_;ULou3kHCAD7EYkw@l$8TN#LO9jC( z1BeFW`k+bu5e8Ns^a8dPcjEVHM;r6UX+cN=Uy7HU)j-myRU0wHd$A1fNI~`4;I~`zC)3ul#8#^rXVSO*m}Ag>c%_;nj=Nv$rCZ z*~L@C@OZg%Q^m)lc-kcX&a*a5`y&DaRxh6O*dfhLfF+fU5wKs(1v*!TkZidw*)YBP za@r`3+^IHRFeO%!ai%rxy;R;;V^Fr=OJlpBX;(b*3+SIw}7= zIq$*Thr(Zft-RlY)D3e8V;BmD&HOfX+E$H#Y@B3?UL5L~_fA-@*IB-!gItK7PIgG9 zgWuGZK_nuZjHVT_Fv(XxtU%)58;W39vzTI2n&)&4Dmq7&JX6G>XFaAR{7_3QB6zsT z?$L8c*WdN~nZGiscY%5KljQARN;`w$gho=p006z;n(qIQ*Zu<``TMO3n0{ARL@gYh zoRwS*|Niw~cR!?hE{m*y@F`1)vx-JRfqET=dJ5_(076st(=lFfjtKHoYg`k3oNmo_ zNbQEw8&sO5jAYmkD|Zaz_yUb0rC})U!rCHOl}JhbYIDLzLvrZVw0~JO`d*6f;X&?V=#T@ND*cv^I;`sFeq4 z##H5;gpZTb^0Hz@3C*~u0AqqNZ-r%rN3KD~%Gw`0XsIq$(^MEb<~H(2*5G^<2(*aI z%7}WB+TRlMIrEK#s0 z93xn*Ohb=kWFc)BNHG4I(~RPn-R8#0lqyBBz5OM6o5|>x9LK@%HaM}}Y5goCQRt2C z{j*2TtT4ne!Z}vh89mjwiSXG=%DURar~=kGNNaO_+Nkb+tRi~Rkf!7a$*QlavziD( z83s4GmQ^Wf*0Bd04f#0HX@ua_d8 z23~z*53ePD6@xwZ(vdl0DLc=>cPIOPOdca&MyR^jhhKrdQO?_jJh`xV3GKz&2lvP8 zEOwW6L*ufvK;TN{=S&R@pzV^U=QNk^Ec}5H z+2~JvEVA{`uMAr)?Kf|aW>33`)UL@bnfIUQc~L;TsTQ6>r-<^rB8uoNOJ>HWgqMI8 zSW}pZmp_;z_2O5_RD|fGyTxaxk53Hg_3Khc<8AUzV|ZeK{fp|Ne933=1&_^Dbv5^u zB9n=*)k*tjHDRJ@$bp9mrh}qFn*s}npMl5BMDC%Hs0M0g-hW~P*3CNG06G!MOPEQ_ zi}Qs-6M8aMt;sL$vlmVBR^+Ry<64jrm1EI1%#j?c?4b*7>)a{aDw#TfTYKq+SjEFA z(aJ&z_0?0JB83D-i3Vh+o|XV4UP+YJ$9Boid2^M2en@APw&wx7vU~t$r2V`F|7Qfo z>WKgI@eNBZ-+Og<{u2ZiG%>YvH2L3fNpV9J;WLJoBZda)01Rn;o@){01{7E#ke(7U zHK>S#qZ(N=aoae*4X!0A{)nu0R_sKpi1{)u>GVjC+b5Jyl6#AoQ-1_3UDovNSo`T> z?c-@7XX*2GMy?k?{g)7?Sv;SJkmxYPJPs!&QqB12ejq`Lee^-cDveVWL^CTUldb(G zjDGe(O4P=S{4fF=#~oAu>LG>wrU^z_?3yt24FOx>}{^lCGh8?vtvY$^hbZ)9I0E3r3NOlb9I?F-Yc=r$*~l`4N^xzlV~N zl~#oc>U)Yjl0BxV>O*Kr@lKT{Z09OXt2GlvE38nfs+DD7exl|&vT;)>VFXJVZp9Np zDK}aO;R3~ag$X*|hRVY3OPax|PG`@_ESc8E!mHRByJbZQRS38V2F__7MW~sgh!a>98Q2%lUNFO=^xU52|?D=IK#QjwBky-C>zOWlsiiM&1n z;!&1((Xn1$9K}xabq~222gYvx3hnZPg}VMF_GV~5ocE=-v>V=T&RsLBo&`)DOyIj* zLV{h)JU_y*7SdRtDajP_Y+rBkNN*1_TXiKwHH2&p51d(#zv~s#HwbNy?<+(=9WBvo zw2hkk2Dj%kTFhY+$T+W-b7@qD!bkfN#Z2ng@Pd=i3-i?xYfs5Z*1hO?kd7Sp^9`;Y zM2jeGg<-nJD1er@Pc_cSY7wo5dzQX44=%6rn}P_SRbpzsA{6B+!$3B0#;}qwO37G^ zL(V_5JK`XT?OHVk|{_$vQ|oNEpab*BO4F zUTNQ7RUhnRsU`TK#~`)$icsvKh~(pl=3p6m98@k3P#~upd=k*u20SNcb{l^1rUa)>qO997)pYRWMncC8A&&MHlbW?7i^7M`+B$hH~Y|J zd>FYOGQ;j>Zc2e7R{KK7)0>>nn_jYJy&o@sK!4G>-rLKM8Hv)f;hi1D2fAc$+six2 zyVZ@wZ6x|fJ!4KrpCJY=!Mq0;)X)OoS~{Lkh6u8J`eK%u0WtKh6B>GW_)PVc zl}-k`p09qwGtZ@VbYJC!>29V?Dr>>vk?)o(x?!z*9DJ||9qG-&G~#kXxbw{KKYy}J zQKa-dPt~M~E}V?PhW0R26xdA%1T*%ra6SguGu50YHngOTIv)@N|YttEXo#OZfgtP7;H?EeZZxo<}3YlYxtBq znJ!WFR^tmGf0Py}N?kZ(#=VtpC@%xJkDmfcCoBTxq zr_|5gP?u1@vJZbxPZ|G0AW4=tpb84gM2DpJU||(b8kMOV1S3|(yuwZJ&rIiFW(U;5 zUtAW`O6F6Zy+eZ1EDuP~AAHlSY-+A_eI5Gx)%*uro5tljy}kCZU*_d7)oJ>oQSZ3* zneTn`{gnNC&uJd)0aMBzAg021?YJ~b(fmkwZAd696a=0NzBAqBN54KuNDwa*no(^O z6p05bioXUR^uXjpTol*ppHp%1v9e)vkoUAUJyBx3lw0UO39b0?^{}yb!$yca(@DUn zCquRF?t=Zb9`Ed3AI6|L{eX~ijVH`VzSMheKoP7LSSf4g>md>`yi!TkoG5P>Ofp+n z(v~rW+(5L96L{vBb^g51B=(o)?%%xhvT*A5btOpw(TKh^g^4c zw>0%X!_0`{iN%RbVk+A^f{w-4-SSf*fu@FhruNL##F~sF24O~u zyYF<3el2b$$wZ_|uW#@Ak+VAGk#e|kS8nL1g>2B-SNMjMp^8;-FfeofY2fphFHO!{ z*!o4oTb{4e;S<|JEs<1_hPsmAlVNk?_5-Fp5KKU&d#FiNW~Y+pVFk@Cua1I{T+1|+ zHx6rFMor)7L)krbilqsWwy@T+g3DiH5MyVf8Wy}XbEaoFIDr~y;@r&I>FMW{ z?Q+(IgyebZ)-i4jNoXQhq4Muy9Fv+OxU;9_Jmn+<`mEC#%2Q_2bpcgzcinygNI!&^ z=V$)o2&Yz04~+&pPWWn`rrWxJ&}8khR)6B(--!9Q zubo}h+1T)>a@c)H^i``@<^j?|r4*{;tQf78(xn0g39IoZw0(CwY1f<%F>kEaJ zp9u|IeMY5mRdAlw*+gSN^5$Q)ShM<~E=(c8QM+T-Qk)FyKz#Sw0EJ*edYcuOtO#~Cx^(M7w5 z3)rl#L)rF|(Vun2LkFr!rg8Q@=r>9p>(t3Gf_auiJ2Xx9HmxYTa|=MH_SUlYL`mz9 zTTS$`%;D-|Jt}AP1&k7PcnfFNTH0A-*FmxstjBDiZX?}%u%Yq94$fUT&z6od+(Uk> zuqsld#G(b$G8tus=M!N#oPd|PVFX)?M?tCD0tS%2IGTfh}3YA3f&UM)W$_GNV8 zQo+a(ml2Km4o6O%gKTCSDNq+#zCTIQ1*`TIJh~k6Gp;htHBFnne))rlFdGqwC6dx2+La1&Mnko*352k0y z+tQcwndQlX`nc6nb$A9?<-o|r*%aWXV#=6PQic0Ok_D;q>wbv&j7cKc!w4~KF#-{6 z(S%6Za)WpGIWf7jZ3svNG5OLs0>vCL9{V7cgO%zevIVMH{WgP*^D9ws&OqA{yr|m| zKD4*07dGXshJHd#e%x%J+qmS^lS|0Bp?{drv;{@{l9ArPO&?Q5=?OO9=}h$oVe#3b z3Yofj&Cb}WC$PxmRRS)H%&$1-)z7jELS}!u!zQ?A^Y{Tv4QVt*vd@uj-^t2fYRzQj zfxGR>-q|o$3sGn^#VzZ!QQx?h9`njeJry}@x?|k0-GTTA4y3t2E`3DZ!A~D?GiJup z)8%PK2^9OVRlP(24P^4_<|D=H^7}WlWu#LgsdHzB%cPy|f8dD3|A^mh4WXxhLTVu_ z@abE{6Saz|Y{rXYPd4$tfPYo}ef(oQWZ=4Bct-=_9`#Qgp4ma$n$`tOwq#&E18$B; z@Bp)bn3&rEi0>fWWZ@7k5WazfoX`SCO4jQWwVuo+$PmSZn^Hz?O(-tW@*DGxuf)V1 zO_xm&;NVCaHD4dqt(-MlszI3F-p?0!-e$fbiCeuaw66h^TTDLWuaV<@C-`=Xe5WL) zwooG7h>4&*)p3pKMS3O!4>-4jQUN}iAMQ)2*70?hP~)TzzR?-f@?Aqy$$1Iy8VGG$ zMM?8;j!pUX7QQD$gRc_#+=raAS577ga-w?jd`vCiN5lu)dEUkkUPl9!?{$IJNxQys z*E4e$eF&n&+AMRQR2gcaFEjAy*r)G!s(P6D&TfoApMFC_*Ftx0|D0@E-=B7tezU@d zZ{hGiN;YLIoSeRS;9o%dEua4b%4R3;$SugDjP$x;Z!M!@QibuSBb)HY!3zJ7M;^jw zlx6AD50FD&p3JyP*>o+t9YWW8(7P2t!VQQ21pHJOcG_SXQD;(5aX#M6x##5H_Re>6lPyDCjxr*R(+HE%c&QN+b^tbT zXBJk?p)zhJj#I?&Y2n&~XiytG9!1ox;bw5Rbj~)7c(MFBb4>IiRATdhg zmiEFlj@S_hwYYI(ki{}&<;_7(Z0Qkfq>am z&LtL=2qc7rWguk3BtE4zL41@#S;NN*-jWw|7Kx7H7~_%7fPt;TIX}Ubo>;Rmj94V> zNB1=;-9AR7s`Pxn}t_6^3ahlq53e&!Lh85uG zec0vJY_6e`tg7LgfrJ3k!DjR)Bi#L@DHIrZ`sK=<5O0Ip!fxGf*OgGSpP@Hbbe&$9 z;ZI}8lEoC2_7;%L2=w?tb%1oL0V+=Z`7b=P&lNGY;yVBazXRYu;+cQDKvm*7NCxu&i;zub zAJh#11%?w>E2rf2e~C4+rAb-&$^vsdACs7 z@|Ra!OfVM(ke{vyiqh7puf&Yp6cd6{DptUteYfIRWG3pI+5< zBVBI_xkBAc<(pcb$!Y%dTW(b;B;2pOI-(QCsLv@U-D1XJ z(Gk8Q3l7Ws46Aktuj>|s{$6zA&xCPuXL-kB`CgYMs}4IeyG*P51IDwW?8UNQd+$i~ zlxOPtSi5L|gJcF@DwmJA5Ju8HEJ>o{{upwIpb!f{2(vLNBw`7xMbvcw<^{Fj@E~1( z?w`iIMieunS#>nXlmUcSMU+D3rX28f?s7z;X=se6bo8;5vM|O^(D6{A9*ChnGH!RG zP##3>LDC3jZPE4PH32AxrqPk|yIIrq~`aL-=}`okhNu9aT%q z1b)7iJ)CN=V#Ly84N_r7U^SH2FGdE5FpTO2 z630TF$P>GNMu8`rOytb(lB2};`;P4YNwW1<5d3Q~AX#P0aX}R2b2)`rgkp#zTxcGj zAV^cvFbhP|JgWrq_e`~exr~sIR$6p5V?o4Wym3kQ3HA+;Pr$bQ0(PmADVO%MKL!^q z?zAM8j1l4jrq|5X+V!8S*2Wl@=7*pPgciTVK6kS1Ge zMsd_u6DFK$jTnvVtE;qa+8(1sGBu~n&F%dh(&c(Zs4Fc#A=gG^^%^AyH}1^?|8quj zl@Z47h$){PlELJgYZCIHHL= z{U8O>Tw4x3<1{?$8>k-P<}1y9DmAZP_;(3Y*{Sk^H^A=_iSJ@+s5ktgwTXz_2$~W9>VVZsfwCm@s0sQ zeB50_yu@uS+e7QoPvdCwDz{prjo(AFwR%C?z`EL{1`|coJHQTk^nX=tvs1<0arUOJ z!^`*x&&BvTYmemyZ)2p~{%eYX=JVR?DYr(rNgqRMA5E1PR1Iw=prk=L2ldy3r3Vg@27IZx43+ywyzr-X*p*d@tZV+!U#~$-q=8c zgdSuh#r?b4GhEGNai)ayHQpk>5(%j5c@C1K3(W1pb~HeHpaqijJZa-e6vq_8t-^M^ zBJxq|MqZc?pjXPIH}70a5vt!IUh;l}<>VX<-Qcv^u@5(@@M2CHSe_hD$VG-eiV^V( zj7*9T0?di?P$FaD6oo?)<)QT>Npf6Og!GO^GmPV(Km0!=+dE&bk#SNI+C9RGQ|{~O*VC+tXK3!n`5 zHfl6>lwf_aEVV3`0T!aHNZLsj$paS$=LL(?b!Czaa5bbSuZ6#$_@LK<(7yrrl+80| z{tOFd=|ta2Z`^ssozD9BINn45NxUeCQis?-BKmU*Kt=FY-NJ+)8S1ecuFtN-M?&42 zl2$G>u!iNhAk*HoJ^4v^9#ORYp5t^wDj6|lx~5w45#E5wVqI1JQ~9l?nPp1YINf++ zMAdSif~_ETv@Er(EFBI^@L4BULFW>)NI+ejHFP*T}UhWNN`I)RRS8za? z*@`1>9ZB}An%aT5K=_2iQmfE;GcBVHLF!$`I99o5GO`O%O_zLr9AG18>&^HkG(;=V z%}c!OBQ~?MX(9h~tajX{=x)+!cbM7$YzTlmsPOdp2L-?GoW`@{lY9U3f;OUo*BwRB z8A+nv(br0-SH#VxGy#ZrgnGD(=@;HME;yd46EgWJ`EL%oXc&lFpc@Y}^>G(W>h_v_ zlN!`idhX+OjL+~T?19sroAFVGfa5tX-D49w$1g2g_-T|EpHL6}K_aX4$K=LTvwtlF zL*z}j{f+Uoe7{-px3_5iKPA<_7W=>Izkk)!l9ez2w%vi(?Y;i8AxRNLSOGDzNoqoI zP!1uAl}r=_871(G?y`i&)-7{u=%nxk7CZ_Qh#!|ITec zwQn`33GTUM`;D2POWnkqngqJhJRlM>CTONzTG}>^Q0wUunQyn|TAiHzyX2_%ATx%P z%7gW)%4rA9^)M<_%k@`Y?RbC<29sWU&5;@|9thf2#zf8z12$hRcZ!CSb>kUp=4N#y zl3hE#y6>kkA8VY2`W`g5Ip?2qC_BY$>R`iGQLhz2-S>x(RuWv)SPaGdl^)gGw7tjR zH@;jwk!jIaCgSg_*9iF|a);sRUTq30(8I(obh^|}S~}P4U^BIGYqcz;MPpC~Y@k_m zaw4WG1_vz2GdCAX!$_a%GHK**@IrHSkGoN>)e}>yzUTm52on`hYot7cB=oA-h1u|R ztH$11t?54Qg2L+i33FPFKKRm1aOjKST{l1*(nps`>sv%VqeVMWjl5+Gh+9);hIP8? zA@$?}Sc z3qIRpba+y5yf{R6G(u8Z^vkg0Fu&D-7?1s=QZU`Ub{-!Y`I?AGf1VNuc^L3v>)>i# z{DV9W$)>34wnzAXUiV^ZpYKw>UElrN_5Xj6{r_3| z$X5PK`e5$7>~9Dj7gK5ash(dvs`vwfk}&RD`>04;j62zoXESkFBklYaKm5seyiX(P zqQ-;XxlV*yg?Dhlx%xt!b0N3GHp@(p$A;8|%# zZ5m2KL|{on4nr>2_s9Yh=r5ScQ0;aMF)G$-9-Ca6%wA`Pa)i?NGFA|#Yi?{X-4ZO_ z^}%7%vkzvUHa$-^Y#aA+aiR5sa%S|Ebyn`EV<3Pc?ax_f>@sBZF1S;7y$CXd5t5=WGsTKBk8$OfH4v|0?0I=Yp}7c=WBSCg!{0n)XmiU;lfx)**zZaYqmDJelxk$)nZyx5`x$6R|fz(;u zEje5Dtm|a%zK!!tk3{i9$I2b{vXNFy%Bf{50X!x{98+BsDr_u9i>G5%*sqEX|06J0 z^IY{UcEbj6LDwuMh7cH`H@9sVt1l1#8kEQ(LyT@&+K}(ReE`ux8gb0r6L_#bDUo^P z3Ka2lRo52Hdtl_%+pwVs14=q`{d^L58PsU@AMf(hENumaxM{7iAT5sYmWh@hQCO^ zK&}ijo=`VqZ#a3vE?`7QW0ZREL17ZvDfdqKGD?0D4fg{7v%|Yj&_jcKJAB)>=*RS* zto8p6@k%;&^ZF>hvXm&$PCuEp{uqw3VPG$9VMdW5$w-fy2CNNT>E;>ejBgy-m_6`& z97L1p{%srn@O_JQgFpa_#f(_)eb#YS>o>q3(*uB;uZb605(iqM$=NK{nHY=+X2*G) zO3-_Xh%aG}fHWe*==58zBwp%&`mge<8uq8;xIxOd=P%9EK!34^E9sk|(Zq1QSz-JVeP12Fp)-`F|KY$LPwUE?rku zY@OJ)Z9A!ojfzfeyJ9;zv2EM7ZQB)AR5xGa-tMn^bl)FmoIiVyJ@!~@%{}qXXD&Ns zPnfe5U+&ohKefILu_1mPfLGuapX@btta5C#gPB2cjk5m4T}Nfi+Vfka!Yd(L?-c~5 z#ZK4VeQEXNPc4r$K00Fg>g#_W!YZ)cJ?JTS<&68_$#cZT-ME`}tcwqg3#``3M3UPvn+pi}(VNNx6y zFIMVb6OwYU(2`at$gHba*qrMVUl8xk5z-z~fb@Q3Y_+aXuEKH}L+>eW__!IAd@V}L zkw#s%H0v2k5-=vh$^vPCuAi22Luu3uKTf6fPo?*nvj$9(u)4$6tvF-%IM+3pt*cgs z_?wW}J7VAA{_~!?))?s6{M=KPpVhg4fNuU*|3THp@_(q!b*hdl{fjRVFWtu^1dV(f z6iOux9hi&+UK=|%M*~|aqFK{Urfl!TA}UWY#`w(0P!KMe1Si{8|o))Gy6d7;!JQYhgMYmXl?3FfOM2nQGN@~Ap6(G z3+d_5y@=nkpKAhRqf{qQ~k7Z$v&l&@m7Ppt#FSNzKPZM z8LhihcE6i=<(#87E|Wr~HKvVWhkll4iSK$^mUHaxgy8*K$_Zj;zJ`L$naPj+^3zTi z-3NTaaKnD5FPY-~?Tq6QHnmDDRxu0mh0D|zD~Y=vv_qig5r-cIbCpxlju&8Sya)@{ zsmv6XUSi)@(?PvItkiZEeN*)AE~I_?#+Ja-r8$(XiXei2d@Hi7Rx8+rZZb?ZLa{;@*EHeRQ-YDadz~M*YCM4&F-r;E#M+@CSJMJ0oU|PQ^ z=E!HBJDMQ2TN*Y(Ag(ynAL8%^v;=~q?s4plA_hig&5Z0x_^Oab!T)@6kRN$)qEJ6E zNuQjg|G7iwU(N8pI@_6==0CL;lRh1dQF#wePhmu@hADFd3B5KIH#dx(2A zp~K&;Xw}F_N6CU~0)QpQk7s$a+LcTOj1%=WXI(U=Dv!6 z{#<#-)2+gCyyv=Jw?Ab#PVkxPDeH|sAxyG`|Ys}A$PW4TdBv%zDz z^?lwrxWR<%Vzc8Sgt|?FL6ej_*e&rhqJZ3Y>k=X(^dytycR;XDU16}Pc9Vn0>_@H+ zQ;a`GSMEG64=JRAOg%~L)x*w{2re6DVprNp+FcNra4VdNjiaF0M^*>CdPkt(m150rCue?FVdL0nFL$V%5y6N z%eLr5%YN7D06k5ji5*p4v$UMM)G??Q%RB27IvH7vYr_^3>1D-M66#MN8tWGw>WED} z5AhlsanO=STFYFs)Il_0i)l)f<8qn|$DW7ZXhf5xI;m+7M5-%P63XFQrG9>DMqHc} zsgNU9nR`b}E^mL5=@7<1_R~j@q_2U^3h|+`7YH-?C=vme1C3m`Fe0HC>pjt6f_XMh zy~-i-8R46QNYneL4t@)<0VU7({aUO?aH`z4V2+kxgH5pYD5)wCh75JqQY)jIPN=U6 z+qi8cGiOtXG2tXm;_CfpH9ESCz#i5B(42}rBJJF$jh<1sbpj^8&L;gzGHb8M{of+} zzF^8VgML2O9nxBW7AvdEt90vp+#kZxWf@A)o9f9}vKJy9NDBjBW zSt=Hcs=YWCwnfY1UYx*+msp{g!w0HC<_SM!VL1(I2PE?CS}r(eh?{I)mQixmo5^p# zV?2R!R@3GV6hwTCrfHiK#3Orj>I!GS2kYhk1S;aFBD_}u2v;0HYFq}Iz1Z(I4oca4 zxquja8$+8JW_EagDHf$a1OTk5S97umGSDaj)gH=fLs9>_=XvVj^Xj9a#gLdk=&3tl zfmK9MNnIX9v{?%xdw7568 zNrZ|roYs(vC4pHB5RJ8>)^*OuyNC>x7ad)tB_}3SgQ96+-JT^Qi<`xi=)_=$Skwv~ zdqeT9Pa`LYvCAn&rMa2aCDV(TMI#PA5g#RtV|CWpgDYRA^|55LLN^uNh*gOU>Z=a06qJ;$C9z8;n-Pq=qZnc1zUwJ@t)L;&NN+E5m zRkQ(SeM8=l-aoAKGKD>!@?mWTW&~)uF2PYUJ;tB^my`r9n|Ly~0c%diYzqs9W#FTjy?h&X3TnH zXqA{QI82sdjPO->f=^K^f>N`+B`q9&rN0bOXO79S&a9XX8zund(kW7O76f4dcWhIu zER`XSMSFbSL>b;Rp#`CuGJ&p$s~G|76){d?xSA5wVg##_O0DrmyEYppyBr%fyWbbv zp`K84JwRNP$d-pJ!Qk|(RMr?*!wi1if-9G#0p>>1QXKXWFy)eB3ai)l3601q8!9JC zvU#ZWWDNKq9g6fYs?JQ)Q4C_cgTy3FhgKb8s&m)DdmL5zhNK#8wWg!J*7G7Qhe9VU zha?^AQTDpYcuN!B+#1dE*X{<#!M%zfUQbj=zLE{dW0XeQ7-oIsGY6RbkP2re@Q{}r_$iiH0xU%iN*ST`A)-EH6eaZB$GA#v)cLi z*MpA(3bYk$oBDKAzu^kJoSUsDd|856DApz={3u8sbQV@JnRkp2nC|)m;#T=DvIL-O zI4vh;g7824l}*`_p@MT4+d`JZ2%6NQh=N9bmgJ#q!hK@_<`HQq3}Z8Ij>3%~<*= zcv=!oT#5xmeGI92lqm9sGVE%#X$ls;St|F#u!?5Y7syhx6q#MVRa&lBmmn%$C0QzU z);*ldgwwCmzM3uglr}!Z2G+?& zf%Dpo&mD%2ZcNFiN-Z0f;c_Q;A%f@>26f?{d1kxIJD}LxsQkB47SAdwinfMILZdN3 zfj^HmTzS3Ku5BxY>ANutS8WPQ-G>v4^_Qndy==P3pDm+Xc?>rUHl-4+^%Sp5atOja z2oP}ftw-rqnb}+khR3CrRg^ibi6?QYk1*i^;kQGirQ=uB9Sd1NTfT-Rbv;hqnY4neE5H1YUrjS2m+2&@uXiAo- zrKUX|Ohg7(6F(AoP~tj;NZlV#xsfo-5reuQHB$&EIAhyZk;bL;k9ouDmJNBAun;H& zn;Of1z_Qj`x&M;5X;{s~iGzBQTY^kv-k{ksbE*Dl%Qf%N@hQCfY~iUw!=F-*$cpf2 z3wix|aLBV0b;W@z^%7S{>9Z^T^fLOI68_;l@+Qzaxo`nAI8emTV@rRhEKZ z?*z_{oGdI~R*#<2{bkz$G~^Qef}$*4OYTgtL$e9q!FY7EqxJ2`zk6SQc}M(k(_MaV zSLJnTXw&@djco1~a(vhBl^&w=$fa9{Sru>7g8SHahv$&Bl(D@(Zwxo_3r=;VH|uc5 zi1Ny)J!<(KN-EcQ(xlw%PNwK8U>4$9nVOhj(y0l9X^vP1TA>r_7WtSExIOsz`nDOP zs}d>Vxb2Vo2e5x8p(n~Y5ggAyvib>d)6?)|E@{FIz?G3PVGLf7-;BxaP;c?7ddH$z zA+{~k^V=bZuXafOv!RPsE1GrR3J2TH9uB=Z67gok+u`V#}BR86hB1xl}H4v`F+mRfr zYhortD%@IGfh!JB(NUNSDh+qDz?4ztEgCz&bIG-Wg7w-ua4ChgQR_c+z8dT3<1?uX z*G(DKy_LTl*Ea!%v!RhpCXW1WJO6F`bgS-SB;Xw9#! z<*K}=#wVu9$`Yo|e!z-CPYH!nj7s9dEPr-E`DXUBu0n!xX~&|%#G=BeM?X@shQQMf zMvr2!y7p_gD5-!Lnm|a@z8Of^EKboZsTMk%5VsJEm>VsJ4W7Kv{<|#4f-qDE$D-W>gWT%z-!qXnDHhOvLk=?^a1*|0j z{pW{M0{#1VcR5;F!!fIlLVNh_Gj zbnW(_j?0c2q$EHIi@fSMR{OUKBcLr{Y&$hrM8XhPByyZaXy|dd&{hYQRJ9@Fn%h3p7*VQolBIV@Eq`=y%5BU~3RPa^$a?ixp^cCg z+}Q*X+CW9~TL29@OOng(#OAOd!)e$d%sr}^KBJ-?-X&|4HTmtemxmp?cT3uA?md4% zT8yZ0U;6Rg6JHy3fJae{6TMGS?ZUX6+gGTT{Q{)SI85$5FD{g-eR%O0KMpWPY`4@O zx!hen1*8^E(*}{m^V_?}(b5k3hYo=T+$&M32+B`}81~KKZhY;2H{7O-M@vbCzuX0n zW-&HXeyr1%I3$@ns-V1~Lb@wIpkmx|8I~ob1Of7i6BTNysEwI}=!nU%q7(V_^+d*G z7G;07m(CRTJup!`cdYi93r^+LY+`M*>aMuHJm(A8_O8C#A*$!Xvddgpjx5)?_EB*q zgE8o5O>e~9IiSC@WtZpF{4Bj2J5eZ>uUzY%TgWF7wdDE!fSQIAWCP)V{;HsU3ap?4 znRsiiDbtN7i9hapO;(|Ew>Ip2TZSvK9Z^N21%J?OiA_&eP1{(Pu_=%JjKy|HOardq ze?zK^K zA%sjF64*Wufad%H<) z^|t>e*h+Z1#l=5wHexzt9HNDNXgM=-OPWKd^5p!~%SIl>Fo&7BvNpbf8{NXmH)o{r zO=aBJ;meX1^{O%q;kqdw*5k!Y7%t_30 zy{nGRVc&5qt?dBwLs+^Sfp;f`YVMSB#C>z^a9@fpZ!xb|b-JEz1LBX7ci)V@W+kvQ89KWA0T~Lj$aCcfW#nD5bt&Y_< z-q{4ZXDqVg?|0o)j1%l0^_it0WF*LCn-+)c!2y5yS7aZIN$>0LqNnkujV*YVes(v$ zY@_-!Q;!ZyJ}Bg|G-~w@or&u0RO?vlt5*9~yeoPV_UWrO2J54b4#{D(D>jF(R88u2 zo#B^@iF_%S>{iXSol8jpmsZuJ?+;epg>k=$d`?GSegAVp3n$`GVDvK${N*#L_1`44 z{w0fL{2%)0|E+qgZtjX}itZz^KJt4Y;*8uSK}Ft38+3>j|K(PxIXXR-t4VopXo#9# zt|F{LWr-?34y`$nLBVV_*UEgA6AUI65dYIbqpNq9cl&uLJ0~L}<=ESlOm?Y-S@L*d z<7vt}`)TW#f%Rp$Q}6@3=j$7Tze@_uZO@aMn<|si{?S}~maII`VTjs&?}jQ4_cut9$)PEqMukwoXobzaKx^MV z2fQwl+;LSZ$qy%Tys0oo^K=jOw$!YwCv^ei4NBVauL)tN%=wz9M{uf{IB(BxK|lT*pFkmNK_1tV`nb%jH=a0~VNq2RCKY(rG7jz!-D^k)Ec)yS%17pE#o6&eY+ z^qN(hQT$}5F(=4lgNQhlxj?nB4N6ntUY6(?+R#B?W3hY_a*)hnr4PA|vJ<6p`K3Z5Hy z{{8(|ux~NLUW=!?9Qe&WXMTAkQnLXg(g=I@(VG3{HE13OaUT|DljyWXPs2FE@?`iU z4GQlM&Q=T<4&v@Fe<+TuXiZQT3G~vZ&^POfmI1K2h6t4eD}Gk5XFGpbj1n_g*{qmD6Xy z`6Vv|lLZtLmrnv*{Q%xxtcWVj3K4M%$bdBk_a&ar{{GWyu#ljM;dII;*jP;QH z#+^o-A4np{@|Mz+LphTD0`FTyxYq#wY)*&Ls5o{0z9yg2K+K7ZN>j1>N&;r+Z`vI| zDzG1LJZ+sE?m?>x{5LJx^)g&pGEpY=fQ-4}{x=ru;}FL$inHemOg%|R*ZXPodU}Kh zFEd5#+8rGq$Y<_?k-}r5zgQ3jRV=ooHiF|@z_#D4pKVEmn5CGV(9VKCyG|sT9nc=U zEoT67R`C->KY8Wp-fEcjjFm^;Cg(ls|*ABVHq8clBE(;~K^b+S>6uj70g? z&{XQ5U&!Z$SO7zfP+y^8XBbiu*Cv-yJG|l-oe*!s5$@Lh_KpxYL2sx`B|V=dETN>5K+C+CU~a_3cI8{vbu$TNVdGf15*>D zz@f{zIlorkY>TRh7mKuAlN9A0>N>SV`X)+bEHms=mfYTMWt_AJtz_h+JMmrgH?mZt zm=lfdF`t^J*XLg7v+iS)XZROygK=CS@CvUaJo&w2W!Wb@aa?~Drtf`JV^cCMjngVZ zv&xaIBEo8EYWuML+vxCpjjY^s1-ahXJzAV6hTw%ZIy!FjI}aJ+{rE&u#>rs)vzuxz z+$5z=7W?zH2>Eb32dvgHYZtCAf!=OLY-pb4>Ae79rd68E2LkVPj-|jFeyqtBCCwiW zkB@kO_(3wFq)7qwV}bA=zD!*@UhT`geq}ITo%@O(Z5Y80nEX~;0-8kO{oB6|(4fQh z);73T!>3@{ZobPwRv*W?7m0Ml9GmJBCJd&6E?hdj9lV= z4flNfsc(J*DyPv?RCOx!MSvk(M952PJ-G|JeVxWVjN~SNS6n-_Ge3Q;TGE;EQvZg86%wZ`MB zSMQua(i*R8a75!6$QRO^(o7sGoomb+Y{OMy;m~Oa`;P9Yqo>?bJAhqXxLr7_3g_n>f#UVtxG!^F#1+y@os6x(sg z^28bsQ@8rw%Gxk-stAEPRbv^}5sLe=VMbkc@Jjimqjvmd!3E7+QnL>|(^3!R} zD-l1l7*Amu@j+PWLGHXXaFG0Ct2Q=}5YNUxEQHCAU7gA$sSC<5OGylNnQUa>>l%sM zyu}z6i&({U@x^hln**o6r2s-(C-L50tQvz|zHTqW!ir?w&V23tuYEDJVV#5pE|OJu z7^R!A$iM$YCe?8n67l*J-okwfZ+ZTkGvZ)tVPfR;|3gyFjF)8V zyXXN=!*bpyRg9#~Bg1+UDYCt0 ztp4&?t1X0q>uz;ann$OrZs{5*r`(oNvw=$7O#rD|Wuv*wIi)4b zGtq4%BX+kkagv3F9Id6~-c+1&?zny%w5j&nk9SQfo0k4LhdSU_kWGW7axkfpgR`8* z!?UTG*Zi_baA1^0eda8S|@&F z{)Rad0kiLjB|=}XFJhD(S3ssKlveFFmkN{Vl^_nb!o5M!RC=m)V&v2%e?ZoRC@h3> zJ(?pvToFd`*Zc@HFPL#=otWKwtuuQ_dT-Hr{S%pQX<6dqVJ8;f(o)4~VM_kEQkMR+ zs1SCVi~k>M`u1u2xc}>#D!V&6nOOh-E$O&SzYrjJdZpaDv1!R-QGA141WjQe2s0J~ zQ;AXG)F+K#K8_5HVqRoRM%^EduqOnS(j2)|ctA6Q^=|s_WJYU;Z%5bHp08HPL`YF2 zR)Ad1z{zh`=sDs^&V}J z%$Z$!jd7BY5AkT?j`eqMs%!Gm@T8)4w3GYEX~IwgE~`d|@T{WYHkudy(47brgHXx& zBL1yFG6!!!VOSmDxBpefy2{L_u5yTwja&HA!mYA#wg#bc-m%~8aRR|~AvMnind@zs zy>wkShe5&*un^zvSOdlVu%kHsEo>@puMQ`b1}(|)l~E{5)f7gC=E$fP(FC2=F<^|A zxeIm?{EE!3sO!Gr7e{w)Dx(uU#3WrFZ>ibmKSQ1tY?*-Nh1TDHLe+k*;{Rp!Bmd_m zb#^kh`Y*8l|9Cz2e{;RL%_lg{#^Ar+NH|3z*Zye>!alpt{z;4dFAw^^H!6ING*EFc z_yqhr8d!;%nHX9AKhFQZBGrSzfzYCi%C!(Q5*~hX>)0N`vbhZ@N|i;_972WSx*>LH z87?en(;2_`{_JHF`Sv6Wlps;dCcj+8IJ8ca6`DsOQCMb3n# z3)_w%FuJ3>fjeOOtWyq)ag|PmgQbC-s}KRHG~enBcIwqIiGW8R8jFeBNY9|YswRY5 zjGUxdGgUD26wOpwM#8a!Nuqg68*dG@VM~SbOroL_On0N6QdT9?)NeB3@0FCC?Z|E0 z6TPZj(AsPtwCw>*{eDEE}Gby>0q{*lI+g2e&(YQrsY&uGM{O~}(oM@YWmb*F zA0^rr5~UD^qmNljq$F#ARXRZ1igP`MQx4aS6*MS;Ot(1L5jF2NJ;de!NujUYg$dr# z=TEL_zTj2@>ZZN(NYCeVX2==~=aT)R30gETO{G&GM4XN<+!&W&(WcDP%oL8PyIVUC zs5AvMgh6qr-2?^unB@mXK*Dbil^y-GTC+>&N5HkzXtozVf93m~xOUHn8`HpX=$_v2 z61H;Z1qK9o;>->tb8y%#4H)765W4E>TQ1o0PFj)uTOPEvv&}%(_mG0ISmyhnQV33Z$#&yd{ zc{>8V8XK$3u8}04CmAQ#I@XvtmB*s4t8va?-IY4@CN>;)mLb_4!&P3XSw4pA_NzDb zORn!blT-aHk1%Jpi>T~oGLuh{DB)JIGZ9KOsciWs2N7mM1JWM+lna4vkDL?Q)z_Ct z`!mi0jtr+4*L&N7jk&LodVO#6?_qRGVaucqVB8*us6i3BTa^^EI0x%EREQSXV@f!lak6Wf1cNZ8>*artIJ(ADO*=<-an`3zB4d*oO*8D1K!f z*A@P1bZCNtU=p!742MrAj%&5v%Xp_dSX@4YCw%F|%Dk=u|1BOmo)HsVz)nD5USa zR~??e61sO(;PR)iaxK{M%QM_rIua9C^4ppVS$qCT9j2%?*em?`4Z;4@>I(c%M&#cH z>4}*;ej<4cKkbCAjjDsyKS8rIm90O)Jjgyxj5^venBx&7B!xLmzxW3jhj7sR(^3Fz z84EY|p1NauwXUr;FfZjdaAfh%ivyp+^!jBjJuAaKa!yCq=?T_)R!>16?{~p)FQ3LDoMyG%hL#pR!f@P%*;#90rs_y z@9}@r1BmM-SJ#DeuqCQk=J?ixDSwL*wh|G#us;dd{H}3*-Y7Tv5m=bQJMcH+_S`zVtf;!0kt*(zwJ zs+kedTm!A}cMiM!qv(c$o5K%}Yd0|nOd0iLjus&;s0Acvoi-PFrWm?+q9f^FslxGi z6ywB`QpL$rJzWDg(4)C4+!2cLE}UPCTBLa*_=c#*$b2PWrRN46$y~yST3a2$7hEH= zNjux+wna^AzQ=KEa_5#9Ph=G1{S0#hh1L3hQ`@HrVnCx{!fw_a0N5xV(iPdKZ-HOM za)LdgK}1ww*C_>V7hbQnTzjURJL`S%`6nTHcgS+dB6b_;PY1FsrdE8(2K6FN>37!62j_cBlui{jO^$dPkGHV>pXvW0EiOA zqW`YaSUBWg_v^Y5tPJfWLcLpsA8T zG)!x>pKMpt!lv3&KV!-um= zKCir6`bEL_LCFx4Z5bAFXW$g3Cq`?Q%)3q0r852XI*Der*JNuKUZ`C{cCuu8R8nkt z%pnF>R$uY8L+D!V{s^9>IC+bmt<05h**>49R*#vpM*4i0qRB2uPbg8{{s#9yC;Z18 zD7|4m<9qneQ84uX|J&f-g8a|nFKFt34@Bt{CU`v(SYbbn95Q67*)_Esl_;v291s=9 z+#2F2apZU4Tq=x+?V}CjwD(P=U~d<=mfEFuyPB`Ey82V9G#Sk8H_Ob_RnP3s?)S_3 zr%}Pb?;lt_)Nf>@zX~D~TBr;-LS<1I##8z`;0ZCvI_QbXNh8Iv)$LS=*gHr;}dgb=w5$3k2la1keIm|=7<-JD>)U%=Avl0Vj@+&vxn zt-)`vJxJr88D&!}2^{GPXc^nmRf#}nb$4MMkBA21GzB`-Or`-3lq^O^svO7Vs~FdM zv`NvzyG+0T!P8l_&8gH|pzE{N(gv_tgDU7SWeiI-iHC#0Ai%Ixn4&nt{5y3(GQs)i z&uA;~_0shP$0Wh0VooIeyC|lak__#KVJfxa7*mYmZ22@(<^W}FdKjd*U1CqSjNKW% z*z$5$=t^+;Ui=MoDW~A7;)Mj%ibX1_p4gu>RC}Z_pl`U*{_z@+HN?AF{_W z?M_X@o%w8fgFIJ$fIzBeK=v#*`mtY$HC3tqw7q^GCT!P$I%=2N4FY7j9nG8aIm$c9 zeKTxVKN!UJ{#W)zxW|Q^K!3s;(*7Gbn;e@pQBCDS(I|Y0euK#dSQ_W^)sv5pa%<^o zyu}3d?Lx`)3-n5Sy9r#`I{+t6x%I%G(iewGbvor&I^{lhu-!#}*Q3^itvY(^UWXgvthH52zLy&T+B)Pw;5>4D6>74 zO_EBS)>l!zLTVkX@NDqyN2cXTwsUVao7$HcqV2%t$YzdAC&T)dwzExa3*kt9d(}al zA~M}=%2NVNUjZiO7c>04YH)sRelXJYpWSn^aC$|Ji|E13a^-v2MB!Nc*b+=KY7MCm zqIteKfNkONq}uM;PB?vvgQvfKLPMB8u5+Am=d#>g+o&Ysb>dX9EC8q?D$pJH!MTAqa=DS5$cb+;hEvjwVfF{4;M{5U&^_+r zvZdu_rildI!*|*A$TzJ&apQWV@p{!W`=?t(o0{?9y&vM)V)ycGSlI3`;ps(vf2PUq zX745#`cmT*ra7XECC0gKkpu2eyhFEUb?;4@X7weEnLjXj_F~?OzL1U1L0|s6M+kIhmi%`n5vvDALMagi4`wMc=JV{XiO+^ z?s9i7;GgrRW{Mx)d7rj)?(;|b-`iBNPqdwtt%32se@?w4<^KU&585_kZ=`Wy^oLu9 z?DQAh5z%q;UkP48jgMFHTf#mj?#z|=w= z(q6~17Vn}P)J3M?O)x))%a5+>TFW3No~TgP;f}K$#icBh;rSS+R|}l鯊%1Et zwk~hMkhq;MOw^Q5`7oC{CUUyTw9x>^%*FHx^qJw(LB+E0WBX@{Ghw;)6aA-KyYg8p z7XDveQOpEr;B4je@2~usI5BlFadedX^ma{b{ypd|RNYqo#~d*mj&y`^iojR}s%~vF z(H!u`yx68D1Tj(3(m;Q+Ma}s2n#;O~bcB1`lYk%Irx60&-nWIUBr2x&@}@76+*zJ5 ze&4?q8?m%L9c6h=J$WBzbiTf1Z-0Eb5$IZs>lvm$>1n_Mezp*qw_pr8<8$6f)5f<@ zyV#tzMCs51nTv_5ca`x`yfE5YA^*%O_H?;tWYdM_kHPubA%vy47i=9>Bq) zRQ&0UwLQHeswmB1yP)+BiR;S+Vc-5TX84KUA;8VY9}yEj0eESSO`7HQ4lO z4(CyA8y1G7_C;6kd4U3K-aNOK!sHE}KL_-^EDl(vB42P$2Km7$WGqNy=%fqB+ zSLdrlcbEH=T@W8V4(TgoXZ*G1_aq$K^@ek=TVhoKRjw;HyI&coln|uRr5mMOy2GXP zwr*F^Y|!Sjr2YQXX(Fp^*`Wk905K%$bd03R4(igl0&7IIm*#f`A!DCarW9$h$z`kYk9MjjqN&5-DsH@8xh63!fTNPxWsFQhNv z#|3RjnP$Thdb#Ys7M+v|>AHm0BVTw)EH}>x@_f4zca&3tXJhTZ8pO}aN?(dHo)44Z z_5j+YP=jMlFqwvf3lq!57-SAuRV2_gJ*wsR_!Y4Z(trO}0wmB9%f#jNDHPdQGHFR; zZXzS-$`;7DQ5vF~oSgP3bNV$6Z(rwo6W(U07b1n3UHqml>{=6&-4PALATsH@Bh^W? z)ob%oAPaiw{?9HfMzpGb)@Kys^J$CN{uf*HX?)z=g`J(uK1YO^8~s1(ZIbG%Et(|q z$D@_QqltVZu9Py4R0Ld8!U|#`5~^M=b>fnHthzKBRr=i+w@0Vr^l|W;=zFT#PJ?*a zbC}G#It}rQP^Ait^W&aa6B;+0gNvz4cWUMzpv(1gvfw-X4xJ2Sv;mt;zb2Tsn|kSS zo*U9N?I{=-;a-OybL4r;PolCfiaL=y@o9{%`>+&FI#D^uy#>)R@b^1ue&AKKwuI*` zx%+6r48EIX6nF4o;>)zhV_8(IEX})NGU6Vs(yslrx{5fII}o3SMHW7wGtK9oIO4OM&@@ECtXSICLcPXoS|{;=_yj>hh*%hP27yZwOmj4&Lh z*Nd@OMkd!aKReoqNOkp5cW*lC)&C$P?+H3*%8)6HcpBg&IhGP^77XPZpc%WKYLX$T zsSQ$|ntaVVOoRat$6lvZO(G-QM5s#N4j*|N_;8cc2v_k4n6zx9c1L4JL*83F-C1Cn zaJhd;>rHXB%%ZN=3_o3&Qd2YOxrK~&?1=UuN9QhL$~OY-Qyg&})#ez*8NpQW_*a&kD&ANjedxT0Ar z<6r{eaVz3`d~+N~vkMaV8{F?RBVemN(jD@S8qO~L{rUw#=2a$V(7rLE+kGUZ<%pdr z?$DP|Vg#gZ9S}w((O2NbxzQ^zTot=89!0^~hE{|c9q1hVzv0?YC5s42Yx($;hAp*E zyoGuRyphQY{Q2ee0Xx`1&lv(l-SeC$NEyS~8iil3_aNlnqF_G|;zt#F%1;J)jnPT& z@iU0S;wHJ2$f!juqEzPZeZkjcQ+Pa@eERSLKsWf=`{R@yv7AuRh&ALRTAy z8=g&nxsSJCe!QLchJ=}6|LshnXIK)SNd zRkJNiqHwKK{SO;N5m5wdL&qK`v|d?5<4!(FAsDxR>Ky#0#t$8XCMptvNo?|SY?d8b z`*8dVBlXTUanlh6n)!EHf2&PDG8sXNAt6~u-_1EjPI1|<=33T8 zEnA00E!`4Ave0d&VVh0e>)Dc}=FfAFxpsC1u9ATfQ`-Cu;mhc8Z>2;uyXtqpLb7(P zd2F9<3cXS} znMg?{&8_YFTGRQZEPU-XPq55%51}RJpw@LO_|)CFAt62-_!u_Uq$csc+7|3+TV_!h z+2a7Yh^5AA{q^m|=KSJL+w-EWDBc&I_I1vOr^}P8i?cKMhGy$CP0XKrQzCheG$}G# zuglf8*PAFO8%xop7KSwI8||liTaQ9NCAFarr~psQt)g*pC@9bORZ>m`_GA`_K@~&% zijH0z;T$fd;-Liw8%EKZas>BH8nYTqsK7F;>>@YsE=Rqo?_8}UO-S#|6~CAW0Oz1} z3F(1=+#wrBJh4H)9jTQ_$~@#9|Bc1Pd3rAIA_&vOpvvbgDJOM(yNPhJJq2%PCcMaI zrbe~toYzvkZYQ{ea(Wiyu#4WB#RRN%bMe=SOk!CbJZv^m?Flo5p{W8|0i3`hI3Np# zvCZqY%o258CI=SGb+A3yJe~JH^i{uU`#U#fvSC~rWTq+K`E%J@ zasU07&pB6A4w3b?d?q}2=0rA#SA7D`X+zg@&zm^iA*HVi z009#PUH<%lk4z~p^l0S{lCJk1Uxi=F4e_DwlfHA`X`rv(|JqWKAA5nH+u4Da+E_p+ zVmH@lg^n4ixs~*@gm_dgQ&eDmE1mnw5wBz9Yg?QdZwF|an67Xd*x!He)Gc8&2!urh z4_uXzbYz-aX)X1>&iUjGp;P1u8&7TID0bTH-jCL&Xk8b&;;6p2op_=y^m@Nq*0{#o!!A;wNAFG@0%Z9rHo zcJs?Th>Ny6+hI`+1XoU*ED$Yf@9f91m9Y=#N(HJP^Y@ZEYR6I?oM{>&Wq4|v0IB(p zqX#Z<_3X(&{H+{3Tr|sFy}~=bv+l=P;|sBz$wk-n^R`G3p0(p>p=5ahpaD7>r|>pm zv;V`_IR@tvZreIuv2EM7ZQHhO+qUgw#kOs%*ekY^n|=1#x9&c;Ro&I~{rG-#_3ZB1 z?|9}IFdbP}^DneP*T-JaoYHt~r@EfvnPE5EKUwIxjPbsr$% zfWW83pgWST7*B(o=kmo)74$8UU)v0{@4DI+ci&%=#90}!CZz|rnH+Mz=HN~97G3~@ z;v5(9_2%eca(9iu@J@aqaMS6*$TMw!S>H(b z4(*B!|H|8&EuB%mITr~O?vVEf%(Gr)6E=>H~1VR z&1YOXluJSG1!?TnT)_*YmJ*o_Q@om~(GdrhI{$Fsx_zrkupc#y{DK1WOUR>tk>ZE) ziOLoBkhZZ?0Uf}cm>GsA>Rd6V8@JF)J*EQlQ<=JD@m<)hyElXR0`pTku*3MU`HJn| zIf7$)RlK^pW-$87U;431;Ye4Ie+l~_B3*bH1>*yKzn23cH0u(i5pXV! z4K?{3oF7ZavmmtTq((wtml)m6i)8X6ot_mrE-QJCW}Yn!(3~aUHYG=^fA<^~`e3yc z-NWTb{gR;DOUcK#zPbN^D*e=2eR^_!(!RKkiwMW@@yYtEoOp4XjOGgzi`;=8 zi3`Ccw1%L*y(FDj=C7Ro-V?q)-%p?Ob2ZElu`eZ99n14-ZkEV#y5C+{Pq87Gu3&>g zFy~Wk7^6v*)4pF3@F@rE__k3ikx(hzN3@e*^0=KNA6|jC^B5nf(XaoQaZN?Xi}Rn3 z$8&m*KmWvPaUQ(V<#J+S&zO|8P-#!f%7G+n_%sXp9=J%Z4&9OkWXeuZN}ssgQ#Tcj z8p6ErJQJWZ+fXLCco=RN8D{W%+*kko*2-LEb))xcHwNl~Xmir>kmAxW?eW50Osw3# zki8Fl$#fvw*7rqd?%E?}ZX4`c5-R&w!Y0#EBbelVXSng+kUfeUiqofPehl}$ormli zg%r)}?%=?_pHb9`Cq9Z|B`L8b>(!+8HSX?`5+5mm81AFXfnAt1*R3F z%b2RPIacKAddx%JfQ8l{3U|vK@W7KB$CdLqn@wP^?azRks@x8z59#$Q*7q!KilY-P zHUbs(IFYRGG1{~@RF;Lqyho$~7^hNC`NL3kn^Td%A7dRgr_&`2k=t+}D-o9&C!y^? z6MsQ=tc3g0xkK(O%DzR9nbNB(r@L;1zQrs8mzx&4dz}?3KNYozOW5;=w18U6$G4U2 z#2^qRLT*Mo4bV1Oeo1PKQ2WQS2Y-hv&S|C7`xh6=Pj7MNLC5K-zokZ67S)C;(F0Dd zloDK2_o1$Fmza>EMj3X9je7e%Q`$39Dk~GoOj89-6q9|_WJlSl!!+*{R=tGp z8u|MuSwm^t7K^nUe+^0G3dkGZr3@(X+TL5eah)K^Tn zXEtHmR9UIaEYgD5Nhh(s*fcG_lh-mfy5iUF3xxpRZ0q3nZ=1qAtUa?(LnT9I&~uxX z`pV?+=|-Gl(kz?w!zIieXT}o}7@`QO>;u$Z!QB${a08_bW0_o@&9cjJUXzVyNGCm8 zm=W+$H!;_Kzp6WQqxUI;JlPY&`V}9C$8HZ^m?NvI*JT@~BM=()T()Ii#+*$y@lTZBkmMMda>7s#O(1YZR+zTG@&}!EXFG{ zEWPSDI5bFi;NT>Yj*FjH((=oe%t%xYmE~AGaOc4#9K_XsVpl<4SP@E!TgC0qpe1oi zNpxU2b0(lEMcoibQ-G^cxO?ySVW26HoBNa;n0}CWL*{k)oBu1>F18X061$SP{Gu67 z-v-Fa=Fl^u3lnGY^o5v)Bux}bNZ~ z5pL+7F_Esoun8^5>z8NFoIdb$sNS&xT8_|`GTe8zSXQzs4r^g0kZjg(b0bJvz`g<70u9Z3fQILX1Lj@;@+##bP|FAOl)U^9U>0rx zGi)M1(Hce)LAvQO-pW!MN$;#ZMX?VE(22lTlJrk#pB0FJNqVwC+*%${Gt#r_tH9I_ z;+#)#8cWAl?d@R+O+}@1A^hAR1s3UcW{G+>;X4utD2d9X(jF555}!TVN-hByV6t+A zdFR^aE@GNNgSxxixS2p=on4(+*+f<8xrwAObC)D5)4!z7)}mTpb7&ofF3u&9&wPS< zB62WHLGMhmrmOAgmJ+|c>qEWTD#jd~lHNgT0?t-p{T=~#EMcB| z=AoDKOL+qXCfk~F)-Rv**V}}gWFl>liXOl7Uec_8v)(S#av99PX1sQIVZ9eNLkhq$ zt|qu0b?GW_uo}TbU8!jYn8iJeIP)r@;!Ze_7mj{AUV$GEz6bDSDO=D!&C9!M@*S2! zfGyA|EPlXGMjkH6x7OMF?gKL7{GvGfED=Jte^p=91FpCu)#{whAMw`vSLa`K#atdN zThnL+7!ZNmP{rc=Z>%$meH;Qi1=m1E3Lq2D_O1-X5C;!I0L>zur@tPAC9*7Jeh)`;eec}1`nkRP(%iv-`N zZ@ip-g|7l6Hz%j%gcAM}6-nrC8oA$BkOTz^?dakvX?`^=ZkYh%vUE z9+&)K1UTK=ahYiaNn&G5nHUY5niLGus@p5E2@RwZufRvF{@$hW{;{3QhjvEHMvduO z#Wf-@oYU4ht?#uP{N3utVzV49mEc9>*TV_W2TVC`6+oI)zAjy$KJrr=*q##&kobiQ z1vNbya&OVjK`2pdRrM?LuK6BgrLN7H_3m z!qpNKg~87XgCwb#I=Q&0rI*l$wM!qTkXrx1ko5q-f;=R2fImRMwt5Qs{P*p^z@9ex z`2#v(qE&F%MXlHpdO#QEZyZftn4f05ab^f2vjxuFaat2}jke{j?5GrF=WYBR?gS(^ z9SBiNi}anzBDBRc+QqizTTQuJrzm^bNA~A{j%ugXP7McZqJ}65l10({wk++$=e8O{ zxWjG!Qp#5OmI#XRQQM?n6?1ztl6^D40hDJr?4$Wc&O_{*OfMfxe)V0=e{|N?J#fgE>j9jAajze$iN!*yeF%jJU#G1c@@rm zolGW!j?W6Q8pP=lkctNFdfgUMg92wlM4E$aks1??M$~WQfzzzXtS)wKrr2sJeCN4X zY(X^H_c^PzfcO8Bq(Q*p4c_v@F$Y8cHLrH$`pJ2}=#*8%JYdqsqnGqEdBQMpl!Ot04tUGSXTQdsX&GDtjbWD=prcCT9(+ z&UM%lW%Q3yrl1yiYs;LxzIy>2G}EPY6|sBhL&X&RAQrSAV4Tlh2nITR?{6xO9ujGu zr*)^E`>o!c=gT*_@6S&>0POxcXYNQd&HMw6<|#{eSute2C3{&h?Ah|cw56-AP^f8l zT^kvZY$YiH8j)sk7_=;gx)vx-PW`hbSBXJGCTkpt;ap(}G2GY=2bbjABU5)ty%G#x zAi07{Bjhv}>OD#5zh#$0w;-vvC@^}F! z#X$@)zIs1L^E;2xDAwEjaXhTBw2<{&JkF*`;c3<1U@A4MaLPe{M5DGGkL}#{cHL%* zYMG+-Fm0#qzPL#V)TvQVI|?_M>=zVJr9>(6ib*#z8q@mYKXDP`k&A4A};xMK0h=yrMp~JW{L?mE~ph&1Y1a#4%SO)@{ zK2juwynUOC)U*hVlJU17%llUxAJFuKZh3K0gU`aP)pc~bE~mM!i1mi!~LTf>1Wp< zuG+ahp^gH8g8-M$u{HUWh0m^9Rg@cQ{&DAO{PTMudV6c?ka7+AO& z746QylZ&Oj`1aqfu?l&zGtJnpEQOt;OAFq19MXTcI~`ZcoZmyMrIKDFRIDi`FH)w; z8+*8tdevMDv*VtQi|e}CnB_JWs>fhLOH-+Os2Lh!&)Oh2utl{*AwR)QVLS49iTp{6 z;|172Jl!Ml17unF+pd+Ff@jIE-{Oxv)5|pOm@CkHW?{l}b@1>Pe!l}VccX#xp@xgJ zyE<&ep$=*vT=}7vtvif0B?9xw_3Gej7mN*dOHdQPtW5kA5_zGD zpA4tV2*0E^OUimSsV#?Tg#oiQ>%4D@1F5@AHwT8Kgen$bSMHD3sXCkq8^(uo7CWk`mT zuslYq`6Yz;L%wJh$3l1%SZv#QnG3=NZ=BK4yzk#HAPbqXa92;3K5?0kn4TQ`%E%X} z&>Lbt!!QclYKd6+J7Nl@xv!uD%)*bY-;p`y^ZCC<%LEHUi$l5biu!sT3TGGSTPA21 zT8@B&a0lJHVn1I$I3I1I{W9fJAYc+8 zVj8>HvD}&O`TqU2AAb={?eT;0hyL(R{|h23=4fDSZKC32;wWxsVj`P z3J3{M$PwdH!ro*Cn!D&=jnFR>BNGR<<|I8CI@+@658Dy(lhqbhXfPTVecY@L8%`3Q z1Fux2w?2C3th60jI~%OC9BtpNF$QPqcG+Pz96qZJ71_`0o0w_q7|h&O>`6U+^BA&5 zXd5Zp1Xkw~>M%RixTm&OqpNl8Q+ue=92Op_>T~_9UON?ZM2c0aGm=^A4ejrXj3dV9 zhh_bCt-b9`uOX#cFLj!vhZ#lS8Tc47OH>*)y#{O9?AT~KR9LntM|#l#Dlm^8{nZdk zjMl#>ZM%#^nK2TPzLcKxqx24P7R1FPlBy7LSBrRvx>fE$9AJ;7{PQm~^LBX^k#6Zq zw*Z(zJC|`!6_)EFR}8|n8&&Rbj8y028~P~sFXBFRt+tmqH-S3<%N;C&WGH!f3{7cm zy_fCAb9@HqaXa1Y5vFbxWf%#zg6SI$C+Uz5=CTO}e|2fjWkZ;Dx|84Ow~bkI=LW+U zuq;KSv9VMboRvs9)}2PAO|b(JCEC_A0wq{uEj|3x@}*=bOd zwr{TgeCGG>HT<@Zeq8y}vTpwDg#UBvD)BEs@1KP$^3$sh&_joQPn{hjBXmLPJ{tC) z*HS`*2+VtJO{|e$mM^|qv1R*8i(m1`%)}g=SU#T#0KlTM2RSvYUc1fP+va|4;5}Bfz98UvDCpq7}+SMV&;nX zQw~N6qOX{P55{#LQkrZk(e5YGzr|(B;Q;ju;2a`q+S9bsEH@i1{_Y0;hWYn1-79jl z5c&bytD*k)GqrVcHn6t-7kinadiD>B{Tl`ZY@`g|b~pvHh5!gKP4({rp?D0aFd_cN zhHRo4dd5^S6ViN(>(28qZT6E>??aRhc($kP`>@<+lIKS5HdhjVU;>f7<4))E*5|g{ z&d1}D|vpuV^eRj5j|xx9nwaCxXFG?Qbjn~_WSy=N}P0W>MP zG-F%70lX5Xr$a)2i6?i|iMyM|;Jtf*hO?=Jxj12oz&>P=1#h~lf%#fc73M2_(SUM- zf&qnjS80|_Y0lDgl&I?*eMumUklLe_=Td!9G@eR*tcPOgIShJipp3{A10u(4eT~DY zHezEj8V+7m!knn7)W!-5QI3=IvC^as5+TW1@Ern@yX| z7Nn~xVx&fGSr+L%4iohtS3w^{-H1A_5=r&x8}R!YZvp<2T^YFvj8G_vm}5q;^UOJf ztl=X3iL;;^^a#`t{Ae-%5Oq{?M#s6Npj+L(n-*LMI-yMR{)qki!~{5z{&`-iL}lgW zxo+tnvICK=lImjV$Z|O_cYj_PlEYCzu-XBz&XC-JVxUh9;6*z4fuBG+H{voCC;`~GYV|hj%j_&I zDZCj>Q_0RCwFauYoVMiUSB+*Mx`tg)bWmM^SwMA+?lBg12QUF_x2b)b?qb88K-YUd z0dO}3k#QirBV<5%jL$#wlf!60dizu;tsp(7XLdI=eQs?P`tOZYMjVq&jE)qK*6B^$ zBe>VvH5TO>s>izhwJJ$<`a8fakTL!yM^Zfr2hV9`f}}VVUXK39p@G|xYRz{fTI+Yq z20d=)iwjuG9RB$%$^&8#(c0_j0t_C~^|n+c`Apu|x7~;#cS-s=X1|C*YxX3ailhg_|0`g!E&GZJEr?bh#Tpb8siR=JxWKc{#w7g zWznLwi;zLFmM1g8V5-P#RsM@iX>TK$xsWuujcsVR^7TQ@!+vCD<>Bk9tdCo7Mzgq5 zv8d>dK9x8C@Qoh01u@3h0X_`SZluTb@5o;{4{{eF!-4405x8X7hewZWpz z2qEi4UTiXTvsa(0X7kQH{3VMF>W|6;6iTrrYD2fMggFA&-CBEfSqPlQDxqsa>{e2M z(R5PJ7uOooFc|9GU0ELA%m4&4Ja#cQpNw8i8ACAoK6?-px+oBl_yKmenZut#Xumjz zk8p^OV2KY&?5MUwGrBOo?ki`Sxo#?-Q4gw*Sh0k`@ zFTaYK2;}%Zk-68`#5DXU$2#=%YL#S&MTN8bF+!J2VT6x^XBci6O)Q#JfW{YMz) zOBM>t2rSj)n#0a3cjvu}r|k3od6W(SN}V-cL?bi*Iz-8uOcCcsX0L>ZXjLqk zZu2uHq5B|Kt>e+=pPKu=1P@1r9WLgYFq_TNV1p9pu0erHGd!+bBp!qGi+~4A(RsYN@CyXNrC&hxGmW)u5m35OmWwX`I+0yByglO`}HC4nGE^_HUs^&A(uaM zKPj^=qI{&ayOq#z=p&pnx@@k&I1JI>cttJcu@Ihljt?6p^6{|ds`0MoQwp+I{3l6` zB<9S((RpLG^>=Kic`1LnhpW2=Gu!x`m~=y;A`Qk!-w`IN;S8S930#vBVMv2vCKi}u z6<-VPrU0AnE&vzwV(CFC0gnZYcpa-l5T0ZS$P6(?9AM;`Aj~XDvt;Jua=jIgF=Fm? zdp=M$>`phx%+Gu};;-&7T|B1AcC#L4@mW5SV_^1BRbo6;2PWe$r+npRV`yc;T1mo& z+~_?7rA+(Um&o@Tddl zL_hxvWk~a)yY}%j`Y+200D%9$bWHy&;(yj{jpi?Rtz{J66ANw)UyPOm;t6FzY3$hx zcn)Ir79nhFvNa7^a{SHN7XH*|Vlsx`CddPnA&Qvh8aNhEA;mPVv;Ah=k<*u!Zq^7 z<=xs*iQTQOMMcg|(NA_auh@x`3#_LFt=)}%SQppP{E>mu_LgquAWvh<>L7tf9+~rO znwUDS52u)OtY<~!d$;m9+87aO+&`#2ICl@Y>&F{jI=H(K+@3M1$rr=*H^dye#~TyD z!){#Pyfn+|ugUu}G;a~!&&0aqQ59U@UT3|_JuBlYUpT$2+11;}JBJ`{+lQN9T@QFY z5+`t;6(TS0F?OlBTE!@7D`8#URDNqx2t6`GZ{ZgXeS@v%-eJzZOHz18aS|svxII$a zZeFjrJ*$IwX$f-Rzr_G>xbu@euGl)B7pC&S+CmDJBg$BoV~jxSO#>y z33`bupN#LDoW0feZe0%q8un0rYN|eRAnwDHQ6e_)xBTbtoZtTA=Fvk){q}9Os~6mQ zKB80VI_&6iSq`LnK7*kfHZoeX6?WE}8yjuDn=2#JG$+;-TOA1%^=DnXx%w{b=w}tS zQbU3XxtOI8E(!%`64r2`zog;5<0b4i)xBmGP^jiDZ2%HNSxIf3@wKs~uk4%3Mxz;~ zts_S~E4>W+YwI<-*-$U8*^HKDEa8oLbmqGg?3vewnaNg%Mm)W=)lcC_J+1ov^u*N3 zXJ?!BrH-+wGYziJq2Y#vyry6Z>NPgkEk+Ke`^DvNRdb>Q2Nlr#v%O@<5hbflI6EKE z9dWc0-ORk^T}jP!nkJ1imyjdVX@GrjOs%cpgA8-c&FH&$(4od#x6Y&=LiJZPINVyW z0snY$8JW@>tc2}DlrD3StQmA0Twck~@>8dSix9CyQOALcREdxoM$Sw*l!}bXKq9&r zysMWR@%OY24@e`?+#xV2bk{T^C_xSo8v2ZI=lBI*l{RciPwuE>L5@uhz@{!l)rtVlWC>)6(G)1~n=Q|S!{E9~6*fdpa*n z!()-8EpTdj=zr_Lswi;#{TxbtH$8*G=UM`I+icz7sr_SdnHXrv=?iEOF1UL+*6O;% zPw>t^kbW9X@oEXx<97%lBm-9?O_7L!DeD)Me#rwE54t~UBu9VZ zl_I1tBB~>jm@bw0Aljz8! zXBB6ATG6iByKIxs!qr%pz%wgqbg(l{65DP4#v(vqhhL{0b#0C8mq`bnqZ1OwFV z7mlZZJFMACm>h9v^2J9+^_zc1=JjL#qM5ZHaThH&n zXPTsR8(+)cj&>Un{6v*z?@VTLr{TmZ@-fY%*o2G}*G}#!bmqpoo*Ay@U!JI^Q@7gj;Kg-HIrLj4}#ec4~D2~X6vo;ghep-@&yOivYP zC19L0D`jjKy1Yi-SGPAn94(768Tcf$urAf{)1)9W58P`6MA{YG%O?|07!g9(b`8PXG1B1Sh0?HQmeJtP0M$O$hI z{5G`&9XzYhh|y@qsF1GnHN|~^ru~HVf#)lOTSrv=S@DyR$UKQk zjdEPFDz{uHM&UM;=mG!xKvp;xAGHOBo~>_=WFTmh$chpC7c`~7?36h)7$fF~Ii}8q zF|YXxH-Z?d+Q+27Rs3X9S&K3N+)OBxMHn1u(vlrUC6ckBY@@jl+mgr#KQUKo#VeFm zFwNYgv0<%~Wn}KeLeD9e1$S>jhOq&(e*I@L<=I5b(?G(zpqI*WBqf|Zge0&aoDUsC zngMRA_Kt0>La+Erl=Uv_J^p(z=!?XHpenzn$%EA`JIq#yYF?JLDMYiPfM(&Csr#f{ zdd+LJL1by?xz|D8+(fgzRs~(N1k9DSyK@LJygwaYX8dZl0W!I&c^K?7)z{2is;OkE zd$VK-(uH#AUaZrp=1z;O*n=b?QJkxu`Xsw&7yrX0?(CX=I-C#T;yi8a<{E~?vr3W> zQrpPqOW2M+AnZ&p{hqmHZU-;Q(7?- zP8L|Q0RM~sB0w1w53f&Kd*y}ofx@c z5Y6B8qGel+uT1JMot$nT1!Tim6{>oZzJXdyA+4euOLME?5Fd_85Uk%#E*ln%y{u8Q z$|?|R@Hpb~yTVK-Yr_S#%NUy7EBfYGAg>b({J|5b+j-PBpPy$Ns`PaJin4JdRfOaS zE|<HjH%NuJgsd2wOlv>~y=np%=2)$M9LS|>P)zJ+Fei5vYo_N~B0XCn+GM76 z)Xz3tg*FRVFgIl9zpESgdpWAavvVViGlU8|UFY{{gVJskg*I!ZjWyk~OW-Td4(mZ6 zB&SQreAAMqwp}rjy`HsG({l2&q5Y52<@AULVAu~rWI$UbFuZs>Sc*x+XI<+ez%$U)|a^unjpiW0l0 zj1!K0(b6$8LOjzRqQ~K&dfbMIE=TF}XFAi)$+h}5SD3lo z%%Qd>p9se=VtQG{kQ;N`sI)G^u|DN#7{aoEd zkksYP%_X$Rq08);-s6o>CGJ<}v`qs%eYf+J%DQ^2k68C%nvikRsN?$ap--f+vCS`K z#&~)f7!N^;sdUXu54gl3L=LN>FB^tuK=y2e#|hWiWUls__n@L|>xH{%8lIJTd5`w? zSwZbnS;W~DawT4OwSJVdAylbY+u5S+ZH{4hAi2&}Iv~W(UvHg(1GTZRPz`@{SOqzy z(8g&Dz=$PfRV=6FgxN~zo+G8OoPI&d-thcGVR*_^(R8COTM@bq?fDwY{}WhsQS1AK zF6R1t8!RdFmfocpJ6?9Yv~;WYi~XPgs(|>{5})j!AR!voO7y9&cMPo#80A(`za@t>cx<0;qxM@S*m(jYP)dMXr*?q0E`oL;12}VAep179uEr8c<=D zr5?A*C{eJ`z9Ee;E$8)MECqatHkbHH z&Y+ho0B$31MIB-xm&;xyaFCtg<{m~M-QDbY)fQ>Q*Xibb~8ytxZQ?QMf9!%cV zU0_X1@b4d+Pg#R!`OJ~DOrQz3@cpiGy~XSKjZQQ|^4J1puvwKeScrH8o{bscBsowomu z^f12kTvje`yEI3eEXDHJ6L+O{Jv$HVj%IKb|J{IvD*l6IG8WUgDJ*UGz z3!C%>?=dlfSJ>4U88)V+`U-!9r^@AxJBx8R;)J4Fn@`~k>8>v0M9xp90OJElWP&R5 zM#v*vtT}*Gm1^)Bv!s72T3PB0yVIjJW)H7a)ilkAvoaH?)jjb`MP>2z{%Y?}83 zUIwBKn`-MSg)=?R)1Q0z3b>dHE^)D8LFs}6ASG1|daDly_^lOSy&zIIhm*HXm1?VS=_iacG);_I9c zUQH1>i#*?oPIwBMJkzi_*>HoUe}_4o>2(SHWzqQ=;TyhAHS;Enr7!#8;sdlty&(>d zl%5cjri8`2X^Ds`jnw7>A`X|bl=U8n+3LKLy(1dAu8`g@9=5iw$R0qk)w8Vh_Dt^U zIglK}sn^)W7aB(Q>HvrX=rxB z+*L)3DiqpQ_%~|m=44LcD4-bxO3OO*LPjsh%p(k?&jvLp0py57oMH|*IMa(<|{m1(0S|x)?R-mqJ=I;_YUZA>J z62v*eSK;5w!h8J+6Z2~oyGdZ68waWfy09?4fU&m7%u~zi?YPHPgK6LDwphgaYu%0j zurtw)AYOpYKgHBrkX189mlJ`q)w-f|6>IER{5Lk97%P~a-JyCRFjejW@L>n4vt6#hq;!|m;hNE||LK3nw1{bJOy+eBJjK=QqNjI;Q6;Rp5 z&035pZDUZ#%Oa;&_7x0T<7!RW`#YBOj}F380Bq?MjjEhrvlCATPdkCTTl+2efTX$k zH&0zR1n^`C3ef~^sXzJK-)52(T}uTG%OF8yDhT76L~|^+hZ2hiSM*QA9*D5odI1>& z9kV9jC~twA5MwyOx(lsGD_ggYmztXPD`2=_V|ks_FOx!_J8!zM zTzh^cc+=VNZ&(OdN=y4Juw)@8-85lwf_#VMN!Ed(eQiRiLB2^2e`4dp286h@v@`O%_b)Y~A; zv}r6U?zs&@uD_+(_4bwoy7*uozNvp?bXFoB8?l8yG0qsm1JYzIvB_OH4_2G*IIOwT zVl%HX1562vLVcxM_RG*~w_`FbIc!(T=3>r528#%mwwMK}uEhJ()3MEby zQQjzqjWkwfI~;Fuj(Lj=Ug0y`>~C7`w&wzjK(rPw+Hpd~EvQ-ufQOiB4OMpyUKJhw zqEt~jle9d7S~LI~$6Z->J~QJ{Vdn3!c}g9}*KG^Kzr^(7VI5Gk(mHLL{itj_hG?&K4Ws0+T4gLfi3eu$N=`s36geNC?c zm!~}vG6lx9Uf^5M;bWntF<-{p^bruy~f?sk9 zcETAPQZLoJ8JzMMg<-=ju4keY@SY%Wo?u9Gx=j&dfa6LIAB|IrbORLV1-H==Z1zCM zeZcOYpm5>U2fU7V*h;%n`8 zN95QhfD994={1*<2vKLCNF)feKOGk`R#K~G=;rfq}|)s20&MCa65 zUM?xF5!&e0lF%|U!#rD@I{~OsS_?=;s_MQ_b_s=PuWdC)q|UQ&ea)DMRh5>fpQjXe z%9#*x=7{iRCtBKT#H>#v%>77|{4_slZ)XCY{s3j_r{tdpvb#|r|sbS^dU1x70$eJMU!h{Y7Kd{dl}9&vxQl6Jt1a` zHQZrWyY0?!vqf@u-fxU_@+}u(%Wm>0I#KP48tiAPYY!TdW(o|KtVI|EUB9V`CBBNaBLVih7+yMVF|GSoIQD0Jfb{ z!OXq;(>Z?O`1gap(L~bUcp>Lc@Jl-})^=6P%<~~9ywY=$iu8pJ0m*hOPzr~q`23eX zgbs;VOxxENe0UMVeN*>uCn9Gk!4siN-e>x)pIKAbQz!G)TcqIJ0`JBBaX>1-4_XO_-HCS^vr2vjv#7KltDZdyQ{tlWh4$Gm zB>|O1cBDC)yG(sbnc*@w6e%e}r*|IhpXckx&;sQCwGdKH+3oSG-2)Bf#x`@<4ETAr z0My%7RFh6ZLiZ_;X6Mu1YmXx7C$lSZ^}1h;j`EZd6@%JNUe=btBE z%s=Xmo1Ps?8G`}9+6>iaB8bgjUdXT?=trMu|4yLX^m0Dg{m7rpKNJey|EwHI+nN1e zL^>qN%5Fg)dGs4DO~uwIdXImN)QJ*Jhpj7$fq_^`{3fwpztL@WBB}OwQ#Epo-mqMO zsM$UgpFiG&d#)lzEQ{3Q;)&zTw;SzGOah-Dpm{!q7<8*)Ti_;xvV2TYXa}=faXZy? z3y?~GY@kl)>G&EvEijk9y1S`*=zBJSB1iet>0;x1Ai)*`^{pj0JMs)KAM=@UyOGtO z3y0BouW$N&TnwU6!%zS%nIrnANvZF&vB1~P5_d`x-giHuG zPJ;>XkVoghm#kZXRf>qxxEix;2;D1CC~NrbO6NBX!`&_$iXwP~P*c($EVV|669kDO zKoTLZNF4Cskh!Jz5ga9uZ`3o%7Pv`d^;a=cXI|>y;zC3rYPFLQkF*nv(r>SQvD*## z(Vo%^9g`%XwS0t#94zPq;mYGLKu4LU3;txF26?V~A0xZbU4Lmy`)>SoQX^m7fd^*E z+%{R4eN!rIk~K)M&UEzxp9dbY;_I^c} zOc{wlIrN_P(PPqi51k_$>Lt|X6A^|CGYgKAmoI#Li?;Wq%q~q*L7ehZkUrMxW67Jl zhsb~+U?33QS>eqyN{(odAkbopo=Q$Az?L+NZW>j;#~@wCDX?=L5SI|OxI~7!Pli;e zELMFcZtJY3!|=Gr2L4>z8yQ-{To>(f80*#;6`4IAiqUw`=Pg$%C?#1 z_g@hIGerILSU>=P>z{gM|DS91A4cT@PEIB^hSop!uhMo#2G;+tQSpDO_6nOnPWSLU zS;a9m^DFMXR4?*X=}d7l;nXuHk&0|m`NQn%d?8|Ab3A9l9Jh5s120ibWBdB z$5YwsK3;wvp!Kn@)Qae{ef`0#NwlRpQ}k^r>yos_Ne1;xyKLO?4)t_G4eK~wkUS2A&@_;)K0-03XGBzU+5f+uMDxC z(s8!8!RvdC#@`~fx$r)TKdLD6fWEVdEYtV#{ncT-ZMX~eI#UeQ-+H(Z43vVn%Yj9X zLdu9>o%wnWdvzA-#d6Z~vzj-}V3FQ5;axDIZ;i(95IIU=GQ4WuU{tl-{gk!5{l4_d zvvb&uE{%!iFwpymz{wh?bKr1*qzeZb5f6e6m_ozRF&zux2mlK=v_(_s^R6b5lu?_W4W3#<$zeG~Pd)^!4tzhs}-Sx$FJP>)ZGF(hVTH|C3(U zs0PO&*h_ zNA-&qZpTP$$LtIgfiCn07}XDbK#HIXdmv8zdz4TY;ifNIH-0jy(gMSByG2EF~Th#eb_TueZC` zE?3I>UTMpKQ})=C;6p!?G)M6w^u*A57bD?2X`m3X^6;&4%i_m(uGJ3Z5h`nwxM<)H z$I5m?wN>O~8`BGnZ=y^p6;0+%_0K}Dcg|K;+fEi|qoBqvHj(M&aHGqNF48~XqhtU? z^ogwBzRlOfpAJ+Rw7IED8lRbTdBdyEK$gPUpUG}j-M42xDj_&qEAQEtbs>D#dRd7Y z<&TpSZ(quQDHiCFn&0xsrz~4`4tz!CdL8m~HxZM_agu@IrBpyeL1Ft}V$HX_ZqDPm z-f89)pjuEzGdq-PRu`b1m+qBGY{zr_>{6Ss>F|xHZlJj9dt5HD$u`1*WZe)qEIuDSR)%z+|n zatVlhQ?$w#XRS7xUrFE;Y8vMGhQS5*T{ZnY=q1P?w5g$OKJ#M&e??tAmPWHMj3xhS ziGxapy?kn@$~2%ZY;M8Bc@%$pkl%Rvj!?o%agBvpQ-Q61n9kznC4ttrRNQ4%GFR5u zyv%Yo9~yxQJWJSfj z?#HY$y=O~F|2pZs22pu|_&Ajd+D(Mt!nPUG{|1nlvP`=R#kKH zO*s$r_%ss5h1YO7k0bHJ2CXN)Yd6CHn~W!R=SqkWe=&nAZu(Q1G!xgcUilM@YVei@2@a`8he z9@pM`)VB*=e7-MWgLlXlc)t;fF&-AwM{E-EX}pViFn0I0CNw2bNEnN2dj!^4(^zS3 zobUm1uQnpqk_4q{pl*n06=TfK_C>UgurKFjRXsK_LEn};=79`TB12tv6KzwSu*-C8 z;=~ohDLZylHQ|Mpx-?yql>|e=vI1Z!epyUpAcDCp4T|*RV&X`Q$0ogNwy6mFALo^@ z9=&(9txO8V@E!@6^(W0{*~CT>+-MA~vnJULBxCTUW>X5>r7*eXYUT0B6+w@lzw%n> z_VjJ<2qf|(d6jYq2(x$(ZDf!yVkfnbvNmb5c|hhZ^2TV_LBz`9w!e_V*W_(MiA7|= z&EeIIkw*+$Xd!)j8<@_<}A5;~A_>3JT*kX^@}cDoLd>Qj<`Se^wdUa(j0dp+Tl8EptwBm{9OGsdFEq zM`!pjf(Lm(`$e3FLOjqA5LnN5o!}z{ zNf}rJuZh@yUtq&ErjHeGzX4(!luV!jB&;FAP|!R_QHYw#^Z1LwTePAKJ6X&IDNO#; z)#I@Xnnzyij~C@UH~X51JCgQeF0&hTXnuoElz#m{heZRexWc0k4<>0+ClX7%0 zEBqCCld1tD9Zwkr4{?Nor19#E5-YKfB8d?qgR82-Ow2^AuNevly2*tHA|sK!ybYkX zm-sLQH72P&{vEAW6+z~O5d0qd=xW~rua~5a?ymYFSD@8&gV)E5@RNNBAj^C99+Z5Z zR@Pq55mbCQbz+Mn$d_CMW<-+?TU960agEk1J<>d>0K=pF19yN))a~4>m^G&tc*xR+yMD*S=yip-q=H zIlredHpsJV8H(32@Zxc@bX6a21dUV95Th--8pE6C&3F>pk=yv$yd6@Haw;$v4+Fcb zRwn{Qo@0`7aPa2LQOP}j9v>sjOo5Kqvn|`FLizX zB+@-u4Lw|jsvz{p^>n8Vo8H2peIqJJnMN}A)q6%$Tmig7eu^}K2 zrh$X?T|ZMsoh{6pdw1G$_T<`Ds-G=jc;qcGdK4{?dN2-XxjDNbb(7pk|3JUVCU4y; z)?LXR>f+AAu)JEiti_Zy#z5{RgsC}R(@jl%9YZ>zu~hKQ*AxbvhC378-I@{~#%Y`Z zy=a=9YpewPIC+gkEUUwtUL7|RU7=!^Aa}Mk^6uxOgRGA#JXjWLsjFUnix|Mau{hDT z7mn*z1m5g`vP(#tjT0Zy4eAY(br&!RiiXE=ZI!{sE1#^#%x^Z7t1U)b<;%Y}Q9=5v z;wpDCEZ@OE36TWT=|gxigT@VaW9BvHS05;_P(#s z8zI4XFQys}q)<`tkX$WnSarn{3e!s}4(J!=Yf>+Y>cP3f;vr63f2{|S^`_pWc)^5_!R z*(x-fuBxL51@xe!lnDBKi}Br$c$BMZ3%f2Sa6kLabiBS{pq*yj;q|k(86x`PiC{p6 z_bxCW{>Q2BA8~Ggz&0jkrcU+-$ANBsOop*ms>34K9lNYil@}jC;?cYP(m^P}nR6FV zk(M%48Z&%2Rx$A&FhOEirEhY0(dn;-k(qkTU)sFQ`+-ih+s@A8g?r8Pw+}2;35WYf zi}VO`jS`p(tc)$X$a>-#WXoW!phhatC*$}|rk>|wUU71eUJG^$c6_jwX?iSHM@6__ zvV|6%U*$sSXJu9SX?2%M^kK|}a2QJ8AhF{fuXrHZxXsI~O zGKX45!K7p*MCPEQ=gp?eu&#AW*pR{lhQR##P_*{c_DjMGL|3T3-bSJ(o$|M{ytU}> zAV>wq*uE*qFo9KvnA^@juy{x<-u*#2NvkV={Ly}ysKYB-k`K3@K#^S1Bb$8Y#0L0# z`6IkSG&|Z$ODy|VLS+y5pFJx&8tvPmMd8c9FhCyiU8~k6FwkakUd^(_ml8`rnl>JS zZV){9G*)xBqPz^LDqRwyS6w86#D^~xP4($150M)SOZRe9sn=>V#aG0Iy(_^YcPpIz8QYM-#s+n% z@Jd?xQq?Xk6=<3xSY7XYP$$yd&Spu{A#uafiIfy8gRC`o0nk{ezEDjb=q_qRAlR1d zFq^*9Gn)yTG4b}R{!+3hWQ+u3GT~8nwl2S1lpw`s0X_qpxv)g+JIkVKl${sYf_nV~B>Em>M;RlqGb5WVil(89 zs=ld@|#;dq1*vQGz=7--Br-|l) zZ%Xh@v8>B7P?~}?Cg$q9_={59l%m~O&*a6TKsCMAzG&vD>k2WDzJ6!tc!V)+oxF;h zJH;apM=wO?r_+*#;ulohuP=E>^zon}a$NnlcQ{1$SO*i=jnGVcQa^>QOILc)e6;eNTI>os=eaJ{*^DE+~jc zS}TYeOykDmJ=6O%>m`i*>&pO_S;qMySJIyP=}4E&J%#1zju$RpVAkZbEl+p%?ZP^C z*$$2b4t%a(e+%>a>d_f_<JjxI#J1x;=hPd1zFPx=6T$;;X1TD*2(edZ3f46zaAoW>L53vS_J*N8TMB|n+;LD| zC=GkQPpyDY#Am4l49chDv*gojhRj_?63&&8#doW`INATAo(qY#{q}%nf@eTIXmtU< zdB<7YWfyCmBs|c)cK>1)v&M#!yNj#4d$~pVfDWQc_ke1?fw{T1Nce_b`v|Vp5ig(H zJvRD^+ps46^hLX;=e2!2e;w9y1D@!D$c@Jc&%%%IL=+xzw55&2?darw=9g~>P z9>?Kdc$r?6c$m%x2S$sdpPl>GQZ{rC9mPS63*qjCVa?OIBj!fW zm|g?>CVfGXNjOfcyqImXR_(tXS(F{FcoNzKvG5R$IgGaxC@)i(e+$ME}vPVIhd|mx2IIE+f zM?9opQHIVgBWu)^A|RzXw!^??S!x)SZOwZaJkGjc<_}2l^eSBm!eAJG9T>EC6I_sy z?bxzDIAn&K5*mX)$RQzDA?s)-no-XF(g*yl4%+GBf`##bDXJ==AQk*xmnatI;SsLp zP9XTHq5mmS=iWu~9ES>b%Q=1aMa|ya^vj$@qz9S!ih{T8_PD%Sf_QrNKwgrXw9ldm zHRVR98*{C?_XNpJn{abA!oix_mowRMu^2lV-LPi;0+?-F(>^5#OHX-fPED zCu^l7u3E%STI}c4{J2!)9SUlGP_@!d?5W^QJXOI-Ea`hFMKjR7TluLvzC-ozCPn1`Tpy z!vlv@_Z58ILX6>nDjTp-1LlFMx~-%GA`aJvG$?8*Ihn;mH37eK**rmOEwqegf-Ccx zrIX4;{c~RK>XuTXxYo5kMiWMy)!IC{*DHG@E$hx?RwP@+wuad(P1{@%tRkyJRqD)3 zMHHHZ4boqDn>-=DgR5VlhQTpfVy182Gk;A_S8A1-;U1RR>+$62>(MUx@Nox$vTjHq z%QR=j!6Gdyb5wu7y(YUktwMuW5<@jl?m4cv4BODiT5o8qVdC0MBqGr@-YBIwnpZAY znX9(_uQjP}JJ=!~Ve9#5I~rUnN|P_3D$LqZcvBnywYhjlMSFHm`;u9GPla{5QD7(7*6Tb3Svr8;(nuAd81q$*uq6HC_&~je*Ca7hP4sJp0av{M8480wF zxASi7Qv+~@2U%Nu1Ud;s-G4CTVWIPyx!sg&8ZG0Wq zG_}i3C(6_1>q3w!EH7$Kwq8uBp2F2N7}l65mk1p*9v0&+;th=_E-W)E;w}P(j⁢ zv5o9#E7!G0XmdzfsS{efPNi`1b44~SZ4Z8fuX!I}#8g+(wxzQwUT#Xb2(tbY1+EUhGKoT@KEU9Ktl>_0 z%bjDJg;#*gtJZv!-Zs`?^}v5eKmnbjqlvnSzE@_SP|LG_PJ6CYU+6zY6>92%E+ z=j@TZf-iW4(%U{lnYxQA;7Q!b;^brF8n0D>)`q5>|WDDXLrqYU_tKN2>=#@~OE7grMnNh?UOz-O~6 z6%rHy{#h9K0AT+lDC7q4{hw^|q6*Ry;;L%Q@)Ga}$60_q%D)rv(CtS$CQbpq9|y1e zRSrN4;$Jyl{m5bZw`$8TGvb}(LpY{-cQ)fcyJv7l3S52TLXVDsphtv&aPuDk1OzCA z4A^QtC(!11`IsNx_HnSy?>EKpHJWT^wmS~hc^p^zIIh@9f6U@I2 zC=Mve{j2^)mS#U$e{@Q?SO6%LDsXz@SY+=cK_QMmXBIU)j!$ajc-zLx3V60EXJ!qC zi<%2x8Q24YN+&8U@CIlN zrZkcT9yh%LrlGS9`G)KdP(@9Eo-AQz@8GEFWcb7U=a0H^ZVbLmz{+&M7W(nXJ4sN8 zJLR7eeK(K8`2-}j(T7JsO`L!+CvbueT%izanm-^A1Dn{`1Nw`9P?cq;7no+XfC`K(GO9?O^5zNIt4M+M8LM0=7Gz8UA@Z0N+lg+cX)NfazRu z5D)~HA^(u%w^cz+@2@_#S|u>GpB+j4KzQ^&Wcl9f z&hG#bCA(Yk0D&t&aJE^xME^&E-&xGHhXn%}psEIj641H+Nl-}boj;)Zt*t(4wZ5DN z@GXF$bL=&pBq-#vkTkh>7hl%K5|3 z{`Vn9b$iR-SoGENp}bn4;fR3>9sA%X2@1L3aE9yTra;Wb#_`xWwLSLdfu+PAu+o3| zGVnpzPr=ch{uuoHjtw7+_!L_2;knQ!DuDl0R`|%jr+}jFzXtrHIKc323?JO{l&;VF z*L1+}JU7%QJOg|5|Tc|D8fN zJORAg=_vsy{ak|o);@)Yh8Lkcg@$FG3k@ep36BRa^>~UmnRPziS>Z=`Jb2x*Q#`%A zU*i3&Vg?TluO@X0O;r2Jl6LKLUOVhSqg1*qOt^|8*c7 zo(298@+r$k_wQNGHv{|$tW(T8L+4_`FQ{kEW5Jgg{yf7ey4ss_(SNKfz(N9lx&a;< je(UuV8hP?p&}TPdm1I$XmG#(RzlD&B2izSj9sl%y5~4qc diff --git a/gradle/wrapper/gradle-wrapper.properties b/gradle/wrapper/gradle-wrapper.properties index 3fa8f862f75..1af9e0930b8 100644 --- a/gradle/wrapper/gradle-wrapper.properties +++ b/gradle/wrapper/gradle-wrapper.properties @@ -1,6 +1,6 @@ distributionBase=GRADLE_USER_HOME distributionPath=wrapper/dists -distributionUrl=https\://services.gradle.org/distributions/gradle-8.4-bin.zip +distributionUrl=https\://services.gradle.org/distributions/gradle-8.5-bin.zip networkTimeout=10000 validateDistributionUrl=true zipStoreBase=GRADLE_USER_HOME From f5fc101fda8d59264615e5c27140ae3661e4fdef Mon Sep 17 00:00:00 2001 From: Gold856 <117957790+Gold856@users.noreply.github.com> Date: Wed, 6 Dec 2023 21:28:38 -0500 Subject: [PATCH 9/9] [build] cmake: Export jars and clean up jar installs (#6014) --- CMakeLists.txt | 2 ++ apriltag/CMakeLists.txt | 6 ++---- apriltag/apriltag-config.cmake.in | 3 +++ cameraserver/CMakeLists.txt | 10 ++++++---- cameraserver/cameraserver-config.cmake.in | 3 +++ cscore/CMakeLists.txt | 6 ++---- cscore/cscore-config.cmake.in | 3 +++ hal/CMakeLists.txt | 6 ++---- hal/hal-config.cmake.in | 3 +++ ntcore/CMakeLists.txt | 6 ++---- ntcore/ntcore-config.cmake.in | 3 +++ romiVendordep/CMakeLists.txt | 10 ++++++---- romiVendordep/romiVendordep-config.cmake.in | 3 +++ wpilib-config.cmake.in | 4 ++++ wpilibNewCommands/CMakeLists.txt | 10 ++++++---- wpilibNewCommands/wpilibNewCommands-config.cmake.in | 3 +++ wpilibj/CMakeLists.txt | 6 ++---- wpimath/CMakeLists.txt | 6 ++---- wpimath/wpimath-config.cmake.in | 5 ++++- wpinet/CMakeLists.txt | 6 ++---- wpinet/wpinet-config.cmake.in | 3 +++ wpiunits/CMakeLists.txt | 7 ++----- wpiutil/CMakeLists.txt | 6 ++---- wpiutil/wpiutil-config.cmake.in | 3 +++ xrpVendordep/CMakeLists.txt | 10 ++++++---- xrpVendordep/xrpVendordep-config.cmake.in | 3 +++ 26 files changed, 82 insertions(+), 54 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index 249b542681c..726a1e8cc4e 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -219,9 +219,11 @@ set(CSCORE_DEP_REPLACE_IMPL "find_dependency(cscore)") set(HAL_DEP_REPLACE_IMPL "find_dependency(hal)") set(NTCORE_DEP_REPLACE "find_dependency(ntcore)") set(WPILIBC_DEP_REPLACE_IMPL "find_dependency(wpilibc)") +set(WPILIBJ_DEP_REPLACE "find_dependency(wpilibj)") set(WPILIBNEWCOMMANDS_DEP_REPLACE "find_dependency(wpilibNewCommands)") set(WPIMATH_DEP_REPLACE "find_dependency(wpimath)") set(WPINET_DEP_REPLACE "find_dependency(wpinet)") +set(WPIUNITS_DEP_REPLACE "find_dependency(wpiunits)") set(WPIUTIL_DEP_REPLACE "find_dependency(wpiutil)") set(FILENAME_DEP_REPLACE "get_filename_component(SELF_DIR \"$\{CMAKE_CURRENT_LIST_FILE\}\" PATH)") diff --git a/apriltag/CMakeLists.txt b/apriltag/CMakeLists.txt index 0e9ed8e6075..9ec2a698b25 100644 --- a/apriltag/CMakeLists.txt +++ b/apriltag/CMakeLists.txt @@ -64,10 +64,8 @@ if(WITH_JAVA) GENERATE_NATIVE_HEADERS apriltag_jni_headers ) - get_property(APRILTAG_JAR_FILE TARGET apriltag_jar PROPERTY JAR_FILE) - install(FILES ${APRILTAG_JAR_FILE} DESTINATION "${java_lib_dest}") - - set_property(TARGET apriltag_jar PROPERTY FOLDER "java") + install_jar(apriltag_jar DESTINATION ${java_lib_dest}) + install_jar_exports(TARGETS apriltag_jar FILE apriltag_jar.cmake DESTINATION share/apriltag) add_library(apriltagjni ${apriltag_jni_src}) wpilib_target_warnings(apriltagjni) diff --git a/apriltag/apriltag-config.cmake.in b/apriltag/apriltag-config.cmake.in index 7477a0eff63..9cb609335a5 100644 --- a/apriltag/apriltag-config.cmake.in +++ b/apriltag/apriltag-config.cmake.in @@ -5,3 +5,6 @@ include(CMakeFindDependencyMacro) @FILENAME_DEP_REPLACE@ include(${SELF_DIR}/apriltag.cmake) +if(@WITH_JAVA@) + include(${SELF_DIR}/apriltag_jar.cmake) +endif() diff --git a/cameraserver/CMakeLists.txt b/cameraserver/CMakeLists.txt index fc1a3acf31c..6290049238c 100644 --- a/cameraserver/CMakeLists.txt +++ b/cameraserver/CMakeLists.txt @@ -31,10 +31,12 @@ if(WITH_JAVA) OUTPUT_NAME cameraserver ) - get_property(CAMERASERVER_JAR_FILE TARGET cameraserver_jar PROPERTY JAR_FILE) - install(FILES ${CAMERASERVER_JAR_FILE} DESTINATION "${java_lib_dest}") - - set_property(TARGET cameraserver_jar PROPERTY FOLDER "java") + install_jar(cameraserver_jar DESTINATION ${java_lib_dest}) + install_jar_exports( + TARGETS cameraserver_jar + FILE cameraserver_jar.cmake + DESTINATION share/cameraserver + ) endif() if(WITH_JAVA_SOURCE) diff --git a/cameraserver/cameraserver-config.cmake.in b/cameraserver/cameraserver-config.cmake.in index 94d681389c9..46d522d121c 100644 --- a/cameraserver/cameraserver-config.cmake.in +++ b/cameraserver/cameraserver-config.cmake.in @@ -7,3 +7,6 @@ find_dependency(OpenCV) @FILENAME_DEP_REPLACE@ include(${SELF_DIR}/cameraserver.cmake) +if(@WITH_JAVA@) + include(${SELF_DIR}/cameraserver_jar.cmake) +endif() diff --git a/cscore/CMakeLists.txt b/cscore/CMakeLists.txt index e3345644651..7891486f3fb 100644 --- a/cscore/CMakeLists.txt +++ b/cscore/CMakeLists.txt @@ -129,8 +129,8 @@ if(WITH_JAVA) GENERATE_NATIVE_HEADERS cscore_jni_headers ) - get_property(CSCORE_JAR_FILE TARGET cscore_jar PROPERTY JAR_FILE) - install(FILES ${CSCORE_JAR_FILE} DESTINATION "${java_lib_dest}") + install_jar(cscore_jar DESTINATION ${java_lib_dest}) + install_jar_exports(TARGETS cscore_jar FILE cscore_jar.cmake DESTINATION share/cscore) install(FILES ${OPENCV_JAR_FILE} DESTINATION "${java_lib_dest}") if(MSVC) @@ -153,8 +153,6 @@ if(WITH_JAVA) endforeach() endif() - set_property(TARGET cscore_jar PROPERTY FOLDER "java") - add_library(cscorejni ${cscore_jni_src}) wpilib_target_warnings(cscorejni) target_link_libraries(cscorejni PUBLIC cscore wpiutil ${OpenCV_LIBS}) diff --git a/cscore/cscore-config.cmake.in b/cscore/cscore-config.cmake.in index 33e0af365ed..da5a71f696f 100644 --- a/cscore/cscore-config.cmake.in +++ b/cscore/cscore-config.cmake.in @@ -5,3 +5,6 @@ find_dependency(OpenCV) @FILENAME_DEP_REPLACE@ include(${SELF_DIR}/cscore.cmake) +if(@WITH_JAVA@) + include(${SELF_DIR}/cscore_jar.cmake) +endif() diff --git a/hal/CMakeLists.txt b/hal/CMakeLists.txt index a7d59b6f7db..3333e9b4e50 100644 --- a/hal/CMakeLists.txt +++ b/hal/CMakeLists.txt @@ -74,10 +74,8 @@ if(WITH_JAVA) GENERATE_NATIVE_HEADERS hal_jni_headers ) - get_property(HAL_JAR_FILE TARGET hal_jar PROPERTY JAR_FILE) - install(FILES ${HAL_JAR_FILE} DESTINATION "${java_lib_dest}") - - set_property(TARGET hal_jar PROPERTY FOLDER "java") + install_jar(hal_jar DESTINATION ${java_lib_dest}) + install_jar_exports(TARGETS hal_jar FILE hal_jar.cmake DESTINATION share/hal) add_library(haljni ${hal_shared_jni_src}) diff --git a/hal/hal-config.cmake.in b/hal/hal-config.cmake.in index 49eac3d40d3..7429597b0e7 100644 --- a/hal/hal-config.cmake.in +++ b/hal/hal-config.cmake.in @@ -4,3 +4,6 @@ include(CMakeFindDependencyMacro) @FILENAME_DEP_REPLACE@ include(${SELF_DIR}/hal.cmake) +if(@WITH_JAVA@) + include(${SELF_DIR}/hal_jar.cmake) +endif() diff --git a/ntcore/CMakeLists.txt b/ntcore/CMakeLists.txt index b56b3d8557e..d87571f5a79 100644 --- a/ntcore/CMakeLists.txt +++ b/ntcore/CMakeLists.txt @@ -60,10 +60,8 @@ if(WITH_JAVA) GENERATE_NATIVE_HEADERS ntcore_jni_headers ) - get_property(NTCORE_JAR_FILE TARGET ntcore_jar PROPERTY JAR_FILE) - install(FILES ${NTCORE_JAR_FILE} DESTINATION "${java_lib_dest}") - - set_property(TARGET ntcore_jar PROPERTY FOLDER "java") + install_jar(ntcore_jar DESTINATION ${java_lib_dest}) + install_jar_exports(TARGETS ntcore_jar FILE ntcore_jar.cmake DESTINATION share/ntcore) add_library(ntcorejni ${ntcore_jni_src}) wpilib_target_warnings(ntcorejni) diff --git a/ntcore/ntcore-config.cmake.in b/ntcore/ntcore-config.cmake.in index 0a85f8b09d7..9642d635ae4 100644 --- a/ntcore/ntcore-config.cmake.in +++ b/ntcore/ntcore-config.cmake.in @@ -5,3 +5,6 @@ include(CMakeFindDependencyMacro) @FILENAME_DEP_REPLACE@ include(${SELF_DIR}/ntcore.cmake) +if(@WITH_JAVA@) + include(${SELF_DIR}/ntcore_jar.cmake) +endif() diff --git a/romiVendordep/CMakeLists.txt b/romiVendordep/CMakeLists.txt index d7f5703ed4a..7ef8bde3370 100644 --- a/romiVendordep/CMakeLists.txt +++ b/romiVendordep/CMakeLists.txt @@ -25,10 +25,12 @@ if(WITH_JAVA) OUTPUT_NAME romiVendordep ) - get_property(ROMIVENDORDEP_JAR_FILE TARGET romiVendordep_jar PROPERTY JAR_FILE) - install(FILES ${ROMIVENDORDEP_JAR_FILE} DESTINATION "${java_lib_dest}") - - set_property(TARGET romiVendordep_jar PROPERTY FOLDER "java") + install_jar(romiVendordep_jar DESTINATION ${java_lib_dest}) + install_jar_exports( + TARGETS romiVendordep_jar + FILE romiVendordep_jar.cmake + DESTINATION share/romiVendordep + ) endif() if(WITH_JAVA_SOURCE) diff --git a/romiVendordep/romiVendordep-config.cmake.in b/romiVendordep/romiVendordep-config.cmake.in index 3711d9cd6dc..2843d3e728a 100644 --- a/romiVendordep/romiVendordep-config.cmake.in +++ b/romiVendordep/romiVendordep-config.cmake.in @@ -9,3 +9,6 @@ include(CMakeFindDependencyMacro) @FILENAME_DEP_REPLACE@ include(${SELF_DIR}/romiVendordep.cmake) + if(@WITH_JAVA@) + include(${SELF_DIR}/romiVendordep_jar.cmake) + endif() diff --git a/wpilib-config.cmake.in b/wpilib-config.cmake.in index 018c39ce933..c08e9d20012 100644 --- a/wpilib-config.cmake.in +++ b/wpilib-config.cmake.in @@ -15,3 +15,7 @@ find_dependency(Threads) @WPIMATH_DEP_REPLACE@ @WPINET_DEP_REPLACE@ @WPIUTIL_DEP_REPLACE@ +if(@WITH_JAVA@) + @WPILIBJ_DEP_REPLACE@ + @WPIUNITS_DEP_REPLACE@ +endif() diff --git a/wpilibNewCommands/CMakeLists.txt b/wpilibNewCommands/CMakeLists.txt index ef3ff496d57..0671e467dd6 100644 --- a/wpilibNewCommands/CMakeLists.txt +++ b/wpilibNewCommands/CMakeLists.txt @@ -25,10 +25,12 @@ if(WITH_JAVA) OUTPUT_NAME wpilibNewCommands ) - get_property(WPILIBNEWCOMMANDS_JAR_FILE TARGET wpilibNewCommands_jar PROPERTY JAR_FILE) - install(FILES ${WPILIBNEWCOMMANDS_JAR_FILE} DESTINATION "${java_lib_dest}") - - set_property(TARGET wpilibNewCommands_jar PROPERTY FOLDER "java") + install_jar(wpilibNewCommands_jar DESTINATION ${java_lib_dest}) + install_jar_exports( + TARGETS wpilibNewCommands_jar + FILE wpilibNewCommands_jar.cmake + DESTINATION share/wpilibNewCommands + ) endif() if(WITH_JAVA_SOURCE) diff --git a/wpilibNewCommands/wpilibNewCommands-config.cmake.in b/wpilibNewCommands/wpilibNewCommands-config.cmake.in index 8a8d8d8ecba..7f33a403d10 100644 --- a/wpilibNewCommands/wpilibNewCommands-config.cmake.in +++ b/wpilibNewCommands/wpilibNewCommands-config.cmake.in @@ -9,3 +9,6 @@ include(CMakeFindDependencyMacro) @FILENAME_DEP_REPLACE@ include(${SELF_DIR}/wpilibNewCommands.cmake) + if(@WITH_JAVA@) + include(${SELF_DIR}/wpilibNewCommands_jar.cmake) + endif() diff --git a/wpilibj/CMakeLists.txt b/wpilibj/CMakeLists.txt index 9c8bd988959..624e87a39a4 100644 --- a/wpilibj/CMakeLists.txt +++ b/wpilibj/CMakeLists.txt @@ -40,10 +40,8 @@ if(WITH_JAVA) OUTPUT_NAME wpilibj ) - get_property(WPILIBJ_JAR_FILE TARGET wpilibj_jar PROPERTY JAR_FILE) - install(FILES ${WPILIBJ_JAR_FILE} DESTINATION "${java_lib_dest}") - - set_property(TARGET wpilibj_jar PROPERTY FOLDER "java") + install_jar(wpilibj_jar DESTINATION ${java_lib_dest}) + install_jar_exports(TARGETS wpilibj_jar FILE wpilibj.cmake DESTINATION share/wpilibj) install(FILES wpilibj-config.cmake DESTINATION share/wpilibj) endif() diff --git a/wpimath/CMakeLists.txt b/wpimath/CMakeLists.txt index f938c4df7e1..d8a9a294359 100644 --- a/wpimath/CMakeLists.txt +++ b/wpimath/CMakeLists.txt @@ -83,10 +83,8 @@ if(WITH_JAVA) GENERATE_NATIVE_HEADERS wpimath_jni_headers ) - get_property(WPIMATH_JAR_FILE TARGET wpimath_jar PROPERTY JAR_FILE) - install(FILES ${WPIMATH_JAR_FILE} DESTINATION "${java_lib_dest}") - - set_property(TARGET wpimath_jar PROPERTY FOLDER "java") + install_jar(wpimath_jar DESTINATION ${java_lib_dest}) + install_jar_exports(TARGETS wpimath_jar FILE wpimath_jar.cmake DESTINATION share/wpimath) add_library(wpimathjni ${wpimath_jni_src}) wpilib_target_warnings(wpimathjni) diff --git a/wpimath/wpimath-config.cmake.in b/wpimath/wpimath-config.cmake.in index 8697dc1836e..3618a1fe8c7 100644 --- a/wpimath/wpimath-config.cmake.in +++ b/wpimath/wpimath-config.cmake.in @@ -1,7 +1,6 @@ include(CMakeFindDependencyMacro) @FILENAME_DEP_REPLACE@ @WPIUTIL_DEP_REPLACE@ -@WPIUNITS_DEP_REPLACE@ if(@USE_SYSTEM_EIGEN@) find_dependency(Eigen3) @@ -9,3 +8,7 @@ endif() @FILENAME_DEP_REPLACE@ include(${SELF_DIR}/wpimath.cmake) +if(@WITH_JAVA@) + @WPIUNITS_DEP_REPLACE@ + include(${SELF_DIR}/wpimath_jar.cmake) +endif() diff --git a/wpinet/CMakeLists.txt b/wpinet/CMakeLists.txt index 12763b16e1b..b2c7e04bb77 100644 --- a/wpinet/CMakeLists.txt +++ b/wpinet/CMakeLists.txt @@ -26,10 +26,8 @@ if(WITH_JAVA) GENERATE_NATIVE_HEADERS wpinet_jni_headers ) - get_property(WPINET_JAR_FILE TARGET wpinet_jar PROPERTY JAR_FILE) - install(FILES ${WPINET_JAR_FILE} DESTINATION "${java_lib_dest}") - - set_property(TARGET wpinet_jar PROPERTY FOLDER "java") + install_jar(wpinet_jar DESTINATION ${java_lib_dest}) + install_jar_exports(TARGETS wpinet_jar FILE wpinet_jar.cmake DESTINATION share/wpinet) add_library(wpinetjni ${wpinet_jni_src}) wpilib_target_warnings(wpinetjni) diff --git a/wpinet/wpinet-config.cmake.in b/wpinet/wpinet-config.cmake.in index f54fe455b7c..e62719bc2a8 100644 --- a/wpinet/wpinet-config.cmake.in +++ b/wpinet/wpinet-config.cmake.in @@ -5,3 +5,6 @@ include(CMakeFindDependencyMacro) @FILENAME_DEP_REPLACE@ include(${SELF_DIR}/wpinet.cmake) +if(@WITH_JAVA@) + include(${SELF_DIR}/wpinet_jar.cmake) +endif() diff --git a/wpiunits/CMakeLists.txt b/wpiunits/CMakeLists.txt index 40ce217480b..bdbe42b8f5e 100644 --- a/wpiunits/CMakeLists.txt +++ b/wpiunits/CMakeLists.txt @@ -10,10 +10,7 @@ if(WITH_JAVA) add_jar(wpiunits_jar ${JAVA_SOURCES} OUTPUT_NAME wpiunits) - get_property(WPIUNITS_JAR_FILE TARGET wpiunits_jar PROPERTY JAR_FILE) - install(FILES ${WPIUNITS_JAR_FILE} DESTINATION "${java_lib_dest}") - - set_property(TARGET wpiunits_jar PROPERTY FOLDER "java") - + install_jar(wpiunits_jar DESTINATION ${java_lib_dest}) + install_jar_exports(TARGETS wpiunits_jar FILE wpiunits.cmake DESTINATION share/wpiunits) install(FILES wpiunits-config.cmake DESTINATION share/wpiunits) endif() diff --git a/wpiutil/CMakeLists.txt b/wpiutil/CMakeLists.txt index 22a93a31021..083829e1241 100644 --- a/wpiutil/CMakeLists.txt +++ b/wpiutil/CMakeLists.txt @@ -70,10 +70,8 @@ if(WITH_JAVA) GENERATE_NATIVE_HEADERS wpiutil_jni_headers ) - get_property(WPIUTIL_JAR_FILE TARGET wpiutil_jar PROPERTY JAR_FILE) - install(FILES ${WPIUTIL_JAR_FILE} DESTINATION "${java_lib_dest}") - - set_property(TARGET wpiutil_jar PROPERTY FOLDER "java") + install_jar(wpiutil_jar DESTINATION ${java_lib_dest}) + install_jar_exports(TARGETS wpiutil_jar FILE wpiutil_jar.cmake DESTINATION share/wpiutil) add_library(wpiutiljni ${wpiutil_jni_src}) wpilib_target_warnings(wpiutiljni) diff --git a/wpiutil/wpiutil-config.cmake.in b/wpiutil/wpiutil-config.cmake.in index a881a9bf0a2..3926ecb9106 100644 --- a/wpiutil/wpiutil-config.cmake.in +++ b/wpiutil/wpiutil-config.cmake.in @@ -11,3 +11,6 @@ endif() @FILENAME_DEP_REPLACE@ include(${SELF_DIR}/wpiutil.cmake) +if(@WITH_JAVA@) + include(${SELF_DIR}/wpiutil_jar.cmake) +endif() diff --git a/xrpVendordep/CMakeLists.txt b/xrpVendordep/CMakeLists.txt index 291926039fa..7a481947cef 100644 --- a/xrpVendordep/CMakeLists.txt +++ b/xrpVendordep/CMakeLists.txt @@ -25,10 +25,12 @@ if(WITH_JAVA) OUTPUT_NAME xrpVendordep ) - get_property(xrpVendordep_JAR_FILE TARGET xrpVendordep_jar PROPERTY JAR_FILE) - install(FILES ${xrpVendordep_JAR_FILE} DESTINATION "${java_lib_dest}") - - set_property(TARGET xrpVendordep_jar PROPERTY FOLDER "java") + install_jar(xrpVendordep_jar DESTINATION ${java_lib_dest}) + install_jar_exports( + TARGETS xrpVendordep_jar + FILE xrpVendordep_jar.cmake + DESTINATION share/xrpVendordep + ) endif() if(WITH_JAVA_SOURCE) diff --git a/xrpVendordep/xrpVendordep-config.cmake.in b/xrpVendordep/xrpVendordep-config.cmake.in index ad06e4ce2ed..42876940023 100644 --- a/xrpVendordep/xrpVendordep-config.cmake.in +++ b/xrpVendordep/xrpVendordep-config.cmake.in @@ -9,3 +9,6 @@ include(CMakeFindDependencyMacro) @FILENAME_DEP_REPLACE@ include(${SELF_DIR}/xrpVendordep.cmake) + if(@WITH_JAVA@) + include(${SELF_DIR}/xrpVendordep_jar.cmake) + endif()