diff --git a/docs/Robot.md b/docs/Robot.md index 457c8880f..1b79bb616 100644 --- a/docs/Robot.md +++ b/docs/Robot.md @@ -15,11 +15,11 @@ The enum Team in [team.hpp](https://github.com/RoboTeamTwente/roboteam_ai/blob/d `vel` -> Current velocity of the robot -`angle` -> Current angle of the robot +`yaw` -> Current yaw of the robot `distanceToBall` -> Distance from the robot to the ball -`angleDiffToBall` -> Angle offset between the kicker and the ball. +`angleDiffToBall` -> Angle offset between the yaw of the kicker and the vector from robot center to ball `angularVelocity` -> Angular velocity of the robot. @@ -33,9 +33,6 @@ The enum Team in [team.hpp](https://github.com/RoboTeamTwente/roboteam_ai/blob/d `DribblerSeesBall` -> True if the dribbler picks up the ball, false if not. -`ballPos` -> Position of the ball (if seesBall == true) - - ## Functions ## ### Trivial getters and setters, therefore will **not** be covered ## diff --git a/roboteam_ai/include/roboteam_ai/control/ControlModule.h b/roboteam_ai/include/roboteam_ai/control/ControlModule.h index 65f463266..1936ce0c4 100644 --- a/roboteam_ai/include/roboteam_ai/control/ControlModule.h +++ b/roboteam_ai/include/roboteam_ai/control/ControlModule.h @@ -4,7 +4,7 @@ #include #include -#include "control/AnglePID.h" +#include "control/YawPID.h" #include "world/views/RobotView.hpp" namespace rtt::ai::control { @@ -18,8 +18,8 @@ namespace rtt::ai::control { */ class ControlModule { protected: - static inline std::vector robotCommands; /**< Vector of all robot commands */ - static inline std::map simulatorAnglePIDmap; /**< Angle controller for each robot */ + static inline std::vector robotCommands; /**< Vector of all robot commands */ + static inline std::map simulatorYawPIDmap; /**< Yaw controller for each robot */ /** * @brief Applies constraints to the internal robot command diff --git a/roboteam_ai/include/roboteam_ai/control/ControlUtils.h b/roboteam_ai/include/roboteam_ai/control/ControlUtils.h index dfc3fcdc1..84f935871 100644 --- a/roboteam_ai/include/roboteam_ai/control/ControlUtils.h +++ b/roboteam_ai/include/roboteam_ai/control/ControlUtils.h @@ -13,7 +13,6 @@ #include "utilities/Constants.h" using Vector2 = rtt::Vector2; -using Angle = rtt::Angle; namespace rtt::ai::control { diff --git a/roboteam_ai/include/roboteam_ai/control/AnglePID.h b/roboteam_ai/include/roboteam_ai/control/YawPID.h similarity index 66% rename from roboteam_ai/include/roboteam_ai/control/AnglePID.h rename to roboteam_ai/include/roboteam_ai/control/YawPID.h index dcbcf723d..ce1f66f8a 100644 --- a/roboteam_ai/include/roboteam_ai/control/AnglePID.h +++ b/roboteam_ai/include/roboteam_ai/control/YawPID.h @@ -1,13 +1,13 @@ -#ifndef RTT_ANGLEPID_H -#define RTT_ANGLEPID_H +#ifndef RTT_YAWPID_H +#define RTT_YAWPID_H #include "roboteam_utils/Angle.h" #include "roboteam_utils/pid.h" namespace rtt { /** - * @brief Class that controls the angle with a PID + * @brief Class that controls the yaw with a PID */ -class AnglePID { +class YawPID { private: double P; /**< Proportional part of the controller */ double I; /**< Integral part of the controller */ @@ -20,23 +20,23 @@ class AnglePID { public: /** - * @brief Constructor of the AnglePID class + * @brief Constructor of the YawPID class * @param P Proportional part of the controller * @param I Integral part of the controller * @param D Derivative part of the controller * @param max_ang_vel Absolute maximum allowed angular velocity * @param dt Time difference since previous tick */ - AnglePID(double P, double I, double D, double max_ang_vel, double dt) : P{P}, I{I}, D{D}, min{-max_ang_vel}, max{max_ang_vel}, previous_error{0.0}, integral{0.0}, dt{dt} {} + YawPID(double P, double I, double D, double max_ang_vel, double dt) : P{P}, I{I}, D{D}, min{-max_ang_vel}, max{max_ang_vel}, previous_error{0.0}, integral{0.0}, dt{dt} {} /** * @brief Retrieves the angular velocity calculated by the controller - * @param target_angle Angle the robot needs to be at - * @param current_angle Current angle of the robot + * @param target_yaw Yaw the robot needs to be at + * @param current_yaw Current yaw of the robot * @return Target angular velocity */ - double getOutput(Angle target_angle, Angle current_angle); + double getOutput(Angle target_yaw, Angle current_yaw); }; } // namespace rtt -#endif // RTT_ANGLEPID_H +#endif // RTT_YAWPID_H diff --git a/roboteam_ai/include/roboteam_ai/stp/StpInfo.h b/roboteam_ai/include/roboteam_ai/stp/StpInfo.h index 398381205..d2152cd3c 100644 --- a/roboteam_ai/include/roboteam_ai/stp/StpInfo.h +++ b/roboteam_ai/include/roboteam_ai/stp/StpInfo.h @@ -40,11 +40,11 @@ struct StpInfo { double getKickChipVelocity() const { return kickChipVelocity; } void setKickChipVelocity(double kickChipVelocity) { this->kickChipVelocity = kickChipVelocity; } - Angle getAngle() const { return angle; } - void setAngle(double angle) { this->angle = Angle(angle); } + Angle getYaw() const { return yaw; } + void setYaw(double yaw) { this->yaw = Angle(yaw); } - int getDribblerSpeed() const { return dribblerSpeed; } - void setDribblerSpeed(int dribblerSpeed) { this->dribblerSpeed = dribblerSpeed; } + bool getDribblerOn() const { return dribblerOn; } + void setDribblerOn(bool dribblerOn) { this->dribblerOn = dribblerOn; } ShotType getShotType() const { return shotType; } void setShotType(ShotType shotType) { this->shotType = shotType; } @@ -152,14 +152,14 @@ struct StpInfo { ShotType shotType{}; /** - * Reference angle of the robot + * Reference yaw of the robot */ - Angle angle = Angle(0.0); + Angle yaw = Angle(0.0); /** - * Speed of the dribbler in % + * Whether the dribbler should be on */ - int dribblerSpeed = 0; + bool dribblerOn; /** * Set the shot to be a kick or chip diff --git a/roboteam_ai/include/roboteam_ai/stp/constants/ControlConstants.h b/roboteam_ai/include/roboteam_ai/stp/constants/ControlConstants.h index 0c71ddc42..259c3688c 100644 --- a/roboteam_ai/include/roboteam_ai/stp/constants/ControlConstants.h +++ b/roboteam_ai/include/roboteam_ai/stp/constants/ControlConstants.h @@ -37,8 +37,8 @@ constexpr double ENEMY_CLOSE_TO_BALL_DISTANCE = 1.0; /**< Distanc /// RobotCommand limits constexpr double MAX_DRIBBLER_CMD = 1; /**< Maximum allowed dribbler velocity that can be send to the robot */ -// Angle increment per tick -constexpr double ANGLE_RATE = 0.2 * M_PI; /**< Maximum allowed angular velocity that can be send to the robot */ +// Yaw increment per tick +constexpr double YAW_RATE = 0.2 * M_PI; /**< Maximum allowed angular velocity that can be send to the robot */ constexpr double MAX_VEL_WHEN_HAS_BALL = 3.0; /**< Maximum allowed velocity that can be send to the robot when that robot has the ball */ /// GoToPos Constants diff --git a/roboteam_ai/include/roboteam_ai/stp/tactics/KeeperBlockBall.h b/roboteam_ai/include/roboteam_ai/stp/tactics/KeeperBlockBall.h index 503c5df32..c8adbc5aa 100644 --- a/roboteam_ai/include/roboteam_ai/stp/tactics/KeeperBlockBall.h +++ b/roboteam_ai/include/roboteam_ai/stp/tactics/KeeperBlockBall.h @@ -83,12 +83,12 @@ class KeeperBlockBall : public Tactic { static std::pair calculateTargetPosition(const StpInfo info) noexcept; /** - * @brief Calculates the angle the robot should have + * @brief Calculates the yaw the robot should have * @param ball the ball for which the keeper should defend * @param targetKeeperPosition the target position the keeper should have - * @return the angle the robot should have + * @return the yaw the robot should have */ - static Angle calculateTargetAngle(const world::view::BallView &ball, const Vector2 &targetKeeperPosition); + static Angle calculateYaw(const world::view::BallView &ball, const Vector2 &targetKeeperPosition); }; } // namespace rtt::ai::stp::tactic diff --git a/roboteam_ai/include/roboteam_ai/stp/tactics/active/ChipAtPos.h b/roboteam_ai/include/roboteam_ai/stp/tactics/active/ChipAtPos.h index 04f657940..075da6fce 100644 --- a/roboteam_ai/include/roboteam_ai/stp/tactics/active/ChipAtPos.h +++ b/roboteam_ai/include/roboteam_ai/stp/tactics/active/ChipAtPos.h @@ -34,7 +34,7 @@ class ChipAtPos : public Tactic { * @brief Should this tactic be reset (go back to the first skill of this tactic) * @param info StpInfo can be used to check some data * @return true if tactic should reset, false if execution should continue - * Returns true when the robot angle is not within its error margin + * Returns true when the robot yaw is not within its error margin */ bool shouldTacticReset(const StpInfo &info) noexcept override; diff --git a/roboteam_ai/include/roboteam_ai/stp/tactics/active/DriveWithBall.h b/roboteam_ai/include/roboteam_ai/stp/tactics/active/DriveWithBall.h index cc2b80e0b..d3dbc90b1 100644 --- a/roboteam_ai/include/roboteam_ai/stp/tactics/active/DriveWithBall.h +++ b/roboteam_ai/include/roboteam_ai/stp/tactics/active/DriveWithBall.h @@ -32,7 +32,7 @@ class DriveWithBall : public Tactic { /** * @brief Should this tactic be reset (go back to the first skill of this tactic) - * Should reset if the angle the robot is at is no longer correct + * Should reset if the yaw the robot is at is no longer correct * @param info StpInfo can be used to check some data * @return true if tactic should reset, false if execution should continue */ diff --git a/roboteam_ai/include/roboteam_ai/stp/tactics/active/InstantKick.h b/roboteam_ai/include/roboteam_ai/stp/tactics/active/InstantKick.h index 5ae896b60..e459a5bd3 100644 --- a/roboteam_ai/include/roboteam_ai/stp/tactics/active/InstantKick.h +++ b/roboteam_ai/include/roboteam_ai/stp/tactics/active/InstantKick.h @@ -32,7 +32,7 @@ class InstantKick : public Tactic { /** * @brief Should this tactic be reset (go back to the first skill of this tactic) - * Returns true when the robot angle is outside some error margin + * Returns true when the robot yaw is outside some error margin * @param info StpInfo can be used to check some data * @return true if tactic should reset, false if execution should continue */ diff --git a/roboteam_ai/include/roboteam_ai/stp/tactics/active/OrbitKick.h b/roboteam_ai/include/roboteam_ai/stp/tactics/active/OrbitKick.h index 03967abcc..17c264efe 100644 --- a/roboteam_ai/include/roboteam_ai/stp/tactics/active/OrbitKick.h +++ b/roboteam_ai/include/roboteam_ai/stp/tactics/active/OrbitKick.h @@ -32,7 +32,7 @@ class OrbitKick : public Tactic { /** * @brief Should this tactic be reset (go back to the first skill of this tactic) - * Returns true when the robot angle is outside some error margin + * Returns true when the robot yaw is outside some error margin * @param info StpInfo can be used to check some data * @return true if tactic should reset, false if execution should continue */ diff --git a/roboteam_ai/include/roboteam_ai/stp/tactics/active/Receive.h b/roboteam_ai/include/roboteam_ai/stp/tactics/active/Receive.h index 52fab6560..ed1655c26 100644 --- a/roboteam_ai/include/roboteam_ai/stp/tactics/active/Receive.h +++ b/roboteam_ai/include/roboteam_ai/stp/tactics/active/Receive.h @@ -51,7 +51,7 @@ class Receive : public Tactic { const char *getName() override; /** - * @brief Calculates the angle the robot needs to have using the ball position + * @brief Calculates the yaw the robot needs to have using the ball position * @param robot * @param ball * @return Angle the robot should take diff --git a/roboteam_ai/include/roboteam_ai/stp/tactics/passive/Halt.h b/roboteam_ai/include/roboteam_ai/stp/tactics/passive/Halt.h index 51d333987..0f4cb9443 100644 --- a/roboteam_ai/include/roboteam_ai/stp/tactics/passive/Halt.h +++ b/roboteam_ai/include/roboteam_ai/stp/tactics/passive/Halt.h @@ -5,7 +5,7 @@ namespace rtt::ai::stp::tactic { /** - * @brief Class that defines the halt tactic. This tactic is used for halting, it rotates the robot to angle 0 + * @brief Class that defines the halt tactic. This tactic is used for halting, it rotates the robot to yaw 0 * It cannot fail and reset. It's not an * end tactic, therefore it can succeed. */ diff --git a/roboteam_ai/include/roboteam_ai/utilities/Constants.h b/roboteam_ai/include/roboteam_ai/utilities/Constants.h index f8d747350..90336094c 100644 --- a/roboteam_ai/include/roboteam_ai/utilities/Constants.h +++ b/roboteam_ai/include/roboteam_ai/utilities/Constants.h @@ -44,8 +44,8 @@ class Constants { /// ROBOT COMMANDS /// static double MAX_VEL_CMD(); /**< The maximum allowed velocity of the robot */ - static double MIN_ANGLE(); /**< The minimum angle the robot can have */ - static double MAX_ANGLE(); /**< The maximum angle the robot can have */ + static double MIN_YAW(); /**< The minimum yaw the robot can have */ + static double MAX_YAW(); /**< The maximum yaw the robot can have */ static double MAX_ANGULAR_VELOCITY(); /**< The maximum angular velocity of the robot */ static double MAX_ACC(); /**< Maximum acceleration of the robot */ diff --git a/roboteam_ai/include/roboteam_ai/utilities/IOManager.h b/roboteam_ai/include/roboteam_ai/utilities/IOManager.h index 94772a25b..aee173c72 100644 --- a/roboteam_ai/include/roboteam_ai/utilities/IOManager.h +++ b/roboteam_ai/include/roboteam_ai/utilities/IOManager.h @@ -53,10 +53,10 @@ class IOManager { rtt::ai::Pause* pause; /**< Pauses the robots when needed */ /** - * @brief Adds the camera angle from world to the robot commands, so the robot can use it for its angle control - * @param robotCommands the robot commands in which the camera angle needs to be added + * @brief Adds the camera yaw from world to the robot commands, so the robot can use it for its yaw control + * @param robotCommands the robot commands in which the camera yaw needs to be added */ - void addCameraAngleToRobotCommands(rtt::RobotCommands& robotCommands); + void addCameraYawToRobotCommands(rtt::RobotCommands& robotCommands); /** * @brief Publishes the robot commands on the given team's socket. * @param robotCommands Commands that need to be published @@ -67,7 +67,7 @@ class IOManager { public: /** - * @brief Publishes all robot commands with the robot angles from world + * @brief Publishes all robot commands with the robot yaw from world * @param robotCommands Commands that need to be published */ void publishAllRobotCommands(rtt::RobotCommands& robotCommands); diff --git a/roboteam_ai/include/roboteam_ai/world/Robot.hpp b/roboteam_ai/include/roboteam_ai/world/Robot.hpp index 5a4730f9a..0c037e576 100644 --- a/roboteam_ai/include/roboteam_ai/world/Robot.hpp +++ b/roboteam_ai/include/roboteam_ai/world/Robot.hpp @@ -31,7 +31,7 @@ class Robot { Vector2 pos; /**< Position of the robot */ Vector2 vel; /**< Velocity of the robot */ - Angle angle; /**< Angle of the robot */ + Angle yaw; /**< Yaw of the robot */ double distanceToBall; /**< Distance from the robot to the ball */ double angleDiffToBall; /**< Angle of the robot relative to the ball */ @@ -43,7 +43,6 @@ class Robot { bool workingBallSensor{}; /**< Indicates whether the robot has a working ball sensor */ bool ballSensorSeesBall{}; /**< Indicates whether the ball sensor sees the ball */ - float ballPos{}; /**< The position of the ball */ bool dribblerSeesBall{}; /**< Indicates whether the dribbler sees the ball */ bool robotHasBall{}; /**< Indicates whether the robot has the ball */ @@ -63,10 +62,10 @@ class Robot { void updateHasBallMap(std::optional &ball); /** - * @brief Set the angle of the robot according to the given angle - * @param angle The angle to which the robot angle should be set to + * @brief Sets the robot's yaw to the specified yaw + * @param yaw The desired yaw for the robot */ - void setAngle(const Angle &angle) noexcept; + void setYaw(const Angle &yaw) noexcept; /** * @brief Set the batteryLow boolean @@ -87,7 +86,7 @@ class Robot { void setDistanceToBall(double distanceToBall) noexcept; /** - * @brief Set the angle difference to the ball + * @brief Set the yaw difference to the ball * @param _angleDiffToBall The Angle of the robot relative to the ball */ void setAngleDiffToBall(double _angleDiffToBall) noexcept; @@ -110,12 +109,6 @@ class Robot { */ void setHasBall(bool _hasBall) noexcept; - /** - * @brief Set the ball position according to the ball sensor - * @param _ballPos The position of the ball according to the ball sensor - */ - void setBallPosBallSensor(float _ballPos) noexcept; - public: /** * @brief Get the ID of the robot @@ -142,10 +135,10 @@ class Robot { [[nodiscard]] const Vector2 &getVel() const noexcept; /** - * @brief Get the angle of the robot - * @return The angle of the robot + * @brief Get the yaw of the robot + * @return The yaw of the robot */ - [[nodiscard]] const Angle &getAngle() const noexcept; + [[nodiscard]] const Angle &getYaw() const noexcept; /** * @brief Get the angular velocity of the robot @@ -184,8 +177,8 @@ class Robot { [[nodiscard]] double getDistanceToBall() const noexcept; /** - * @brief Get the angle of the robot relative to the ball - * @return The angle of the robot relative to the ball + * @brief Get the yaw of the robot relative to the ball + * @return The yaw of the robot relative to the ball */ [[nodiscard]] double getAngleDiffToBall() const noexcept; diff --git a/roboteam_ai/src/control/ControlModule.cpp b/roboteam_ai/src/control/ControlModule.cpp index db90a8b2d..9e0d7aa8f 100644 --- a/roboteam_ai/src/control/ControlModule.cpp +++ b/roboteam_ai/src/control/ControlModule.cpp @@ -12,7 +12,7 @@ namespace rtt::ai::control { void ControlModule::rotateRobotCommand(rtt::RobotCommand& command) { command.velocity.x = -command.velocity.x; command.velocity.y = -command.velocity.y; - command.targetAngle += M_PI; + command.yaw += M_PI; } void ControlModule::limitRobotCommand(rtt::RobotCommand& command, rtt::world::view::RobotView robot) { @@ -25,26 +25,26 @@ void ControlModule::limitVel(rtt::RobotCommand& command) { } void ControlModule::limitAngularVel(rtt::RobotCommand& command, rtt::world::view::RobotView robot) { - // Limit the angular velocity when the robot has the ball by setting the target angle in small steps + // Limit the angular velocity when the robot has the ball by setting the target yaw in small steps if (robot->hasBall() && !command.useAngularVelocity) { - auto targetAngle = command.targetAngle; - auto robotAngle = robot->getAngle(); + auto yaw = command.yaw; + auto robotYaw = robot->getYaw(); - // Adjust robot angle if game is not on the left + // Adjust robot yaw if game is not on the left if (!GameSettings::isLeft()) { - robotAngle += M_PI; + robotYaw += M_PI; } - // If the angle error is larger than the desired angle rate, adjust the angle command - if (robotAngle.shortestAngleDiff(targetAngle) > stp::control_constants::ANGLE_RATE) { + // If the yaw error is larger than the desired yaw rate, adjust the yaw command + if (robotYaw.shortestAngleDiff(yaw) > stp::control_constants::YAW_RATE) { // Determine direction of rotation (shortest distance) - int direction = Angle(robotAngle).rotateDirection(targetAngle) ? 1 : -1; + int direction = Angle(robotYaw).rotateDirection(yaw) ? 1 : -1; - // Set the angle command to the current robot angle + the angle rate - command.targetAngle = robotAngle + Angle(direction * stp::control_constants::ANGLE_RATE); + // Set the yaw command to the current robot yaw + the yaw rate + command.yaw = robotYaw + Angle(direction * stp::control_constants::YAW_RATE); } } - // TODO: Well, then also limit the target angular velocity just like target angle! + // TODO: Well, then also limit the target angular velocity just like target yaw! } void ControlModule::addRobotCommand(std::optional<::rtt::world::view::RobotView> robot, rtt::RobotCommand command) noexcept { @@ -69,14 +69,14 @@ void ControlModule::addRobotCommand(std::optional<::rtt::world::view::RobotView> void ControlModule::simulator_angular_control(const std::optional<::rtt::world::view::RobotView>& robot, rtt::RobotCommand& robot_command) { double ang_velocity_out = 0.0; // in case there is no robot visible, we just adjust the command to not have any angular velocity if (robot) { - Angle current_angle = robot->get()->getAngle(); + Angle current_yaw = robot->get()->getYaw(); if (!GameSettings::isLeft()) { - current_angle += M_PI; + current_yaw += M_PI; } - Angle target_angle(robot_command.targetAngle); + Angle target_yaw(robot_command.yaw); // get relevant PID controller - if (simulatorAnglePIDmap.contains(robot->get()->getId())) { - ang_velocity_out = simulatorAnglePIDmap.at(robot->get()->getId()).getOutput(target_angle, current_angle); + if (simulatorYawPIDmap.contains(robot->get()->getId())) { + ang_velocity_out = simulatorYawPIDmap.at(robot->get()->getId()).getOutput(target_yaw, current_yaw); } else { // initialize PID controller for robot // below tuning only works ish for erforce, is completely useless in grsim @@ -86,9 +86,9 @@ void ControlModule::simulator_angular_control(const std::optional<::rtt::world:: double max_ang_vel = 5.0; // rad/s double dt = 1. / double(Constants::STP_TICK_RATE()); - AnglePID pid(P, I, D, max_ang_vel, dt); - ang_velocity_out = pid.getOutput(target_angle, current_angle); - simulatorAnglePIDmap.insert({robot->get()->getId(), pid}); + YawPID pid(P, I, D, max_ang_vel, dt); + ang_velocity_out = pid.getOutput(target_yaw, current_yaw); + simulatorYawPIDmap.insert({robot->get()->getId(), pid}); } } robot_command.useAngularVelocity = true; diff --git a/roboteam_ai/src/control/AnglePID.cpp b/roboteam_ai/src/control/YawPID.cpp similarity index 67% rename from roboteam_ai/src/control/AnglePID.cpp rename to roboteam_ai/src/control/YawPID.cpp index beaa6c9e3..239c29aa4 100644 --- a/roboteam_ai/src/control/AnglePID.cpp +++ b/roboteam_ai/src/control/YawPID.cpp @@ -1,11 +1,11 @@ -#include "control/AnglePID.h" +#include "control/YawPID.h" #include -double rtt::AnglePID::getOutput(rtt::Angle target_angle, rtt::Angle current_angle) { - // Calculate error; note that crossing the 'border' between two angles - double dir = current_angle.rotateDirection(target_angle) ? 1.0 : -1.0; - double error = dir * current_angle.shortestAngleDiff(target_angle); +double rtt::YawPID::getOutput(Angle target_yaw, Angle current_yaw) { + // Calculate error; note that crossing the 'border' between two yaws + double dir = current_yaw.rotateDirection(target_yaw) ? 1.0 : -1.0; + double error = dir * current_yaw.shortestAngleDiff(target_yaw); // Proportional term double Pout = P * error; diff --git a/roboteam_ai/src/stp/Play.cpp b/roboteam_ai/src/stp/Play.cpp index 5c326996b..ff7318b6a 100644 --- a/roboteam_ai/src/stp/Play.cpp +++ b/roboteam_ai/src/stp/Play.cpp @@ -219,6 +219,7 @@ void Play::DrawMargins() noexcept { pathToPlacementLocation = {world->getWorld()->getBall()->get()->position, rtt::ai::GameStateManager::getRefereeDesignatedPosition()}; // Drawing all figures regarding states robots have to avoid certain area's (stop, ball placement, free kick, kick off) + proto::Drawing::Color color; if (ruleSetTitle == RuleSetName::STOP || currentGameState == RefCommand::DIRECT_FREE_THEM || currentGameState == RefCommand::DIRECT_FREE_THEM_STOP || currentGameState == RefCommand::DIRECT_FREE_US || currentGameState == RefCommand::KICKOFF_US || currentGameState == RefCommand::KICKOFF_THEM || currentGameState == RefCommand::PREPARE_FORCED_START || currentGameState == RefCommand::BALL_PLACEMENT_THEM || currentGameState == RefCommand::BALL_PLACEMENT_US || @@ -245,7 +246,6 @@ void Play::DrawMargins() noexcept { }, rightDefenseAreaMargin); } - proto::Drawing::Color color; if (currentGameState == RefCommand::BALL_PLACEMENT_THEM || currentGameState == RefCommand::DIRECT_FREE_THEM || currentGameState == RefCommand::KICKOFF_THEM) color = GameSettings::isYellow() ? proto::Drawing::YELLOW : proto::Drawing::BLUE; else if (currentGameState == RefCommand::BALL_PLACEMENT_US || currentGameState == RefCommand::BALL_PLACEMENT_US_DIRECT || currentGameState == RefCommand::DIRECT_FREE_US || @@ -253,18 +253,21 @@ void Play::DrawMargins() noexcept { color = GameSettings::isYellow() ? proto::Drawing::BLUE : proto::Drawing::YELLOW; else color = proto::Drawing::RED; - for (auto method : {proto::Drawing::CIRCLES, proto::Drawing::LINES_CONNECTED}) { - rtt::ai::gui::Out::draw( - { - .label = method == proto::Drawing::CIRCLES ? "Ball area to avoid" : "Path to placement location", - .color = method == proto::Drawing::CIRCLES ? color : proto::Drawing::BLACK, - .method = method, - .category = proto::Drawing::MARGINS, - .size = method == proto::Drawing::CIRCLES ? 52 : 8, - .thickness = method == proto::Drawing::CIRCLES ? 4 : 8, - }, - pathToPlacementLocation); - } + + } + else color = proto::Drawing::GREY; + + for (auto method : {proto::Drawing::CIRCLES, proto::Drawing::LINES_CONNECTED}) { + rtt::ai::gui::Out::draw( + { + .label = method == proto::Drawing::CIRCLES ? "Ball area to avoid" : "Path to placement location", + .color = method == proto::Drawing::CIRCLES ? color : proto::Drawing::BLACK, + .method = method, + .category = proto::Drawing::MARGINS, + .size = method == proto::Drawing::CIRCLES ? 52 : 8, + .thickness = method == proto::Drawing::CIRCLES ? 4 : 8, + }, + pathToPlacementLocation); } // Drawing all figures regarding ball placement location and the path towards it diff --git a/roboteam_ai/src/stp/computations/PositionComputations.cpp b/roboteam_ai/src/stp/computations/PositionComputations.cpp index 3590b3962..d9f1f5182 100644 --- a/roboteam_ai/src/stp/computations/PositionComputations.cpp +++ b/roboteam_ai/src/stp/computations/PositionComputations.cpp @@ -251,18 +251,18 @@ void PositionComputations::calculateInfoForHarasser(std::unordered_mapgetWorld()->getBall()->get()->position - interceptionLocation).angle()); + stpInfos["harasser"].setYaw((world->getWorld()->getBall()->get()->position - interceptionLocation).angle()); return; } - auto enemyAngle = enemyClosestToBall->get()->getAngle(); - auto harasserAngle = stpInfos["harasser"].getAngle(); + auto enemyAngle = enemyClosestToBall->get()->getYaw(); + auto harasserAngle = stpInfos["harasser"].getYaw(); // If enemy is not facing our goal AND does have the ball, stand between the enemy and our goal if (enemyClosestToBall->get()->hasBall() && enemyAngle.shortestAngleDiff(harasserAngle) < M_PI / 1.5) { auto enemyPos = enemyClosestToBall->get()->getPos(); auto targetPos = enemyPos + (field.leftGoalArea.leftLine().center() - enemyPos).stretchToLength(control_constants::ROBOT_RADIUS * 4 + control_constants::GO_TO_POS_ERROR_MARGIN); stpInfos["harasser"].setPositionToMoveTo(targetPos); - stpInfos["harasser"].setAngle((world->getWorld()->getBall()->get()->position - targetPos).angle()); + stpInfos["harasser"].setYaw((world->getWorld()->getBall()->get()->position - targetPos).angle()); } else { auto harasser = std::find_if(roles->begin(), roles->end(), [](const std::unique_ptr &role) { return role != nullptr && role->getName() == "harasser"; }); if (harasser != roles->end() && !harasser->get()->finished() && strcmp(harasser->get()->getCurrentTactic()->getName(), "Formation") == 0) @@ -369,7 +369,7 @@ void PositionComputations::calculateInfoForDefendersAndWallers(std::unordered_ma auto &wallerStpInfo = stpInfos[currentWallerName]; wallerStpInfo.setPositionToMoveTo(positionToMoveTo); - wallerStpInfo.setAngle((world->getWorld()->getBall()->get()->position - field.leftGoalArea.rightLine().center()).angle()); + wallerStpInfo.setYaw((world->getWorld()->getBall()->get()->position - field.leftGoalArea.rightLine().center()).angle()); // If the waller is close to its target, ignore collisions constexpr double IGNORE_COLLISIONS_DISTANCE = 0.4; diff --git a/roboteam_ai/src/stp/plays/referee_specific/BallPlacementThem.cpp b/roboteam_ai/src/stp/plays/referee_specific/BallPlacementThem.cpp index 6bf938319..42cfd7066 100644 --- a/roboteam_ai/src/stp/plays/referee_specific/BallPlacementThem.cpp +++ b/roboteam_ai/src/stp/plays/referee_specific/BallPlacementThem.cpp @@ -71,7 +71,7 @@ void BallPlacementThem::calculateInfoForHarasser() noexcept { auto placementPos = rtt::ai::GameStateManager::getRefereeDesignatedPosition(); auto targetPos = placementPos + (field.leftGoalArea.rightLine().center() - placementPos).stretchToLength(control_constants::AVOID_BALL_DISTANCE); stpInfos["harasser"].setPositionToMoveTo(targetPos); - stpInfos["harasser"].setAngle((placementPos - field.leftGoalArea.rightLine().center()).toAngle()); + stpInfos["harasser"].setYaw((placementPos - field.leftGoalArea.rightLine().center()).toAngle()); } const char* BallPlacementThem::getName() const { return "Ball Placement Them"; } diff --git a/roboteam_ai/src/stp/plays/referee_specific/BallPlacementUsForceStart.cpp b/roboteam_ai/src/stp/plays/referee_specific/BallPlacementUsForceStart.cpp index 0582250ce..1d12734e6 100644 --- a/roboteam_ai/src/stp/plays/referee_specific/BallPlacementUsForceStart.cpp +++ b/roboteam_ai/src/stp/plays/referee_specific/BallPlacementUsForceStart.cpp @@ -94,7 +94,7 @@ void BallPlacementUsForceStart::calculateInfoForRoles() noexcept { if (stpInfos["ball_placer"].getRobot() && stpInfos["ball_placer"].getRobot()->get()->getDistanceToBall() < 1.0) stpInfos["ball_placer"].setMaxRobotVelocity(0.75); if (stpInfos["ball_placer"].getRobot() && stpInfos["ball_placer"].getRobot()->get()->getDistanceToBall() < control_constants::TURN_ON_DRIBBLER_DISTANCE) { - stpInfos["ball_placer"].setDribblerSpeed(100); + stpInfos["ball_placer"].setDribblerOn(true); } } diff --git a/roboteam_ai/src/stp/plays/referee_specific/BallPlacementUsFreeKick.cpp b/roboteam_ai/src/stp/plays/referee_specific/BallPlacementUsFreeKick.cpp index f8c615784..af17056dd 100644 --- a/roboteam_ai/src/stp/plays/referee_specific/BallPlacementUsFreeKick.cpp +++ b/roboteam_ai/src/stp/plays/referee_specific/BallPlacementUsFreeKick.cpp @@ -93,7 +93,7 @@ void BallPlacementUsFreeKick::calculateInfoForRoles() noexcept { } if (stpInfos["ball_placer"].getRobot() && stpInfos["ball_placer"].getRobot()->get()->getDistanceToBall() < 1.0) stpInfos["ball_placer"].setMaxRobotVelocity(0.75); if (stpInfos["ball_placer"].getRobot() && stpInfos["ball_placer"].getRobot()->get()->getDistanceToBall() < control_constants::TURN_ON_DRIBBLER_DISTANCE) { - stpInfos["ball_placer"].setDribblerSpeed(100); + stpInfos["ball_placer"].setDribblerOn(true); } } diff --git a/roboteam_ai/src/stp/plays/referee_specific/FreeKickThem.cpp b/roboteam_ai/src/stp/plays/referee_specific/FreeKickThem.cpp index b297bbb28..5a146c818 100644 --- a/roboteam_ai/src/stp/plays/referee_specific/FreeKickThem.cpp +++ b/roboteam_ai/src/stp/plays/referee_specific/FreeKickThem.cpp @@ -75,7 +75,7 @@ void FreeKickThem::calculateInfoForHarasser() noexcept { auto enemyToBall = (ballPos - enemyClosestToBall->getPos()); auto targetPos = ballPos + (enemyToBall).stretchToLength(control_constants::AVOID_BALL_DISTANCE); stpInfos["harasser"].setPositionToMoveTo(targetPos); - stpInfos["harasser"].setAngle(enemyToBall.angle() + M_PI); + stpInfos["harasser"].setYaw(enemyToBall.angle() + M_PI); } const char* FreeKickThem::getName() const { return "Free Kick Them"; } diff --git a/roboteam_ai/src/stp/plays/referee_specific/PenaltyThemPrepare.cpp b/roboteam_ai/src/stp/plays/referee_specific/PenaltyThemPrepare.cpp index be6df6f84..c89f91679 100644 --- a/roboteam_ai/src/stp/plays/referee_specific/PenaltyThemPrepare.cpp +++ b/roboteam_ai/src/stp/plays/referee_specific/PenaltyThemPrepare.cpp @@ -90,7 +90,7 @@ void PenaltyThemPrepare::calculateInfoForRoles() noexcept { stpInfos[formationName].setPositionToMoveTo(position); auto angleToGoal = (field.leftGoalArea.rightLine().center() - position).toAngle(); - stpInfos[formationName].setAngle(angleToGoal); + stpInfos[formationName].setYaw(angleToGoal); } /// Top row of robots @@ -100,7 +100,7 @@ void PenaltyThemPrepare::calculateInfoForRoles() noexcept { stpInfos[formationName].setPositionToMoveTo(position); auto angleToGoal = (field.leftGoalArea.rightLine().center() - position).toAngle(); - stpInfos[formationName].setAngle(angleToGoal); + stpInfos[formationName].setYaw(angleToGoal); } } diff --git a/roboteam_ai/src/stp/plays/referee_specific/PenaltyUsPrepare.cpp b/roboteam_ai/src/stp/plays/referee_specific/PenaltyUsPrepare.cpp index 4d37c6b11..87ca9c704 100644 --- a/roboteam_ai/src/stp/plays/referee_specific/PenaltyUsPrepare.cpp +++ b/roboteam_ai/src/stp/plays/referee_specific/PenaltyUsPrepare.cpp @@ -96,7 +96,7 @@ void PenaltyUsPrepare::calculateInfoForRoles() noexcept { stpInfos[formationName].setPositionToMoveTo(position); auto angleToGoal = (field.rightGoalArea.leftLine().center() - position).toAngle(); - stpInfos[formationName].setAngle(angleToGoal); + stpInfos[formationName].setYaw(angleToGoal); } /// Top row of robots @@ -106,7 +106,7 @@ void PenaltyUsPrepare::calculateInfoForRoles() noexcept { stpInfos[formationName].setPositionToMoveTo(position); auto angleToGoal = (field.rightGoalArea.leftLine().center() - position).toAngle(); - stpInfos[formationName].setAngle(angleToGoal); + stpInfos[formationName].setYaw(angleToGoal); } } diff --git a/roboteam_ai/src/stp/roles/active/PenaltyTaker.cpp b/roboteam_ai/src/stp/roles/active/PenaltyTaker.cpp index a56ddc32b..aabc63b03 100644 --- a/roboteam_ai/src/stp/roles/active/PenaltyTaker.cpp +++ b/roboteam_ai/src/stp/roles/active/PenaltyTaker.cpp @@ -23,7 +23,7 @@ PenaltyTaker::PenaltyTaker(std::string name) : Role(std::move(name)) { // set position to move to the current position infoCopy.setPositionToMoveTo(currentPos - Vector2(0.1, 0)); if (currentVel.x < 0.1) { - infoCopy.setDribblerSpeed(0); + infoCopy.setDribblerOn(false); } } // if we don't have ball, reset the tactic diff --git a/roboteam_ai/src/stp/skills/Chip.cpp b/roboteam_ai/src/stp/skills/Chip.cpp index fb18281fa..0efa92f04 100644 --- a/roboteam_ai/src/stp/skills/Chip.cpp +++ b/roboteam_ai/src/stp/skills/Chip.cpp @@ -9,11 +9,9 @@ Status Chip::onUpdate(const StpInfo &info) noexcept { command.kickType = KickType::CHIP; command.kickSpeed = chipVelocity; - int targetDribblerPercentage = std::clamp(info.getDribblerSpeed(), 0, 10); - double targetDribblerSpeed = targetDribblerPercentage / 100.0 * stp::control_constants::MAX_DRIBBLER_CMD; - command.dribblerSpeed = targetDribblerSpeed; + command.dribblerOn = info.getDribblerOn(); - command.targetAngle = info.getRobot().value()->getAngle(); + command.yaw = info.getRobot().value()->getYaw(); if (chipAttempts > control_constants::MAX_CHIP_ATTEMPTS) { command.waitForBall = false; diff --git a/roboteam_ai/src/stp/skills/GoToPos.cpp b/roboteam_ai/src/stp/skills/GoToPos.cpp index a8d88c0c8..b8f71beb8 100644 --- a/roboteam_ai/src/stp/skills/GoToPos.cpp +++ b/roboteam_ai/src/stp/skills/GoToPos.cpp @@ -44,11 +44,9 @@ Status GoToPos::onUpdate(const StpInfo &info) noexcept { robot->getVel(), targetPos, info.getMaxRobotVelocity(), avoidObj); auto distanceToTarget = (robot->getPos() - targetPos).length(); - command.targetAngle = distanceToTarget <= 0.5 ? info.getAngle() : robot->getAngle() + rtt::Angle(0.5 / distanceToTarget * (info.getAngle() - robot->getAngle())); + command.yaw = distanceToTarget <= 0.5 ? info.getYaw() : robot->getYaw() + rtt::Angle(0.5 / distanceToTarget * (info.getYaw() - robot->getYaw())); - // Clamp and set dribbler speed - int targetDribblerPercentage = std::clamp(info.getDribblerSpeed(), 0, 100); - command.dribblerSpeed = targetDribblerPercentage / 100.0 * stp::control_constants::MAX_DRIBBLER_CMD; + command.dribblerOn = info.getDribblerOn(); // set command ID command.id = robot->getId(); diff --git a/roboteam_ai/src/stp/skills/Kick.cpp b/roboteam_ai/src/stp/skills/Kick.cpp index 380507ee0..ff458d4d7 100644 --- a/roboteam_ai/src/stp/skills/Kick.cpp +++ b/roboteam_ai/src/stp/skills/Kick.cpp @@ -13,13 +13,10 @@ Status Kick::onUpdate(const StpInfo &info) noexcept { command.kickType = KickType::KICK; command.kickSpeed = kickVelocity; - // Clamp and set dribbler speed - int targetDribblerPercentage = std::clamp(info.getDribblerSpeed(), 0, 100); - double targetDribblerSpeed = targetDribblerPercentage / 100.0 * stp::control_constants::MAX_DRIBBLER_CMD; - command.dribblerSpeed = targetDribblerSpeed; + command.dribblerOn = info.getDribblerOn(); - // Set angle command - command.targetAngle = robot->getAngle(); + // Set yaw command + command.yaw = robot->getYaw(); command.waitForBall = false; diff --git a/roboteam_ai/src/stp/skills/Orbit.cpp b/roboteam_ai/src/stp/skills/Orbit.cpp index 2599bf651..efab3e086 100644 --- a/roboteam_ai/src/stp/skills/Orbit.cpp +++ b/roboteam_ai/src/stp/skills/Orbit.cpp @@ -10,15 +10,15 @@ Status Orbit::onUpdate(const StpInfo &info) noexcept { Vector2 directionVector = ball->position - robot->getPos(); double normalAngle = directionVector.rotate(M_PI).rotate(M_PI_2).angle(); - Angle targetAngle = (info.getPositionToShootAt().value() - ball->position).toAngle(); + Angle yaw = (info.getPositionToShootAt().value() - ball->position).toAngle(); double margin = 1.5 * control_constants::ROBOT_RADIUS + stp::control_constants::BALL_RADIUS; double adjustDistance = robot->getDistanceToBall() - margin; // Get the direction of movement, counterclockwise or clockwise - auto direction = Angle(directionVector).rotateDirection(targetAngle) ? -1.0 : 1.0; + auto direction = Angle(directionVector).rotateDirection(yaw) ? -1.0 : 1.0; - double error = targetAngle.shortestAngleDiff(directionVector.angle()); + double error = yaw.shortestAngleDiff(directionVector.angle()); error = error * direction; // Use PID controller to determine desired velocity multiplier @@ -34,7 +34,7 @@ Status Orbit::onUpdate(const StpInfo &info) noexcept { if (targetVelocity.length() > maxVel) targetVelocity = targetVelocity.stretchToLength(maxVel); command.velocity = targetVelocity; - command.targetAngle = targetAngle; + command.yaw = yaw; command.id = robot->getId(); // forward the generated command to the ControlModule, for checking and limiting @@ -42,7 +42,7 @@ Status Orbit::onUpdate(const StpInfo &info) noexcept { // Check if successful double errorMargin = stp::control_constants::GO_TO_POS_ANGLE_ERROR_MARGIN * M_PI; - if (directionVector.toAngle().shortestAngleDiff(targetAngle) < errorMargin) { + if (directionVector.toAngle().shortestAngleDiff(yaw) < errorMargin) { counter++; } else { counter = 0; diff --git a/roboteam_ai/src/stp/skills/OrbitAngular.cpp b/roboteam_ai/src/stp/skills/OrbitAngular.cpp index b46bd9eb2..ae84e0edc 100644 --- a/roboteam_ai/src/stp/skills/OrbitAngular.cpp +++ b/roboteam_ai/src/stp/skills/OrbitAngular.cpp @@ -8,17 +8,17 @@ Status OrbitAngular::onUpdate(const StpInfo &info) noexcept { auto robot = info.getRobot().value(); auto ball = info.getBall()->get(); - // Calculate target and current angles - Angle currentAngle = robot->getAngle(); - Angle targetAngle = (info.getPositionToShootAt().value() - ball->position).toAngle(); + // Calculate target and current yaws + Angle currentYaw = robot->getYaw(); + Angle yaw = (info.getPositionToShootAt().value() - ball->position).toAngle(); // Determine direction and speed factor - int direction = targetAngle.rotateDirection(currentAngle) ? -1 : 1; - double speedFactor = std::clamp(currentAngle.shortestAngleDiff(targetAngle) * 2 * M_PI, 0.0, M_PI); + int direction = yaw.rotateDirection(currentYaw) ? -1 : 1; + double speedFactor = std::clamp(currentYaw.shortestAngleDiff(yaw) * 2 * M_PI, 0.0, M_PI); // Calculate target angular velocity and normal vector double targetAngularVelocity = direction * speedFactor; - Vector2 normalVector = currentAngle.toVector2().rotate(-direction * M_PI_2); + Vector2 normalVector = currentYaw.toVector2().rotate(-direction * M_PI_2); // Calculate target velocity Vector2 targetVelocity = normalVector * speedFactor * (stp::control_constants::BALL_RADIUS + stp::control_constants::CENTER_TO_FRONT); @@ -27,20 +27,20 @@ Status OrbitAngular::onUpdate(const StpInfo &info) noexcept { command.id = robot->getId(); command.velocity = targetVelocity; // Commented for the control code before the Schubert open on 3 April 2024. Possible wise to use again somewhere in the distant future. - // We could also switch to _just_ using angle, as on all other places in the code. The magic numbers here might still need some love after testing irl. + // We could also switch to _just_ using yaw, as on all other places in the code. The magic numbers here might still need some love after testing irl. // command.useAngularVelocity = true; // command.targetAngularVelocity = targetAngularVelocity; - // command.targetAngle = targetAngle; + // command.yaw = yaw; - // target angle is angular velocity times the time step (1/60th of a second) - command.targetAngle = currentAngle + Angle(targetAngularVelocity * 1 / 2.5); - command.dribblerSpeed = stp::control_constants::MAX_DRIBBLER_CMD; + // target yaw is angular velocity times the time step (1/60th of a second) + command.yaw = currentYaw + Angle(targetAngularVelocity * 1 / 2.5); + command.dribblerOn = stp::control_constants::MAX_DRIBBLER_CMD; forwardRobotCommand(); // Send the robot command // Check if the robot is within the error margin double errorMargin = stp::control_constants::GO_TO_POS_ANGLE_ERROR_MARGIN * M_PI; - if (currentAngle.shortestAngleDiff(targetAngle) < errorMargin) { + if (currentYaw.shortestAngleDiff(yaw) < errorMargin) { withinMarginCount++; } else { withinMarginCount = 0; diff --git a/roboteam_ai/src/stp/skills/Rotate.cpp b/roboteam_ai/src/stp/skills/Rotate.cpp index 2d02bc3e4..4aa2fcac8 100644 --- a/roboteam_ai/src/stp/skills/Rotate.cpp +++ b/roboteam_ai/src/stp/skills/Rotate.cpp @@ -7,13 +7,12 @@ namespace rtt::ai::stp::skill { Status Rotate::onUpdate(const StpInfo &info) noexcept { auto robot = info.getRobot().value(); - auto targetAngle = info.getAngle(); + auto yaw = info.getYaw(); - // Set angle command - command.targetAngle = targetAngle; + // Set yaw command + command.yaw = yaw; - // Set dribbler speed command - command.dribblerSpeed = std::clamp(info.getDribblerSpeed(), 0, 100) / 100.0 * stp::control_constants::MAX_DRIBBLER_CMD; + command.dribblerOn = info.getDribblerOn(); // Set command ID command.id = robot->getId(); @@ -23,7 +22,7 @@ Status Rotate::onUpdate(const StpInfo &info) noexcept { // Check if the robot is within the error margin double errorMargin = stp::control_constants::GO_TO_POS_ANGLE_ERROR_MARGIN * M_PI; - if (robot->getAngle().shortestAngleDiff(targetAngle) < errorMargin) { + if (robot->getYaw().shortestAngleDiff(yaw) < errorMargin) { withinMarginCount++; } else { withinMarginCount = 0; diff --git a/roboteam_ai/src/stp/tactics/KeeperBlockBall.cpp b/roboteam_ai/src/stp/tactics/KeeperBlockBall.cpp index d069a670d..083e8685e 100644 --- a/roboteam_ai/src/stp/tactics/KeeperBlockBall.cpp +++ b/roboteam_ai/src/stp/tactics/KeeperBlockBall.cpp @@ -42,8 +42,8 @@ std::optional KeeperBlockBall::calculateInfoForSkill(const StpInfo &inf skillStpInfo.setShouldAvoidOurRobots(targetPosition.second); skillStpInfo.setShouldAvoidTheirRobots(targetPosition.second); - const auto targetAngle = calculateTargetAngle(info.getBall().value(), targetPosition.first); - skillStpInfo.setAngle(targetAngle); + const auto yaw = calculateYaw(info.getBall().value(), targetPosition.first); + skillStpInfo.setYaw(yaw); return skillStpInfo; } @@ -79,7 +79,7 @@ std::optional KeeperBlockBall::estimateBallTrajectory(const world::vie // If the enemy robot already has the ball, it will probably kick in the direction it is facing if (hasEnemy && enemyRobot->get()->hasBall()) { const auto start = enemyRobot->get()->getPos(); - const auto direction = enemyRobot->get()->getPos() + enemyRobot->get()->getAngle().toVector2(); + const auto direction = enemyRobot->get()->getPos() + enemyRobot->get()->getYaw().toVector2(); return HalfLine(start, direction); } @@ -145,7 +145,7 @@ std::pair KeeperBlockBall::calculateTargetPosition(const StpInfo return {Vector2(keepersLineSegment.start.x, 0), shouldAvoidGoalPosts}; } -Angle KeeperBlockBall::calculateTargetAngle(const world::view::BallView &ball, const Vector2 &targetKeeperPosition) { +Angle KeeperBlockBall::calculateYaw(const world::view::BallView &ball, const Vector2 &targetKeeperPosition) { // Look towards ball to ensure ball hits the front assembly to reduce odds of ball reflecting in goal const auto keeperToBall = (ball->position - targetKeeperPosition) / 1.6; return keeperToBall.angle(); diff --git a/roboteam_ai/src/stp/tactics/active/ChipAtPos.cpp b/roboteam_ai/src/stp/tactics/active/ChipAtPos.cpp index a828941da..747749f7d 100644 --- a/roboteam_ai/src/stp/tactics/active/ChipAtPos.cpp +++ b/roboteam_ai/src/stp/tactics/active/ChipAtPos.cpp @@ -14,13 +14,13 @@ std::optional ChipAtPos::calculateInfoForSkill(const StpInfo &info) noe StpInfo skillStpInfo = info; auto angleToTarget = (info.getPositionToShootAt().value() - info.getRobot().value()->getPos()).angle(); - skillStpInfo.setAngle(angleToTarget); + skillStpInfo.setYaw(angleToTarget); auto distanceBallToTarget = (info.getBall()->get()->position - info.getPositionToShootAt().value()).length(); skillStpInfo.setKickChipVelocity(control::ControlUtils::determineChipForce(distanceBallToTarget)); if (skills.current_num() == 0) { - skillStpInfo.setDribblerSpeed(100); + skillStpInfo.setDribblerOn(true); } return skillStpInfo; @@ -38,7 +38,7 @@ bool ChipAtPos::isTacticFailing(const StpInfo &info) noexcept { bool ChipAtPos::shouldTacticReset(const StpInfo &info) noexcept { if (skills.current_num() != 0) { auto errorMargin = stp::control_constants::GO_TO_POS_ANGLE_ERROR_MARGIN * M_PI; - return info.getRobot().value()->getAngle().shortestAngleDiff(info.getAngle()) > errorMargin; + return info.getRobot().value()->getYaw().shortestAngleDiff(info.getYaw()) > errorMargin; } return false; } diff --git a/roboteam_ai/src/stp/tactics/active/DriveWithBall.cpp b/roboteam_ai/src/stp/tactics/active/DriveWithBall.cpp index fd0baddee..4e145fe84 100644 --- a/roboteam_ai/src/stp/tactics/active/DriveWithBall.cpp +++ b/roboteam_ai/src/stp/tactics/active/DriveWithBall.cpp @@ -12,8 +12,8 @@ std::optional DriveWithBall::calculateInfoForSkill(const StpInfo &info) StpInfo skillStpInfo = info; auto angleToTarget = (info.getPositionToMoveTo().value() - info.getRobot()->get()->getPos()).angle(); - skillStpInfo.setAngle(skills.current_num() == 0 ? angleToTarget : (info.getPositionToMoveTo().value() - info.getBall()->get()->position).angle()); - skillStpInfo.setDribblerSpeed(100); + skillStpInfo.setYaw(skills.current_num() == 0 ? angleToTarget : (info.getPositionToMoveTo().value() - info.getBall()->get()->position).angle()); + skillStpInfo.setDribblerOn(true); return skillStpInfo; } @@ -21,7 +21,7 @@ std::optional DriveWithBall::calculateInfoForSkill(const StpInfo &info) bool DriveWithBall::isTacticFailing(const StpInfo &info) noexcept { return !info.getRobot().value()->hasBall() || !info.getPositionToMoveTo(); } bool DriveWithBall::shouldTacticReset(const StpInfo &info) noexcept { - return skills.current_num() == 1 && info.getRobot()->get()->getAngle().shortestAngleDiff(info.getAngle()) > Constants::HAS_BALL_ANGLE(); + return skills.current_num() == 1 && info.getRobot()->get()->getYaw().shortestAngleDiff(info.getYaw()) > Constants::HAS_BALL_ANGLE(); } bool DriveWithBall::isEndTactic() noexcept { return false; } diff --git a/roboteam_ai/src/stp/tactics/active/GetBall.cpp b/roboteam_ai/src/stp/tactics/active/GetBall.cpp index 960650724..285732aef 100644 --- a/roboteam_ai/src/stp/tactics/active/GetBall.cpp +++ b/roboteam_ai/src/stp/tactics/active/GetBall.cpp @@ -48,10 +48,10 @@ std::optional GetBall::calculateInfoForSkill(const StpInfo &info) noexc skillStpInfo.setPositionToMoveTo(newRobotPosition); } - skillStpInfo.setAngle((ballPosition - robotPosition).angle()); + skillStpInfo.setYaw((ballPosition - robotPosition).angle()); if (distanceToBall < control_constants::TURN_ON_DRIBBLER_DISTANCE) { - skillStpInfo.setDribblerSpeed(100); + skillStpInfo.setDribblerOn(true); } return skillStpInfo; diff --git a/roboteam_ai/src/stp/tactics/active/GetBehindBallInDirection.cpp b/roboteam_ai/src/stp/tactics/active/GetBehindBallInDirection.cpp index 87e6d9950..0cd675de9 100644 --- a/roboteam_ai/src/stp/tactics/active/GetBehindBallInDirection.cpp +++ b/roboteam_ai/src/stp/tactics/active/GetBehindBallInDirection.cpp @@ -22,7 +22,7 @@ std::optional GetBehindBallInDirection::calculateInfoForSkill(const Stp Vector2 ballPosition = info.getBall()->get()->position; Vector2 positionToShootAt = info.getPositionToShootAt().value(); - skillStpInfo.setAngle((positionToShootAt - robotPosition).angle()); + skillStpInfo.setYaw((positionToShootAt - robotPosition).angle()); if ((ballPosition - robotPosition).length() > DISTANCE_THRESHOLD || info.getObjectsToAvoid().shouldAvoidBall) { Vector2 targetPos = calculateTargetPosition(ballPosition, robotPosition, positionToShootAt); diff --git a/roboteam_ai/src/stp/tactics/active/InstantKick.cpp b/roboteam_ai/src/stp/tactics/active/InstantKick.cpp index bbdd1fa50..870a9285b 100644 --- a/roboteam_ai/src/stp/tactics/active/InstantKick.cpp +++ b/roboteam_ai/src/stp/tactics/active/InstantKick.cpp @@ -15,7 +15,7 @@ std::optional InstantKick::calculateInfoForSkill(const StpInfo &info) n StpInfo skillStpInfo = info; double distanceBallToTarget = (info.getBall()->get()->position - info.getPositionToShootAt().value()).length(); skillStpInfo.setKickChipVelocity(control::ControlUtils::determineKickForce(distanceBallToTarget, skillStpInfo.getShotType())); - skillStpInfo.setDribblerSpeed(0); + skillStpInfo.setDribblerOn(false); return skillStpInfo; } diff --git a/roboteam_ai/src/stp/tactics/active/OrbitKick.cpp b/roboteam_ai/src/stp/tactics/active/OrbitKick.cpp index 71d6f40a7..93841fbf1 100644 --- a/roboteam_ai/src/stp/tactics/active/OrbitKick.cpp +++ b/roboteam_ai/src/stp/tactics/active/OrbitKick.cpp @@ -13,12 +13,12 @@ std::optional OrbitKick::calculateInfoForSkill(const StpInfo &info) noe StpInfo skillStpInfo = info; double angleToTarget = (info.getPositionToShootAt().value() - info.getRobot().value()->getPos()).angle(); - skillStpInfo.setAngle(angleToTarget); + skillStpInfo.setYaw(angleToTarget); double distanceBallToTarget = (info.getBall()->get()->position - info.getPositionToShootAt().value()).length(); skillStpInfo.setKickChipVelocity(control::ControlUtils::determineKickForce(distanceBallToTarget, skillStpInfo.getShotType())); - skillStpInfo.setDribblerSpeed(100); + skillStpInfo.setDribblerOn(true); return skillStpInfo; } @@ -29,7 +29,7 @@ bool OrbitKick::isTacticFailing(const StpInfo &info) noexcept { return !info.get bool OrbitKick::shouldTacticReset(const StpInfo &info) noexcept { const auto errorMargin = stp::control_constants::GO_TO_POS_ANGLE_ERROR_MARGIN * M_PI; - return info.getRobot().value()->getAngle().shortestAngleDiff(info.getAngle()) > errorMargin; + return info.getRobot().value()->getYaw().shortestAngleDiff(info.getYaw()) > errorMargin; } const char *OrbitKick::getName() { return "Orbit Kick"; } diff --git a/roboteam_ai/src/stp/tactics/active/Receive.cpp b/roboteam_ai/src/stp/tactics/active/Receive.cpp index c7c3a990c..6f50b721f 100644 --- a/roboteam_ai/src/stp/tactics/active/Receive.cpp +++ b/roboteam_ai/src/stp/tactics/active/Receive.cpp @@ -13,8 +13,8 @@ std::optional Receive::calculateInfoForSkill(StpInfo const &info) noexc if (!skillStpInfo.getRobot() || !skillStpInfo.getBall()) return std::nullopt; - skillStpInfo.setAngle(calculateAngle(info.getRobot().value(), info.getBall().value())); - skillStpInfo.setDribblerSpeed(100); + skillStpInfo.setYaw(calculateAngle(info.getRobot().value(), info.getBall().value())); + skillStpInfo.setDribblerOn(true); return skillStpInfo; } diff --git a/roboteam_ai/src/stp/tactics/passive/BallStandBack.cpp b/roboteam_ai/src/stp/tactics/passive/BallStandBack.cpp index 239a0df49..a16f6661c 100644 --- a/roboteam_ai/src/stp/tactics/passive/BallStandBack.cpp +++ b/roboteam_ai/src/stp/tactics/passive/BallStandBack.cpp @@ -35,10 +35,10 @@ std::optional BallStandBack::calculateInfoForSkill(StpInfo const &info) skillStpInfo.setShouldAvoidBall(false); } - double angle = (info.getBall()->get()->position - targetPosition).angle(); + double yaw = (info.getBall()->get()->position - targetPosition).angle(); skillStpInfo.setPositionToMoveTo(targetPosition); - skillStpInfo.setAngle(angle); - skillStpInfo.setDribblerSpeed(0); + skillStpInfo.setYaw(yaw); + skillStpInfo.setDribblerOn(false); return skillStpInfo; } diff --git a/roboteam_ai/src/stp/tactics/passive/BlockBall.cpp b/roboteam_ai/src/stp/tactics/passive/BlockBall.cpp index 8a1635e7b..f51ce00b7 100644 --- a/roboteam_ai/src/stp/tactics/passive/BlockBall.cpp +++ b/roboteam_ai/src/stp/tactics/passive/BlockBall.cpp @@ -23,10 +23,10 @@ std::optional BlockBall::calculateInfoForSkill(StpInfo const &info) noe skillStpInfo.setPositionToMoveTo(targetPosition); - auto targetAngle = (info.getBall()->get()->position - info.getRobot()->get()->getPos()).angle(); - skillStpInfo.setAngle(targetAngle); + auto yaw = (info.getBall()->get()->position - info.getRobot()->get()->getPos()).angle(); + skillStpInfo.setYaw(yaw); } else { - skillStpInfo.setDribblerSpeed(0); + skillStpInfo.setDribblerOn(false); } return skillStpInfo; diff --git a/roboteam_ai/src/stp/tactics/passive/Formation.cpp b/roboteam_ai/src/stp/tactics/passive/Formation.cpp index ab22f9b0c..f64b3a78f 100644 --- a/roboteam_ai/src/stp/tactics/passive/Formation.cpp +++ b/roboteam_ai/src/stp/tactics/passive/Formation.cpp @@ -12,8 +12,8 @@ std::optional Formation::calculateInfoForSkill(StpInfo const &info) noe StpInfo skillStpInfo = info; if (!info.getPositionToMoveTo()) return std::nullopt; - if (!info.getAngle()) skillStpInfo.setAngle(0); - skillStpInfo.setDribblerSpeed(0); + if (!info.getYaw()) skillStpInfo.setYaw(0); + skillStpInfo.setDribblerOn(false); return skillStpInfo; } diff --git a/roboteam_ai/src/stp/tactics/passive/Halt.cpp b/roboteam_ai/src/stp/tactics/passive/Halt.cpp index 8837f9665..5c00ae233 100644 --- a/roboteam_ai/src/stp/tactics/passive/Halt.cpp +++ b/roboteam_ai/src/stp/tactics/passive/Halt.cpp @@ -8,7 +8,7 @@ Halt::Halt() { skills = collections::state_machine{skill std::optional Halt::calculateInfoForSkill(StpInfo const &info) noexcept { StpInfo skillInfo = info; - skillInfo.setAngle(0.0); + skillInfo.setYaw(0.0); return skillInfo; } diff --git a/roboteam_ai/src/utilities/Constants.cpp b/roboteam_ai/src/utilities/Constants.cpp index cddf630df..8f7ec2176 100644 --- a/roboteam_ai/src/utilities/Constants.cpp +++ b/roboteam_ai/src/utilities/Constants.cpp @@ -22,9 +22,9 @@ double Constants::MAX_ANGULAR_VELOCITY() { return 6.0; } double Constants::MAX_VEL_CMD() { return 4.0; } -double Constants::MIN_ANGLE() { return -M_PI; } +double Constants::MIN_YAW() { return -M_PI; } -double Constants::MAX_ANGLE() { return M_PI; } +double Constants::MAX_YAW() { return M_PI; } double Constants::MAX_ACC() { return 3.5; } diff --git a/roboteam_ai/src/utilities/IOManager.cpp b/roboteam_ai/src/utilities/IOManager.cpp index 82354202b..30dd7228e 100644 --- a/roboteam_ai/src/utilities/IOManager.cpp +++ b/roboteam_ai/src/utilities/IOManager.cpp @@ -90,7 +90,7 @@ void IOManager::publishSettings() { } } -void IOManager::addCameraAngleToRobotCommands(rtt::RobotCommands& robotCommands) { +void IOManager::addCameraYawToRobotCommands(rtt::RobotCommands& robotCommands) { const auto state = this->getState(); if (state.has_last_seen_world()) { const auto world = getState().last_seen_world(); @@ -98,8 +98,8 @@ void IOManager::addCameraAngleToRobotCommands(rtt::RobotCommands& robotCommands) for (auto& robotCommand : robotCommands) { for (const auto& robot : robots) { if (robot.id() == static_cast(robotCommand.id)) { - robotCommand.cameraAngleOfRobot = robot.angle(); - robotCommand.cameraAngleOfRobotIsSet = true; + robotCommand.cameraYawOfRobot = robot.yaw(); + robotCommand.cameraYawOfRobotIsSet = true; } } } @@ -108,7 +108,7 @@ void IOManager::addCameraAngleToRobotCommands(rtt::RobotCommands& robotCommands) void IOManager::publishAllRobotCommands(rtt::RobotCommands& robotCommands) { if (!RuntimeConfig::isPaused && !robotCommands.empty()) { - this->addCameraAngleToRobotCommands(robotCommands); + this->addCameraYawToRobotCommands(robotCommands); this->publishRobotCommands(robotCommands, GameSettings::isYellow()); } diff --git a/roboteam_ai/src/utilities/normalize.cpp b/roboteam_ai/src/utilities/normalize.cpp index 28759de9d..7309a1a41 100644 --- a/roboteam_ai/src/utilities/normalize.cpp +++ b/roboteam_ai/src/utilities/normalize.cpp @@ -19,7 +19,7 @@ void rotate(proto::WorldRobot *robot) { robot->mutable_vel()->set_x(robot->vel().x() * -1); robot->mutable_vel()->set_y(robot->vel().y() * -1); robot->set_w(robot->w() * -1); - robot->set_angle(static_cast(rtt::cleanAngle(robot->angle() + M_PI))); + robot->set_yaw(static_cast(rtt::cleanAngle(robot->yaw() + M_PI))); } // rotate the ball and robots @@ -81,7 +81,7 @@ void rotate(proto::SSL_GeometryFieldSize *field) { void rotate(rtt::RobotCommand *command) { assert(command && "Invalid pointer for command"); command->velocity = command->velocity * -1; - command->targetAngle += M_PI; + command->yaw += M_PI; } void rotate(proto::SSL_WrapperPacket *packet) { if (packet->has_detection()) { diff --git a/roboteam_ai/src/world/Ball.cpp b/roboteam_ai/src/world/Ball.cpp index a62e77bdc..e4e67609e 100644 --- a/roboteam_ai/src/world/Ball.cpp +++ b/roboteam_ai/src/world/Ball.cpp @@ -91,7 +91,7 @@ void Ball::updateBallAtRobotPosition(const world::World* data) noexcept { } double distanceInFrontOfRobot = ai::stp::control_constants::CENTER_TO_FRONT + ai::Constants::BALL_RADIUS(); - position = robotWithBall->get()->getPos() + robotWithBall->get()->getAngle().toVector2(distanceInFrontOfRobot); + position = robotWithBall->get()->getPos() + robotWithBall->get()->getYaw().toVector2(distanceInFrontOfRobot); velocity = robotWithBall->get()->getVel(); } diff --git a/roboteam_ai/src/world/Robot.cpp b/roboteam_ai/src/world/Robot.cpp index 775b23579..52a3d8153 100644 --- a/roboteam_ai/src/world/Robot.cpp +++ b/roboteam_ai/src/world/Robot.cpp @@ -11,7 +11,7 @@ Robot::Robot(const proto::WorldRobot ©, rtt::world::Team team, std::optional team{team}, pos{copy.pos().x(), copy.pos().y()}, vel{copy.vel().x(), copy.vel().y()}, - angle{copy.angle()}, + yaw{copy.yaw()}, distanceToBall{-1.0}, angularVelocity{copy.w()} { if (id < 16) { @@ -22,7 +22,7 @@ Robot::Robot(const proto::WorldRobot ©, rtt::world::Team team, std::optional if (ball.has_value()) { setDistanceToBall(pos.dist((*ball)->position)); auto angleRobotToBall = ((*ball)->position - pos).angle(); - setAngleDiffToBall(angle.shortestAngleDiff(Angle(angleRobotToBall))); + setAngleDiffToBall(yaw.shortestAngleDiff(Angle(angleRobotToBall))); } if (team == Team::us) { @@ -44,9 +44,9 @@ const Vector2 &Robot::getPos() const noexcept { return pos; } const Vector2 &Robot::getVel() const noexcept { return vel; } -const Angle &Robot::getAngle() const noexcept { return angle; } +const Angle &Robot::getYaw() const noexcept { return yaw; } -void Robot::setAngle(const Angle &_angle) noexcept { Robot::angle = _angle; } +void Robot::setYaw(const Angle &_yaw) noexcept { Robot::yaw = _yaw; } double Robot::getAngularVelocity() const noexcept { return angularVelocity; } @@ -71,8 +71,6 @@ void Robot::setHasBall(bool _hasBall) noexcept { Robot::robotHasBall = _hasBall; bool Robot::hasBall() const noexcept { return robotHasBall; } -void Robot::setBallPosBallSensor(float _ballPos) noexcept { Robot::ballPos = _ballPos; } - double Robot::getDistanceToBall() const noexcept { return distanceToBall; } void Robot::setDistanceToBall(double _distanceToBall) noexcept { Robot::distanceToBall = _distanceToBall; } @@ -88,7 +86,6 @@ void Robot::updateFromFeedback(const proto::RobotProcessedFeedback &feedback) no setBatteryLow(feedback.battery_level() < 22); // TODO: Figure out with electronics which value should be considered low setBallSensorSeesBall(feedback.ball_sensor_sees_ball()); setDribblerSeesBall(feedback.dribbler_sees_ball()); - setBallPosBallSensor(feedback.ball_position()); } } diff --git a/roboteam_ai/test/WorldTests/RobotTests.cpp b/roboteam_ai/test/WorldTests/RobotTests.cpp index 5cee10946..86621fa94 100644 --- a/roboteam_ai/test/WorldTests/RobotTests.cpp +++ b/roboteam_ai/test/WorldTests/RobotTests.cpp @@ -20,7 +20,7 @@ TEST(RobotAndView, test_getters) { proto::WorldRobot robotData{}; robotData.set_id(1); - robotData.set_angle(5.0); + robotData.set_yaw(5.0); robotData.set_allocated_pos(getVec(5, 7)); robotData.set_allocated_vel(getVec(3, 0)); robotData.set_w(5.0); @@ -28,7 +28,7 @@ TEST(RobotAndView, test_getters) { Robot data{robotData, us}; ASSERT_EQ(data.getId(), 1); - ASSERT_EQ(data.getAngle(), Angle(5.0)); + ASSERT_EQ(data.getYaw(), Angle(5.0)); ASSERT_EQ(data.getPos(), Vector2(5.0, 7.0)); ASSERT_EQ(data.getVel(), Vector2(3, 0)); ASSERT_EQ(data.getAngularVelocity(), 5.0); diff --git a/roboteam_ai/test/WorldTests/WhichRobotHasBallTest.cpp b/roboteam_ai/test/WorldTests/WhichRobotHasBallTest.cpp index 7153946f6..c82545627 100644 --- a/roboteam_ai/test/WorldTests/WhichRobotHasBallTest.cpp +++ b/roboteam_ai/test/WorldTests/WhichRobotHasBallTest.cpp @@ -28,18 +28,18 @@ TEST(worldTest, WhichRobotHasBallTest) { roboty1.mutable_feedbackinfo()->set_dribbler_sees_ball(true); roboty1.mutable_feedbackinfo()->set_ball_sensor_sees_ball(true); - roboty1.set_angle(M_PI); + roboty1.set_yaw(M_PI); proto::WorldRobot roboty2; roboty2.set_id(2); roboty2.mutable_pos()->set_x(0.5); - roboty2.set_angle(M_PI); + roboty2.set_yaw(M_PI); // Create robots blue proto::WorldRobot robotb1; robotb1.set_id(3); robotb1.mutable_pos()->set_x(0.05); - robotb1.set_angle(M_PI); + robotb1.set_yaw(M_PI); /* Setup : Ball ..0.05.. robotb1(3) ..0.1.. roboty1(1) ..0.5.. roboty2(2) */ @@ -96,20 +96,20 @@ TEST(worldTest, NoRobotHasBall) { roboty1.set_id(4); roboty1.mutable_pos()->set_x(1); roboty1.mutable_pos()->set_y(0); - roboty1.set_angle(M_PI); + roboty1.set_yaw(M_PI); proto::WorldRobot roboty2; roboty2.set_id(5); roboty2.mutable_pos()->set_x(2); roboty2.mutable_pos()->set_y(0); - roboty2.set_angle(M_PI); + roboty2.set_yaw(M_PI); // Create robots blue proto::WorldRobot robotb1; robotb1.set_id(6); robotb1.mutable_pos()->set_x(3); robotb1.mutable_pos()->set_y(0); - robotb1.set_angle(M_PI); + robotb1.set_yaw(M_PI); /* Setup : Ball ..1.. robotb1(3) ..2.. roboty1(1) ..3.. roboty2(2) */ diff --git a/roboteam_ai/test/helpers/WorldHelper.cpp b/roboteam_ai/test/helpers/WorldHelper.cpp index 324618df1..e815393d0 100644 --- a/roboteam_ai/test/helpers/WorldHelper.cpp +++ b/roboteam_ai/test/helpers/WorldHelper.cpp @@ -84,7 +84,7 @@ proto::WorldRobot WorldHelper::generateRandomRobot(int id, proto::SSL_GeometryFi robot.set_id((unsigned)id); robot.mutable_pos()->set_x(randomFieldPos.x); robot.mutable_pos()->set_y(randomFieldPos.y); - robot.set_angle(static_cast(getRandomValue(rtt::ai::Constants::MIN_ANGLE(), rtt::ai::Constants::MAX_ANGLE()))); + robot.set_yaw(static_cast(getRandomValue(rtt::ai::Constants::MIN_YAW(), rtt::ai::Constants::MAX_YAW()))); robot.mutable_vel()->set_x(randomVel.x); robot.mutable_vel()->set_y(randomVel.x); robot.set_w(static_cast(getRandomValue(0, rtt::ai::Constants::MAX_ANGULAR_VELOCITY()))); @@ -115,10 +115,10 @@ proto::WorldBall *WorldHelper::generateRandomBall(proto::SSL_GeometryFieldSize f * so close that we can say that the robot has the ball. */ rtt::Vector2 WorldHelper::getLocationRightBeforeRobot(proto::WorldRobot robot) { - rtt::Vector2 angleVector = rtt::Vector2(cos(robot.angle()), sin(robot.angle())); - angleVector = angleVector.stretchToLength(rtt::ai::Constants::ROBOT_RADIUS()); + rtt::Vector2 yawVector = rtt::Vector2(cos(robot.yaw()), sin(robot.yaw())); + yawVector = yawVector.stretchToLength(rtt::ai::Constants::ROBOT_RADIUS()); rtt::Vector2 robotPos = rtt::Vector2(robot.pos().x(), robot.pos().y()); - return robotPos + angleVector; + return robotPos + yawVector; } /* diff --git a/roboteam_interface/package.json b/roboteam_interface/package.json index 713ebc69c..2745a3d8f 100644 --- a/roboteam_interface/package.json +++ b/roboteam_interface/package.json @@ -11,7 +11,7 @@ "build": "VITE_NETWORK_PROCESSOR=tauri vite build && tauri build", "preview": "vite preview", "ts:check": "vue-tsc --noEmit", - "gen:proto": "pbjs --es6 -t static-module -w es6 -o src/generated/proto.js $(ls ../roboteam_networking/proto/* | grep -xv \"../roboteam_networking/proto/CMakeLists.txt\") && pbts --pb3-optional -o src/generated/proto.d.ts src/generated/proto.js", + "gen:proto": "pbjs --es6 -t static-module -w es6 -o src/generated/proto.js $(ls ../roboteam_networking/proto/*.proto) && pbts --pb3-optional -o src/generated/proto.d.ts src/generated/proto.js", "lint": "eslint src/ --ext .vue,.js,.jsx,.cjs,.mjs,.ts,.tsx,.cts,.mts --fix", "format": "prettier --write src/" }, diff --git a/roboteam_interface/src/app.vue b/roboteam_interface/src/app.vue index 72505725c..60f1d4247 100644 --- a/roboteam_interface/src/app.vue +++ b/roboteam_interface/src/app.vue @@ -46,17 +46,25 @@ const bottomPanelSize = computed(() => `${uiStore.panelSize('bottomPanel')}px`)
-
- x: {{ formatFloat(uiStore.pointerLocation?.x) }} y: {{ formatFloat(uiStore.pointerLocation?.y)}} +
+ x: {{ formatFloat(uiStore.pointerLocation?.x) }} y: + {{ formatFloat(uiStore.pointerLocation?.y) }}
- - + + diff --git a/roboteam_interface/src/generated/proto.d.ts b/roboteam_interface/src/generated/proto.d.ts index 3f90ea001..69449f1ba 100644 --- a/roboteam_interface/src/generated/proto.d.ts +++ b/roboteam_interface/src/generated/proto.d.ts @@ -3,6 +3,131 @@ import Long = require("long"); /** Namespace proto. */ export namespace proto { + /** Properties of a GameSettings. */ + interface IGameSettings { + + /** GameSettings isPrimaryAi */ + isPrimaryAi?: (boolean|null); + + /** GameSettings isYellow */ + isYellow?: (boolean|null); + + /** GameSettings isLeft */ + isLeft?: (boolean|null); + + /** GameSettings robotHubMode */ + robotHubMode?: (proto.GameSettings.RobotHubMode|null); + } + + /** Represents a GameSettings. */ + class GameSettings implements IGameSettings { + + /** + * Constructs a new GameSettings. + * @param [properties] Properties to set + */ + constructor(properties?: proto.IGameSettings); + + /** GameSettings isPrimaryAi. */ + public isPrimaryAi: boolean; + + /** GameSettings isYellow. */ + public isYellow: boolean; + + /** GameSettings isLeft. */ + public isLeft: boolean; + + /** GameSettings robotHubMode. */ + public robotHubMode: proto.GameSettings.RobotHubMode; + + /** + * Creates a new GameSettings instance using the specified properties. + * @param [properties] Properties to set + * @returns GameSettings instance + */ + public static create(properties?: proto.IGameSettings): proto.GameSettings; + + /** + * Encodes the specified GameSettings message. Does not implicitly {@link proto.GameSettings.verify|verify} messages. + * @param message GameSettings message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encode(message: proto.IGameSettings, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Encodes the specified GameSettings message, length delimited. Does not implicitly {@link proto.GameSettings.verify|verify} messages. + * @param message GameSettings message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encodeDelimited(message: proto.IGameSettings, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Decodes a GameSettings message from the specified reader or buffer. + * @param reader Reader or buffer to decode from + * @param [length] Message length if known beforehand + * @returns GameSettings + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.GameSettings; + + /** + * Decodes a GameSettings message from the specified reader or buffer, length delimited. + * @param reader Reader or buffer to decode from + * @returns GameSettings + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.GameSettings; + + /** + * Verifies a GameSettings message. + * @param message Plain object to verify + * @returns `null` if valid, otherwise the reason why it is not + */ + public static verify(message: { [k: string]: any }): (string|null); + + /** + * Creates a GameSettings message from a plain object. Also converts values to their respective internal types. + * @param object Plain object + * @returns GameSettings + */ + public static fromObject(object: { [k: string]: any }): proto.GameSettings; + + /** + * Creates a plain object from a GameSettings message. Also converts values to other types if specified. + * @param message GameSettings + * @param [options] Conversion options + * @returns Plain object + */ + public static toObject(message: proto.GameSettings, options?: $protobuf.IConversionOptions): { [k: string]: any }; + + /** + * Converts this GameSettings to JSON. + * @returns JSON object + */ + public toJSON(): { [k: string]: any }; + + /** + * Gets the default type url for GameSettings + * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns The default type url + */ + public static getTypeUrl(typeUrlPrefix?: string): string; + } + + namespace GameSettings { + + /** RobotHubMode enum. */ + enum RobotHubMode { + UNKNOWN = 0, + BASESTATION = 1, + SIMULATOR = 2 + } + } + /** Properties of a Drawing. */ interface IDrawing { @@ -168,7 +293,8 @@ export namespace proto { CYAN = 4, MAGENTA = 5, WHITE = 6, - BLACK = 7 + GREY = 7, + BLACK = 8 } /** Category enum. */ @@ -1434,14 +1560,14 @@ export namespace proto { /** PlayInfo keeperId */ keeperId?: (number|null); - /** PlayInfo timeLeft */ - timeLeft?: (number|null); + /** PlayInfo timeleft */ + timeleft?: (number|null); - /** PlayInfo commandFromRef */ - commandFromRef?: (string|null); + /** PlayInfo followupcommandfromrefName */ + followupcommandfromrefName?: (string|null); - /** PlayInfo followUpCommandFromRef */ - followUpCommandFromRef?: (string|null); + /** PlayInfo commandfromrefName */ + commandfromrefName?: (string|null); } /** Represents a PlayInfo. */ @@ -1462,6 +1588,15 @@ export namespace proto { /** PlayInfo keeperId. */ public keeperId: number; + /** PlayInfo timeleft. */ + public timeleft: number; + + /** PlayInfo followupcommandfromrefName. */ + public followupcommandfromrefName: string; + + /** PlayInfo commandfromrefName. */ + public commandfromrefName: string; + /** * Creates a new PlayInfo instance using the specified properties. * @param [properties] Properties to set @@ -1894,131 +2029,6 @@ export namespace proto { public static getTypeUrl(typeUrlPrefix?: string): string; } - /** Properties of a GameSettings. */ - interface IGameSettings { - - /** GameSettings isPrimaryAi */ - isPrimaryAi?: (boolean|null); - - /** GameSettings isYellow */ - isYellow?: (boolean|null); - - /** GameSettings isLeft */ - isLeft?: (boolean|null); - - /** GameSettings robotHubMode */ - robotHubMode?: (proto.GameSettings.RobotHubMode|null); - } - - /** Represents a GameSettings. */ - class GameSettings implements IGameSettings { - - /** - * Constructs a new GameSettings. - * @param [properties] Properties to set - */ - constructor(properties?: proto.IGameSettings); - - /** GameSettings isPrimaryAi. */ - public isPrimaryAi: boolean; - - /** GameSettings isYellow. */ - public isYellow: boolean; - - /** GameSettings isLeft. */ - public isLeft: boolean; - - /** GameSettings robotHubMode. */ - public robotHubMode: proto.GameSettings.RobotHubMode; - - /** - * Creates a new GameSettings instance using the specified properties. - * @param [properties] Properties to set - * @returns GameSettings instance - */ - public static create(properties?: proto.IGameSettings): proto.GameSettings; - - /** - * Encodes the specified GameSettings message. Does not implicitly {@link proto.GameSettings.verify|verify} messages. - * @param message GameSettings message or plain object to encode - * @param [writer] Writer to encode to - * @returns Writer - */ - public static encode(message: proto.IGameSettings, writer?: $protobuf.Writer): $protobuf.Writer; - - /** - * Encodes the specified GameSettings message, length delimited. Does not implicitly {@link proto.GameSettings.verify|verify} messages. - * @param message GameSettings message or plain object to encode - * @param [writer] Writer to encode to - * @returns Writer - */ - public static encodeDelimited(message: proto.IGameSettings, writer?: $protobuf.Writer): $protobuf.Writer; - - /** - * Decodes a GameSettings message from the specified reader or buffer. - * @param reader Reader or buffer to decode from - * @param [length] Message length if known beforehand - * @returns GameSettings - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.GameSettings; - - /** - * Decodes a GameSettings message from the specified reader or buffer, length delimited. - * @param reader Reader or buffer to decode from - * @returns GameSettings - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.GameSettings; - - /** - * Verifies a GameSettings message. - * @param message Plain object to verify - * @returns `null` if valid, otherwise the reason why it is not - */ - public static verify(message: { [k: string]: any }): (string|null); - - /** - * Creates a GameSettings message from a plain object. Also converts values to their respective internal types. - * @param object Plain object - * @returns GameSettings - */ - public static fromObject(object: { [k: string]: any }): proto.GameSettings; - - /** - * Creates a plain object from a GameSettings message. Also converts values to other types if specified. - * @param message GameSettings - * @param [options] Conversion options - * @returns Plain object - */ - public static toObject(message: proto.GameSettings, options?: $protobuf.IConversionOptions): { [k: string]: any }; - - /** - * Converts this GameSettings to JSON. - * @returns JSON object - */ - public toJSON(): { [k: string]: any }; - - /** - * Gets the default type url for GameSettings - * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") - * @returns The default type url - */ - public static getTypeUrl(typeUrlPrefix?: string): string; - } - - namespace GameSettings { - - /** RobotHubMode enum. */ - enum RobotHubMode { - UNKNOWN = 0, - BASESTATION = 1, - SIMULATOR = 2 - } - } - /** Properties of a State. */ interface IState { @@ -2041,13 +2051,13 @@ export namespace proto { field?: (proto.ISSL_GeometryData|null); /** State referee */ - referee?: (proto.ISSL_Referee|null); + referee?: (proto.IReferee|null); /** State processedVisionPackets */ processedVisionPackets?: (proto.ISSL_WrapperPacket[]|null); /** State processedRefereePackets */ - processedRefereePackets?: (proto.ISSL_Referee[]|null); + processedRefereePackets?: (proto.IReferee[]|null); /** State processedFeedbackPackets */ processedFeedbackPackets?: (proto.IRobotsFeedback[]|null); @@ -2081,13 +2091,13 @@ export namespace proto { public field?: (proto.ISSL_GeometryData|null); /** State referee. */ - public referee?: (proto.ISSL_Referee|null); + public referee?: (proto.IReferee|null); /** State processedVisionPackets. */ public processedVisionPackets: proto.ISSL_WrapperPacket[]; /** State processedRefereePackets. */ - public processedRefereePackets: proto.ISSL_Referee[]; + public processedRefereePackets: proto.IReferee[]; /** State processedFeedbackPackets. */ public processedFeedbackPackets: proto.IRobotsFeedback[]; @@ -2542,8 +2552,8 @@ export namespace proto { /** WorldRobot pos */ pos?: (proto.IVector2f|null); - /** WorldRobot angle */ - angle?: (number|null); + /** WorldRobot yaw */ + yaw?: (number|null); /** WorldRobot vel */ vel?: (proto.IVector2f|null); @@ -2570,8 +2580,8 @@ export namespace proto { /** WorldRobot pos. */ public pos?: (proto.IVector2f|null); - /** WorldRobot angle. */ - public angle: number; + /** WorldRobot yaw. */ + public yaw: number; /** WorldRobot vel. */ public vel?: (proto.IVector2f|null); @@ -2660,233 +2670,12 @@ export namespace proto { public static getTypeUrl(typeUrlPrefix?: string): string; } - /** Properties of a RobotWheel. */ - interface IRobotWheel { - - /** RobotWheel locked */ - locked?: (boolean|null); - - /** RobotWheel braking */ - braking?: (boolean|null); - } - - /** Represents a RobotWheel. */ - class RobotWheel implements IRobotWheel { - - /** - * Constructs a new RobotWheel. - * @param [properties] Properties to set - */ - constructor(properties?: proto.IRobotWheel); - - /** RobotWheel locked. */ - public locked: boolean; - - /** RobotWheel braking. */ - public braking: boolean; - - /** - * Creates a new RobotWheel instance using the specified properties. - * @param [properties] Properties to set - * @returns RobotWheel instance - */ - public static create(properties?: proto.IRobotWheel): proto.RobotWheel; - - /** - * Encodes the specified RobotWheel message. Does not implicitly {@link proto.RobotWheel.verify|verify} messages. - * @param message RobotWheel message or plain object to encode - * @param [writer] Writer to encode to - * @returns Writer - */ - public static encode(message: proto.IRobotWheel, writer?: $protobuf.Writer): $protobuf.Writer; - - /** - * Encodes the specified RobotWheel message, length delimited. Does not implicitly {@link proto.RobotWheel.verify|verify} messages. - * @param message RobotWheel message or plain object to encode - * @param [writer] Writer to encode to - * @returns Writer - */ - public static encodeDelimited(message: proto.IRobotWheel, writer?: $protobuf.Writer): $protobuf.Writer; - - /** - * Decodes a RobotWheel message from the specified reader or buffer. - * @param reader Reader or buffer to decode from - * @param [length] Message length if known beforehand - * @returns RobotWheel - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.RobotWheel; - - /** - * Decodes a RobotWheel message from the specified reader or buffer, length delimited. - * @param reader Reader or buffer to decode from - * @returns RobotWheel - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.RobotWheel; - - /** - * Verifies a RobotWheel message. - * @param message Plain object to verify - * @returns `null` if valid, otherwise the reason why it is not - */ - public static verify(message: { [k: string]: any }): (string|null); - - /** - * Creates a RobotWheel message from a plain object. Also converts values to their respective internal types. - * @param object Plain object - * @returns RobotWheel - */ - public static fromObject(object: { [k: string]: any }): proto.RobotWheel; - - /** - * Creates a plain object from a RobotWheel message. Also converts values to other types if specified. - * @param message RobotWheel - * @param [options] Conversion options - * @returns Plain object - */ - public static toObject(message: proto.RobotWheel, options?: $protobuf.IConversionOptions): { [k: string]: any }; - - /** - * Converts this RobotWheel to JSON. - * @returns JSON object - */ - public toJSON(): { [k: string]: any }; - - /** - * Gets the default type url for RobotWheel - * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") - * @returns The default type url - */ - public static getTypeUrl(typeUrlPrefix?: string): string; - } - - /** Properties of a RobotWheels. */ - interface IRobotWheels { - - /** RobotWheels rightFront */ - rightFront?: (proto.IRobotWheel|null); - - /** RobotWheels rightBack */ - rightBack?: (proto.IRobotWheel|null); - - /** RobotWheels leftBack */ - leftBack?: (proto.IRobotWheel|null); - - /** RobotWheels leftFront */ - leftFront?: (proto.IRobotWheel|null); - } - - /** Represents a RobotWheels. */ - class RobotWheels implements IRobotWheels { - - /** - * Constructs a new RobotWheels. - * @param [properties] Properties to set - */ - constructor(properties?: proto.IRobotWheels); - - /** RobotWheels rightFront. */ - public rightFront?: (proto.IRobotWheel|null); - - /** RobotWheels rightBack. */ - public rightBack?: (proto.IRobotWheel|null); - - /** RobotWheels leftBack. */ - public leftBack?: (proto.IRobotWheel|null); - - /** RobotWheels leftFront. */ - public leftFront?: (proto.IRobotWheel|null); - - /** - * Creates a new RobotWheels instance using the specified properties. - * @param [properties] Properties to set - * @returns RobotWheels instance - */ - public static create(properties?: proto.IRobotWheels): proto.RobotWheels; - - /** - * Encodes the specified RobotWheels message. Does not implicitly {@link proto.RobotWheels.verify|verify} messages. - * @param message RobotWheels message or plain object to encode - * @param [writer] Writer to encode to - * @returns Writer - */ - public static encode(message: proto.IRobotWheels, writer?: $protobuf.Writer): $protobuf.Writer; - - /** - * Encodes the specified RobotWheels message, length delimited. Does not implicitly {@link proto.RobotWheels.verify|verify} messages. - * @param message RobotWheels message or plain object to encode - * @param [writer] Writer to encode to - * @returns Writer - */ - public static encodeDelimited(message: proto.IRobotWheels, writer?: $protobuf.Writer): $protobuf.Writer; - - /** - * Decodes a RobotWheels message from the specified reader or buffer. - * @param reader Reader or buffer to decode from - * @param [length] Message length if known beforehand - * @returns RobotWheels - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.RobotWheels; - - /** - * Decodes a RobotWheels message from the specified reader or buffer, length delimited. - * @param reader Reader or buffer to decode from - * @returns RobotWheels - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.RobotWheels; - - /** - * Verifies a RobotWheels message. - * @param message Plain object to verify - * @returns `null` if valid, otherwise the reason why it is not - */ - public static verify(message: { [k: string]: any }): (string|null); - - /** - * Creates a RobotWheels message from a plain object. Also converts values to their respective internal types. - * @param object Plain object - * @returns RobotWheels - */ - public static fromObject(object: { [k: string]: any }): proto.RobotWheels; - - /** - * Creates a plain object from a RobotWheels message. Also converts values to other types if specified. - * @param message RobotWheels - * @param [options] Conversion options - * @returns Plain object - */ - public static toObject(message: proto.RobotWheels, options?: $protobuf.IConversionOptions): { [k: string]: any }; - - /** - * Converts this RobotWheels to JSON. - * @returns JSON object - */ - public toJSON(): { [k: string]: any }; - - /** - * Gets the default type url for RobotWheels - * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") - * @returns The default type url - */ - public static getTypeUrl(typeUrlPrefix?: string): string; - } - - /** Properties of a RobotProcessedFeedback. */ - interface IRobotProcessedFeedback { + /** Properties of a RobotProcessedFeedback. */ + interface IRobotProcessedFeedback { /** RobotProcessedFeedback ballSensorSeesBall */ ballSensorSeesBall?: (boolean|null); - /** RobotProcessedFeedback ballPosition */ - ballPosition?: (number|null); - /** RobotProcessedFeedback ballSensorIsWorking */ ballSensorIsWorking?: (boolean|null); @@ -2899,14 +2688,8 @@ export namespace proto { /** RobotProcessedFeedback capacitorIsCharged */ capacitorIsCharged?: (boolean|null); - /** RobotProcessedFeedback wheelInformation */ - wheelInformation?: (proto.IRobotWheels|null); - /** RobotProcessedFeedback batteryLevel */ batteryLevel?: (number|null); - - /** RobotProcessedFeedback signalStrength */ - signalStrength?: (number|null); } /** Represents a RobotProcessedFeedback. */ @@ -2921,9 +2704,6 @@ export namespace proto { /** RobotProcessedFeedback ballSensorSeesBall. */ public ballSensorSeesBall: boolean; - /** RobotProcessedFeedback ballPosition. */ - public ballPosition: number; - /** RobotProcessedFeedback ballSensorIsWorking. */ public ballSensorIsWorking: boolean; @@ -2936,15 +2716,9 @@ export namespace proto { /** RobotProcessedFeedback capacitorIsCharged. */ public capacitorIsCharged: boolean; - /** RobotProcessedFeedback wheelInformation. */ - public wheelInformation?: (proto.IRobotWheels|null); - /** RobotProcessedFeedback batteryLevel. */ public batteryLevel: number; - /** RobotProcessedFeedback signalStrength. */ - public signalStrength: number; - /** * Creates a new RobotProcessedFeedback instance using the specified properties. * @param [properties] Properties to set @@ -3141,8 +2915,8 @@ export namespace proto { /** RobotParameters dribblerWidth */ dribblerWidth?: (number|null); - /** RobotParameters angleOffset */ - angleOffset?: (number|null); + /** RobotParameters yawOffset */ + yawOffset?: (number|null); } /** Represents a RobotParameters. */ @@ -3166,8 +2940,8 @@ export namespace proto { /** RobotParameters dribblerWidth. */ public dribblerWidth: number; - /** RobotParameters angleOffset. */ - public angleOffset: number; + /** RobotParameters yawOffset. */ + public yawOffset: number; /** * Creates a new RobotParameters instance using the specified properties. @@ -4141,6 +3915,24 @@ export namespace proto { /** SSL_GeometryFieldSize penaltyAreaWidth */ penaltyAreaWidth?: (number|null); + + /** SSL_GeometryFieldSize centerCircleRadius */ + centerCircleRadius?: (number|null); + + /** SSL_GeometryFieldSize lineThickness */ + lineThickness?: (number|null); + + /** SSL_GeometryFieldSize goalCenterToPenaltyMark */ + goalCenterToPenaltyMark?: (number|null); + + /** SSL_GeometryFieldSize goalHeight */ + goalHeight?: (number|null); + + /** SSL_GeometryFieldSize ballRadius */ + ballRadius?: (number|null); + + /** SSL_GeometryFieldSize maxRobotRadius */ + maxRobotRadius?: (number|null); } /** Represents a SSL_GeometryFieldSize. */ @@ -4179,6 +3971,24 @@ export namespace proto { /** SSL_GeometryFieldSize penaltyAreaWidth. */ public penaltyAreaWidth: number; + /** SSL_GeometryFieldSize centerCircleRadius. */ + public centerCircleRadius: number; + + /** SSL_GeometryFieldSize lineThickness. */ + public lineThickness: number; + + /** SSL_GeometryFieldSize goalCenterToPenaltyMark. */ + public goalCenterToPenaltyMark: number; + + /** SSL_GeometryFieldSize goalHeight. */ + public goalHeight: number; + + /** SSL_GeometryFieldSize ballRadius. */ + public ballRadius: number; + + /** SSL_GeometryFieldSize maxRobotRadius. */ + public maxRobotRadius: number; + /** * Creates a new SSL_GeometryFieldSize instance using the specified properties. * @param [properties] Properties to set @@ -4450,315 +4260,660 @@ export namespace proto { public static getTypeUrl(typeUrlPrefix?: string): string; } - /** Properties of a SSL_GeometryData. */ - interface ISSL_GeometryData { + /** Properties of a SSL_BallModelStraightTwoPhase. */ + interface ISSL_BallModelStraightTwoPhase { - /** SSL_GeometryData field */ - field: proto.ISSL_GeometryFieldSize; + /** SSL_BallModelStraightTwoPhase accSlide */ + accSlide: number; - /** SSL_GeometryData calib */ - calib?: (proto.ISSL_GeometryCameraCalibration[]|null); + /** SSL_BallModelStraightTwoPhase accRoll */ + accRoll: number; + + /** SSL_BallModelStraightTwoPhase kSwitch */ + kSwitch: number; } - /** Represents a SSL_GeometryData. */ - class SSL_GeometryData implements ISSL_GeometryData { + /** Represents a SSL_BallModelStraightTwoPhase. */ + class SSL_BallModelStraightTwoPhase implements ISSL_BallModelStraightTwoPhase { /** - * Constructs a new SSL_GeometryData. + * Constructs a new SSL_BallModelStraightTwoPhase. * @param [properties] Properties to set */ - constructor(properties?: proto.ISSL_GeometryData); + constructor(properties?: proto.ISSL_BallModelStraightTwoPhase); - /** SSL_GeometryData field. */ - public field: proto.ISSL_GeometryFieldSize; + /** SSL_BallModelStraightTwoPhase accSlide. */ + public accSlide: number; - /** SSL_GeometryData calib. */ - public calib: proto.ISSL_GeometryCameraCalibration[]; + /** SSL_BallModelStraightTwoPhase accRoll. */ + public accRoll: number; + + /** SSL_BallModelStraightTwoPhase kSwitch. */ + public kSwitch: number; /** - * Creates a new SSL_GeometryData instance using the specified properties. + * Creates a new SSL_BallModelStraightTwoPhase instance using the specified properties. * @param [properties] Properties to set - * @returns SSL_GeometryData instance + * @returns SSL_BallModelStraightTwoPhase instance */ - public static create(properties?: proto.ISSL_GeometryData): proto.SSL_GeometryData; + public static create(properties?: proto.ISSL_BallModelStraightTwoPhase): proto.SSL_BallModelStraightTwoPhase; /** - * Encodes the specified SSL_GeometryData message. Does not implicitly {@link proto.SSL_GeometryData.verify|verify} messages. - * @param message SSL_GeometryData message or plain object to encode + * Encodes the specified SSL_BallModelStraightTwoPhase message. Does not implicitly {@link proto.SSL_BallModelStraightTwoPhase.verify|verify} messages. + * @param message SSL_BallModelStraightTwoPhase message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encode(message: proto.ISSL_GeometryData, writer?: $protobuf.Writer): $protobuf.Writer; + public static encode(message: proto.ISSL_BallModelStraightTwoPhase, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Encodes the specified SSL_GeometryData message, length delimited. Does not implicitly {@link proto.SSL_GeometryData.verify|verify} messages. - * @param message SSL_GeometryData message or plain object to encode + * Encodes the specified SSL_BallModelStraightTwoPhase message, length delimited. Does not implicitly {@link proto.SSL_BallModelStraightTwoPhase.verify|verify} messages. + * @param message SSL_BallModelStraightTwoPhase message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encodeDelimited(message: proto.ISSL_GeometryData, writer?: $protobuf.Writer): $protobuf.Writer; + public static encodeDelimited(message: proto.ISSL_BallModelStraightTwoPhase, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Decodes a SSL_GeometryData message from the specified reader or buffer. + * Decodes a SSL_BallModelStraightTwoPhase message from the specified reader or buffer. * @param reader Reader or buffer to decode from * @param [length] Message length if known beforehand - * @returns SSL_GeometryData + * @returns SSL_BallModelStraightTwoPhase * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.SSL_GeometryData; + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.SSL_BallModelStraightTwoPhase; /** - * Decodes a SSL_GeometryData message from the specified reader or buffer, length delimited. + * Decodes a SSL_BallModelStraightTwoPhase message from the specified reader or buffer, length delimited. * @param reader Reader or buffer to decode from - * @returns SSL_GeometryData + * @returns SSL_BallModelStraightTwoPhase * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.SSL_GeometryData; + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.SSL_BallModelStraightTwoPhase; /** - * Verifies a SSL_GeometryData message. + * Verifies a SSL_BallModelStraightTwoPhase message. * @param message Plain object to verify * @returns `null` if valid, otherwise the reason why it is not */ public static verify(message: { [k: string]: any }): (string|null); /** - * Creates a SSL_GeometryData message from a plain object. Also converts values to their respective internal types. + * Creates a SSL_BallModelStraightTwoPhase message from a plain object. Also converts values to their respective internal types. * @param object Plain object - * @returns SSL_GeometryData + * @returns SSL_BallModelStraightTwoPhase */ - public static fromObject(object: { [k: string]: any }): proto.SSL_GeometryData; + public static fromObject(object: { [k: string]: any }): proto.SSL_BallModelStraightTwoPhase; /** - * Creates a plain object from a SSL_GeometryData message. Also converts values to other types if specified. - * @param message SSL_GeometryData + * Creates a plain object from a SSL_BallModelStraightTwoPhase message. Also converts values to other types if specified. + * @param message SSL_BallModelStraightTwoPhase * @param [options] Conversion options * @returns Plain object */ - public static toObject(message: proto.SSL_GeometryData, options?: $protobuf.IConversionOptions): { [k: string]: any }; + public static toObject(message: proto.SSL_BallModelStraightTwoPhase, options?: $protobuf.IConversionOptions): { [k: string]: any }; /** - * Converts this SSL_GeometryData to JSON. + * Converts this SSL_BallModelStraightTwoPhase to JSON. * @returns JSON object */ public toJSON(): { [k: string]: any }; /** - * Gets the default type url for SSL_GeometryData + * Gets the default type url for SSL_BallModelStraightTwoPhase * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns The default type url */ public static getTypeUrl(typeUrlPrefix?: string): string; } - /** SSL_FieldShapeType enum. */ - enum SSL_FieldShapeType { - Undefined = 0, - CenterCircle = 1, - TopTouchLine = 2, - BottomTouchLine = 3, - LeftGoalLine = 4, - RightGoalLine = 5, - HalfwayLine = 6, - CenterLine = 7, - LeftPenaltyStretch = 8, - RightPenaltyStretch = 9, - LeftFieldLeftPenaltyStretch = 10, - LeftFieldRightPenaltyStretch = 11, - RightFieldLeftPenaltyStretch = 12, - RightFieldRightPenaltyStretch = 13 - } - - /** Properties of a SSL_Referee. */ - interface ISSL_Referee { - - /** SSL_Referee packetTimestamp */ - packetTimestamp: (number|Long); - - /** SSL_Referee stage */ - stage: proto.SSL_Referee.Stage; - - /** SSL_Referee stageTimeLeft */ - stageTimeLeft?: (number|null); - - /** SSL_Referee command */ - command: proto.SSL_Referee.Command; - - /** SSL_Referee commandCounter */ - commandCounter: number; - - /** SSL_Referee commandTimestamp */ - commandTimestamp: (number|Long); - - /** SSL_Referee yellow */ - yellow: proto.SSL_Referee.ITeamInfo; - - /** SSL_Referee blue */ - blue: proto.SSL_Referee.ITeamInfo; - - /** SSL_Referee designatedPosition */ - designatedPosition?: (proto.SSL_Referee.IPoint|null); - - /** SSL_Referee blueTeamOnPositiveHalf */ - blueTeamOnPositiveHalf?: (boolean|null); - - /** SSL_Referee nextCommand */ - nextCommand?: (proto.SSL_Referee.Command|null); + /** Properties of a SSL_BallModelChipFixedLoss. */ + interface ISSL_BallModelChipFixedLoss { - /** SSL_Referee gameEvents */ - gameEvents?: (proto.IGameEvent[]|null); + /** SSL_BallModelChipFixedLoss dampingXyFirstHop */ + dampingXyFirstHop: number; - /** SSL_Referee gameEventProposals */ - gameEventProposals?: (proto.IGameEventProposalGroup[]|null); + /** SSL_BallModelChipFixedLoss dampingXyOtherHops */ + dampingXyOtherHops: number; - /** SSL_Referee currentActionTimeRemaining */ - currentActionTimeRemaining?: (number|null); + /** SSL_BallModelChipFixedLoss dampingZ */ + dampingZ: number; } - /** Represents a SSL_Referee. */ - class SSL_Referee implements ISSL_Referee { + /** Represents a SSL_BallModelChipFixedLoss. */ + class SSL_BallModelChipFixedLoss implements ISSL_BallModelChipFixedLoss { /** - * Constructs a new SSL_Referee. + * Constructs a new SSL_BallModelChipFixedLoss. * @param [properties] Properties to set */ - constructor(properties?: proto.ISSL_Referee); - - /** SSL_Referee packetTimestamp. */ - public packetTimestamp: (number|Long); - - /** SSL_Referee stage. */ - public stage: proto.SSL_Referee.Stage; - - /** SSL_Referee stageTimeLeft. */ - public stageTimeLeft: number; - - /** SSL_Referee command. */ - public command: proto.SSL_Referee.Command; - - /** SSL_Referee commandCounter. */ - public commandCounter: number; - - /** SSL_Referee commandTimestamp. */ - public commandTimestamp: (number|Long); - - /** SSL_Referee yellow. */ - public yellow: proto.SSL_Referee.ITeamInfo; - - /** SSL_Referee blue. */ - public blue: proto.SSL_Referee.ITeamInfo; - - /** SSL_Referee designatedPosition. */ - public designatedPosition?: (proto.SSL_Referee.IPoint|null); + constructor(properties?: proto.ISSL_BallModelChipFixedLoss); - /** SSL_Referee blueTeamOnPositiveHalf. */ - public blueTeamOnPositiveHalf: boolean; - - /** SSL_Referee nextCommand. */ - public nextCommand: proto.SSL_Referee.Command; - - /** SSL_Referee gameEvents. */ - public gameEvents: proto.IGameEvent[]; + /** SSL_BallModelChipFixedLoss dampingXyFirstHop. */ + public dampingXyFirstHop: number; - /** SSL_Referee gameEventProposals. */ - public gameEventProposals: proto.IGameEventProposalGroup[]; + /** SSL_BallModelChipFixedLoss dampingXyOtherHops. */ + public dampingXyOtherHops: number; - /** SSL_Referee currentActionTimeRemaining. */ - public currentActionTimeRemaining: number; + /** SSL_BallModelChipFixedLoss dampingZ. */ + public dampingZ: number; /** - * Creates a new SSL_Referee instance using the specified properties. + * Creates a new SSL_BallModelChipFixedLoss instance using the specified properties. * @param [properties] Properties to set - * @returns SSL_Referee instance + * @returns SSL_BallModelChipFixedLoss instance */ - public static create(properties?: proto.ISSL_Referee): proto.SSL_Referee; + public static create(properties?: proto.ISSL_BallModelChipFixedLoss): proto.SSL_BallModelChipFixedLoss; /** - * Encodes the specified SSL_Referee message. Does not implicitly {@link proto.SSL_Referee.verify|verify} messages. - * @param message SSL_Referee message or plain object to encode + * Encodes the specified SSL_BallModelChipFixedLoss message. Does not implicitly {@link proto.SSL_BallModelChipFixedLoss.verify|verify} messages. + * @param message SSL_BallModelChipFixedLoss message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encode(message: proto.ISSL_Referee, writer?: $protobuf.Writer): $protobuf.Writer; + public static encode(message: proto.ISSL_BallModelChipFixedLoss, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Encodes the specified SSL_Referee message, length delimited. Does not implicitly {@link proto.SSL_Referee.verify|verify} messages. - * @param message SSL_Referee message or plain object to encode + * Encodes the specified SSL_BallModelChipFixedLoss message, length delimited. Does not implicitly {@link proto.SSL_BallModelChipFixedLoss.verify|verify} messages. + * @param message SSL_BallModelChipFixedLoss message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encodeDelimited(message: proto.ISSL_Referee, writer?: $protobuf.Writer): $protobuf.Writer; + public static encodeDelimited(message: proto.ISSL_BallModelChipFixedLoss, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Decodes a SSL_Referee message from the specified reader or buffer. + * Decodes a SSL_BallModelChipFixedLoss message from the specified reader or buffer. * @param reader Reader or buffer to decode from * @param [length] Message length if known beforehand - * @returns SSL_Referee + * @returns SSL_BallModelChipFixedLoss * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.SSL_Referee; + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.SSL_BallModelChipFixedLoss; /** - * Decodes a SSL_Referee message from the specified reader or buffer, length delimited. + * Decodes a SSL_BallModelChipFixedLoss message from the specified reader or buffer, length delimited. * @param reader Reader or buffer to decode from - * @returns SSL_Referee + * @returns SSL_BallModelChipFixedLoss * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.SSL_Referee; + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.SSL_BallModelChipFixedLoss; /** - * Verifies a SSL_Referee message. + * Verifies a SSL_BallModelChipFixedLoss message. * @param message Plain object to verify * @returns `null` if valid, otherwise the reason why it is not */ public static verify(message: { [k: string]: any }): (string|null); /** - * Creates a SSL_Referee message from a plain object. Also converts values to their respective internal types. + * Creates a SSL_BallModelChipFixedLoss message from a plain object. Also converts values to their respective internal types. * @param object Plain object - * @returns SSL_Referee + * @returns SSL_BallModelChipFixedLoss */ - public static fromObject(object: { [k: string]: any }): proto.SSL_Referee; + public static fromObject(object: { [k: string]: any }): proto.SSL_BallModelChipFixedLoss; /** - * Creates a plain object from a SSL_Referee message. Also converts values to other types if specified. - * @param message SSL_Referee + * Creates a plain object from a SSL_BallModelChipFixedLoss message. Also converts values to other types if specified. + * @param message SSL_BallModelChipFixedLoss * @param [options] Conversion options * @returns Plain object */ - public static toObject(message: proto.SSL_Referee, options?: $protobuf.IConversionOptions): { [k: string]: any }; + public static toObject(message: proto.SSL_BallModelChipFixedLoss, options?: $protobuf.IConversionOptions): { [k: string]: any }; /** - * Converts this SSL_Referee to JSON. + * Converts this SSL_BallModelChipFixedLoss to JSON. * @returns JSON object */ public toJSON(): { [k: string]: any }; /** - * Gets the default type url for SSL_Referee + * Gets the default type url for SSL_BallModelChipFixedLoss * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns The default type url */ public static getTypeUrl(typeUrlPrefix?: string): string; } - namespace SSL_Referee { + /** Properties of a SSL_GeometryModels. */ + interface ISSL_GeometryModels { - /** Stage enum. */ - enum Stage { - NORMAL_FIRST_HALF_PRE = 0, - NORMAL_FIRST_HALF = 1, - NORMAL_HALF_TIME = 2, - NORMAL_SECOND_HALF_PRE = 3, - NORMAL_SECOND_HALF = 4, - EXTRA_TIME_BREAK = 5, - EXTRA_FIRST_HALF_PRE = 6, - EXTRA_FIRST_HALF = 7, - EXTRA_HALF_TIME = 8, + /** SSL_GeometryModels straightTwoPhase */ + straightTwoPhase?: (proto.ISSL_BallModelStraightTwoPhase|null); + + /** SSL_GeometryModels chipFixedLoss */ + chipFixedLoss?: (proto.ISSL_BallModelChipFixedLoss|null); + } + + /** Represents a SSL_GeometryModels. */ + class SSL_GeometryModels implements ISSL_GeometryModels { + + /** + * Constructs a new SSL_GeometryModels. + * @param [properties] Properties to set + */ + constructor(properties?: proto.ISSL_GeometryModels); + + /** SSL_GeometryModels straightTwoPhase. */ + public straightTwoPhase?: (proto.ISSL_BallModelStraightTwoPhase|null); + + /** SSL_GeometryModels chipFixedLoss. */ + public chipFixedLoss?: (proto.ISSL_BallModelChipFixedLoss|null); + + /** + * Creates a new SSL_GeometryModels instance using the specified properties. + * @param [properties] Properties to set + * @returns SSL_GeometryModels instance + */ + public static create(properties?: proto.ISSL_GeometryModels): proto.SSL_GeometryModels; + + /** + * Encodes the specified SSL_GeometryModels message. Does not implicitly {@link proto.SSL_GeometryModels.verify|verify} messages. + * @param message SSL_GeometryModels message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encode(message: proto.ISSL_GeometryModels, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Encodes the specified SSL_GeometryModels message, length delimited. Does not implicitly {@link proto.SSL_GeometryModels.verify|verify} messages. + * @param message SSL_GeometryModels message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encodeDelimited(message: proto.ISSL_GeometryModels, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Decodes a SSL_GeometryModels message from the specified reader or buffer. + * @param reader Reader or buffer to decode from + * @param [length] Message length if known beforehand + * @returns SSL_GeometryModels + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.SSL_GeometryModels; + + /** + * Decodes a SSL_GeometryModels message from the specified reader or buffer, length delimited. + * @param reader Reader or buffer to decode from + * @returns SSL_GeometryModels + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.SSL_GeometryModels; + + /** + * Verifies a SSL_GeometryModels message. + * @param message Plain object to verify + * @returns `null` if valid, otherwise the reason why it is not + */ + public static verify(message: { [k: string]: any }): (string|null); + + /** + * Creates a SSL_GeometryModels message from a plain object. Also converts values to their respective internal types. + * @param object Plain object + * @returns SSL_GeometryModels + */ + public static fromObject(object: { [k: string]: any }): proto.SSL_GeometryModels; + + /** + * Creates a plain object from a SSL_GeometryModels message. Also converts values to other types if specified. + * @param message SSL_GeometryModels + * @param [options] Conversion options + * @returns Plain object + */ + public static toObject(message: proto.SSL_GeometryModels, options?: $protobuf.IConversionOptions): { [k: string]: any }; + + /** + * Converts this SSL_GeometryModels to JSON. + * @returns JSON object + */ + public toJSON(): { [k: string]: any }; + + /** + * Gets the default type url for SSL_GeometryModels + * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns The default type url + */ + public static getTypeUrl(typeUrlPrefix?: string): string; + } + + /** Properties of a SSL_GeometryData. */ + interface ISSL_GeometryData { + + /** SSL_GeometryData field */ + field: proto.ISSL_GeometryFieldSize; + + /** SSL_GeometryData calib */ + calib?: (proto.ISSL_GeometryCameraCalibration[]|null); + + /** SSL_GeometryData models */ + models?: (proto.ISSL_GeometryModels|null); + } + + /** Represents a SSL_GeometryData. */ + class SSL_GeometryData implements ISSL_GeometryData { + + /** + * Constructs a new SSL_GeometryData. + * @param [properties] Properties to set + */ + constructor(properties?: proto.ISSL_GeometryData); + + /** SSL_GeometryData field. */ + public field: proto.ISSL_GeometryFieldSize; + + /** SSL_GeometryData calib. */ + public calib: proto.ISSL_GeometryCameraCalibration[]; + + /** SSL_GeometryData models. */ + public models?: (proto.ISSL_GeometryModels|null); + + /** + * Creates a new SSL_GeometryData instance using the specified properties. + * @param [properties] Properties to set + * @returns SSL_GeometryData instance + */ + public static create(properties?: proto.ISSL_GeometryData): proto.SSL_GeometryData; + + /** + * Encodes the specified SSL_GeometryData message. Does not implicitly {@link proto.SSL_GeometryData.verify|verify} messages. + * @param message SSL_GeometryData message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encode(message: proto.ISSL_GeometryData, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Encodes the specified SSL_GeometryData message, length delimited. Does not implicitly {@link proto.SSL_GeometryData.verify|verify} messages. + * @param message SSL_GeometryData message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encodeDelimited(message: proto.ISSL_GeometryData, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Decodes a SSL_GeometryData message from the specified reader or buffer. + * @param reader Reader or buffer to decode from + * @param [length] Message length if known beforehand + * @returns SSL_GeometryData + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.SSL_GeometryData; + + /** + * Decodes a SSL_GeometryData message from the specified reader or buffer, length delimited. + * @param reader Reader or buffer to decode from + * @returns SSL_GeometryData + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.SSL_GeometryData; + + /** + * Verifies a SSL_GeometryData message. + * @param message Plain object to verify + * @returns `null` if valid, otherwise the reason why it is not + */ + public static verify(message: { [k: string]: any }): (string|null); + + /** + * Creates a SSL_GeometryData message from a plain object. Also converts values to their respective internal types. + * @param object Plain object + * @returns SSL_GeometryData + */ + public static fromObject(object: { [k: string]: any }): proto.SSL_GeometryData; + + /** + * Creates a plain object from a SSL_GeometryData message. Also converts values to other types if specified. + * @param message SSL_GeometryData + * @param [options] Conversion options + * @returns Plain object + */ + public static toObject(message: proto.SSL_GeometryData, options?: $protobuf.IConversionOptions): { [k: string]: any }; + + /** + * Converts this SSL_GeometryData to JSON. + * @returns JSON object + */ + public toJSON(): { [k: string]: any }; + + /** + * Gets the default type url for SSL_GeometryData + * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns The default type url + */ + public static getTypeUrl(typeUrlPrefix?: string): string; + } + + /** SSL_FieldShapeType enum. */ + enum SSL_FieldShapeType { + Undefined = 0, + CenterCircle = 1, + TopTouchLine = 2, + BottomTouchLine = 3, + LeftGoalLine = 4, + RightGoalLine = 5, + HalfwayLine = 6, + CenterLine = 7, + LeftPenaltyStretch = 8, + RightPenaltyStretch = 9, + LeftFieldLeftPenaltyStretch = 10, + LeftFieldRightPenaltyStretch = 11, + RightFieldLeftPenaltyStretch = 12, + RightFieldRightPenaltyStretch = 13 + } + + /** Properties of a Referee. */ + interface IReferee { + + /** Referee sourceIdentifier */ + sourceIdentifier?: (string|null); + + /** Referee matchType */ + matchType?: (proto.MatchType|null); + + /** Referee packetTimestamp */ + packetTimestamp: (number|Long); + + /** Referee stage */ + stage: proto.Referee.Stage; + + /** Referee stageTimeLeft */ + stageTimeLeft?: (number|Long|null); + + /** Referee command */ + command: proto.Referee.Command; + + /** Referee commandCounter */ + commandCounter: number; + + /** Referee commandTimestamp */ + commandTimestamp: (number|Long); + + /** Referee yellow */ + yellow: proto.Referee.ITeamInfo; + + /** Referee blue */ + blue: proto.Referee.ITeamInfo; + + /** Referee designatedPosition */ + designatedPosition?: (proto.Referee.IPoint|null); + + /** Referee blueTeamOnPositiveHalf */ + blueTeamOnPositiveHalf?: (boolean|null); + + /** Referee nextCommand */ + nextCommand?: (proto.Referee.Command|null); + + /** Referee gameEvents */ + gameEvents?: (proto.IGameEvent[]|null); + + /** Referee gameEventProposals */ + gameEventProposals?: (proto.IGameEventProposalGroup[]|null); + + /** Referee currentActionTimeRemaining */ + currentActionTimeRemaining?: (number|Long|null); + + /** Referee statusMessage */ + statusMessage?: (string|null); + } + + /** Represents a Referee. */ + class Referee implements IReferee { + + /** + * Constructs a new Referee. + * @param [properties] Properties to set + */ + constructor(properties?: proto.IReferee); + + /** Referee sourceIdentifier. */ + public sourceIdentifier: string; + + /** Referee matchType. */ + public matchType: proto.MatchType; + + /** Referee packetTimestamp. */ + public packetTimestamp: (number|Long); + + /** Referee stage. */ + public stage: proto.Referee.Stage; + + /** Referee stageTimeLeft. */ + public stageTimeLeft: (number|Long); + + /** Referee command. */ + public command: proto.Referee.Command; + + /** Referee commandCounter. */ + public commandCounter: number; + + /** Referee commandTimestamp. */ + public commandTimestamp: (number|Long); + + /** Referee yellow. */ + public yellow: proto.Referee.ITeamInfo; + + /** Referee blue. */ + public blue: proto.Referee.ITeamInfo; + + /** Referee designatedPosition. */ + public designatedPosition?: (proto.Referee.IPoint|null); + + /** Referee blueTeamOnPositiveHalf. */ + public blueTeamOnPositiveHalf: boolean; + + /** Referee nextCommand. */ + public nextCommand: proto.Referee.Command; + + /** Referee gameEvents. */ + public gameEvents: proto.IGameEvent[]; + + /** Referee gameEventProposals. */ + public gameEventProposals: proto.IGameEventProposalGroup[]; + + /** Referee currentActionTimeRemaining. */ + public currentActionTimeRemaining: (number|Long); + + /** Referee statusMessage. */ + public statusMessage: string; + + /** + * Creates a new Referee instance using the specified properties. + * @param [properties] Properties to set + * @returns Referee instance + */ + public static create(properties?: proto.IReferee): proto.Referee; + + /** + * Encodes the specified Referee message. Does not implicitly {@link proto.Referee.verify|verify} messages. + * @param message Referee message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encode(message: proto.IReferee, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Encodes the specified Referee message, length delimited. Does not implicitly {@link proto.Referee.verify|verify} messages. + * @param message Referee message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encodeDelimited(message: proto.IReferee, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Decodes a Referee message from the specified reader or buffer. + * @param reader Reader or buffer to decode from + * @param [length] Message length if known beforehand + * @returns Referee + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.Referee; + + /** + * Decodes a Referee message from the specified reader or buffer, length delimited. + * @param reader Reader or buffer to decode from + * @returns Referee + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.Referee; + + /** + * Verifies a Referee message. + * @param message Plain object to verify + * @returns `null` if valid, otherwise the reason why it is not + */ + public static verify(message: { [k: string]: any }): (string|null); + + /** + * Creates a Referee message from a plain object. Also converts values to their respective internal types. + * @param object Plain object + * @returns Referee + */ + public static fromObject(object: { [k: string]: any }): proto.Referee; + + /** + * Creates a plain object from a Referee message. Also converts values to other types if specified. + * @param message Referee + * @param [options] Conversion options + * @returns Plain object + */ + public static toObject(message: proto.Referee, options?: $protobuf.IConversionOptions): { [k: string]: any }; + + /** + * Converts this Referee to JSON. + * @returns JSON object + */ + public toJSON(): { [k: string]: any }; + + /** + * Gets the default type url for Referee + * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns The default type url + */ + public static getTypeUrl(typeUrlPrefix?: string): string; + } + + namespace Referee { + + /** Stage enum. */ + enum Stage { + NORMAL_FIRST_HALF_PRE = 0, + NORMAL_FIRST_HALF = 1, + NORMAL_HALF_TIME = 2, + NORMAL_SECOND_HALF_PRE = 3, + NORMAL_SECOND_HALF = 4, + EXTRA_TIME_BREAK = 5, + EXTRA_FIRST_HALF_PRE = 6, + EXTRA_FIRST_HALF = 7, + EXTRA_HALF_TIME = 8, EXTRA_SECOND_HALF_PRE = 9, EXTRA_SECOND_HALF = 10, PENALTY_SHOOTOUT_BREAK = 11, @@ -4828,6 +4983,9 @@ export namespace proto { /** TeamInfo ballPlacementFailuresReached */ ballPlacementFailuresReached?: (boolean|null); + + /** TeamInfo botSubstitutionAllowed */ + botSubstitutionAllowed?: (boolean|null); } /** Represents a TeamInfo. */ @@ -4837,7 +4995,7 @@ export namespace proto { * Constructs a new TeamInfo. * @param [properties] Properties to set */ - constructor(properties?: proto.SSL_Referee.ITeamInfo); + constructor(properties?: proto.Referee.ITeamInfo); /** TeamInfo name. */ public name: string; @@ -4881,28 +5039,31 @@ export namespace proto { /** TeamInfo ballPlacementFailuresReached. */ public ballPlacementFailuresReached: boolean; + /** TeamInfo botSubstitutionAllowed. */ + public botSubstitutionAllowed: boolean; + /** * Creates a new TeamInfo instance using the specified properties. * @param [properties] Properties to set * @returns TeamInfo instance */ - public static create(properties?: proto.SSL_Referee.ITeamInfo): proto.SSL_Referee.TeamInfo; + public static create(properties?: proto.Referee.ITeamInfo): proto.Referee.TeamInfo; /** - * Encodes the specified TeamInfo message. Does not implicitly {@link proto.SSL_Referee.TeamInfo.verify|verify} messages. + * Encodes the specified TeamInfo message. Does not implicitly {@link proto.Referee.TeamInfo.verify|verify} messages. * @param message TeamInfo message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encode(message: proto.SSL_Referee.ITeamInfo, writer?: $protobuf.Writer): $protobuf.Writer; + public static encode(message: proto.Referee.ITeamInfo, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Encodes the specified TeamInfo message, length delimited. Does not implicitly {@link proto.SSL_Referee.TeamInfo.verify|verify} messages. + * Encodes the specified TeamInfo message, length delimited. Does not implicitly {@link proto.Referee.TeamInfo.verify|verify} messages. * @param message TeamInfo message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encodeDelimited(message: proto.SSL_Referee.ITeamInfo, writer?: $protobuf.Writer): $protobuf.Writer; + public static encodeDelimited(message: proto.Referee.ITeamInfo, writer?: $protobuf.Writer): $protobuf.Writer; /** * Decodes a TeamInfo message from the specified reader or buffer. @@ -4912,7 +5073,7 @@ export namespace proto { * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.SSL_Referee.TeamInfo; + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.Referee.TeamInfo; /** * Decodes a TeamInfo message from the specified reader or buffer, length delimited. @@ -4921,7 +5082,7 @@ export namespace proto { * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.SSL_Referee.TeamInfo; + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.Referee.TeamInfo; /** * Verifies a TeamInfo message. @@ -4935,7 +5096,7 @@ export namespace proto { * @param object Plain object * @returns TeamInfo */ - public static fromObject(object: { [k: string]: any }): proto.SSL_Referee.TeamInfo; + public static fromObject(object: { [k: string]: any }): proto.Referee.TeamInfo; /** * Creates a plain object from a TeamInfo message. Also converts values to other types if specified. @@ -4943,7 +5104,7 @@ export namespace proto { * @param [options] Conversion options * @returns Plain object */ - public static toObject(message: proto.SSL_Referee.TeamInfo, options?: $protobuf.IConversionOptions): { [k: string]: any }; + public static toObject(message: proto.Referee.TeamInfo, options?: $protobuf.IConversionOptions): { [k: string]: any }; /** * Converts this TeamInfo to JSON. @@ -4976,7 +5137,7 @@ export namespace proto { * Constructs a new Point. * @param [properties] Properties to set */ - constructor(properties?: proto.SSL_Referee.IPoint); + constructor(properties?: proto.Referee.IPoint); /** Point x. */ public x: number; @@ -4989,23 +5150,23 @@ export namespace proto { * @param [properties] Properties to set * @returns Point instance */ - public static create(properties?: proto.SSL_Referee.IPoint): proto.SSL_Referee.Point; + public static create(properties?: proto.Referee.IPoint): proto.Referee.Point; /** - * Encodes the specified Point message. Does not implicitly {@link proto.SSL_Referee.Point.verify|verify} messages. + * Encodes the specified Point message. Does not implicitly {@link proto.Referee.Point.verify|verify} messages. * @param message Point message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encode(message: proto.SSL_Referee.IPoint, writer?: $protobuf.Writer): $protobuf.Writer; + public static encode(message: proto.Referee.IPoint, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Encodes the specified Point message, length delimited. Does not implicitly {@link proto.SSL_Referee.Point.verify|verify} messages. + * Encodes the specified Point message, length delimited. Does not implicitly {@link proto.Referee.Point.verify|verify} messages. * @param message Point message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encodeDelimited(message: proto.SSL_Referee.IPoint, writer?: $protobuf.Writer): $protobuf.Writer; + public static encodeDelimited(message: proto.Referee.IPoint, writer?: $protobuf.Writer): $protobuf.Writer; /** * Decodes a Point message from the specified reader or buffer. @@ -5015,7 +5176,7 @@ export namespace proto { * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.SSL_Referee.Point; + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.Referee.Point; /** * Decodes a Point message from the specified reader or buffer, length delimited. @@ -5024,7 +5185,7 @@ export namespace proto { * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.SSL_Referee.Point; + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.Referee.Point; /** * Verifies a Point message. @@ -5038,7 +5199,7 @@ export namespace proto { * @param object Plain object * @returns Point */ - public static fromObject(object: { [k: string]: any }): proto.SSL_Referee.Point; + public static fromObject(object: { [k: string]: any }): proto.Referee.Point; /** * Creates a plain object from a Point message. Also converts values to other types if specified. @@ -5046,7 +5207,7 @@ export namespace proto { * @param [options] Conversion options * @returns Plain object */ - public static toObject(message: proto.SSL_Referee.Point, options?: $protobuf.IConversionOptions): { [k: string]: any }; + public static toObject(message: proto.Referee.Point, options?: $protobuf.IConversionOptions): { [k: string]: any }; /** * Converts this Point to JSON. @@ -5066,8 +5227,11 @@ export namespace proto { /** Properties of a GameEventProposalGroup. */ interface IGameEventProposalGroup { - /** GameEventProposalGroup gameEvent */ - gameEvent?: (proto.IGameEvent[]|null); + /** GameEventProposalGroup id */ + id?: (string|null); + + /** GameEventProposalGroup gameEvents */ + gameEvents?: (proto.IGameEvent[]|null); /** GameEventProposalGroup accepted */ accepted?: (boolean|null); @@ -5082,8 +5246,11 @@ export namespace proto { */ constructor(properties?: proto.IGameEventProposalGroup); - /** GameEventProposalGroup gameEvent. */ - public gameEvent: proto.IGameEvent[]; + /** GameEventProposalGroup id. */ + public id: string; + + /** GameEventProposalGroup gameEvents. */ + public gameEvents: proto.IGameEvent[]; /** GameEventProposalGroup accepted. */ public accepted: boolean; @@ -5166,15 +5333,29 @@ export namespace proto { public static getTypeUrl(typeUrlPrefix?: string): string; } + /** MatchType enum. */ + enum MatchType { + UNKNOWN_MATCH = 0, + GROUP_PHASE = 1, + ELIMINATION_PHASE = 2, + FRIENDLY = 3 + } + /** Properties of a GameEvent. */ interface IGameEvent { + /** GameEvent id */ + id?: (string|null); + /** GameEvent type */ type?: (proto.GameEvent.Type|null); /** GameEvent origin */ origin?: (string[]|null); + /** GameEvent createdTimestamp */ + createdTimestamp?: (number|Long|null); + /** GameEvent ballLeftFieldTouchLine */ ballLeftFieldTouchLine?: (proto.GameEvent.IBallLeftField|null); @@ -5208,6 +5389,9 @@ export namespace proto { /** GameEvent botTippedOver */ botTippedOver?: (proto.GameEvent.IBotTippedOver|null); + /** GameEvent botDroppedParts */ + botDroppedParts?: (proto.GameEvent.IBotDroppedParts|null); + /** GameEvent attackerTouchedBallInDefenseArea */ attackerTouchedBallInDefenseArea?: (proto.GameEvent.IAttackerTouchedBallInDefenseArea|null); @@ -5268,6 +5452,9 @@ export namespace proto { /** GameEvent challengeFlag */ challengeFlag?: (proto.GameEvent.IChallengeFlag|null); + /** GameEvent challengeFlagHandled */ + challengeFlagHandled?: (proto.GameEvent.IChallengeFlagHandled|null); + /** GameEvent emergencyStop */ emergencyStop?: (proto.GameEvent.IEmergencyStop|null); @@ -5287,12 +5474,18 @@ export namespace proto { */ constructor(properties?: proto.IGameEvent); + /** GameEvent id. */ + public id: string; + /** GameEvent type. */ public type: proto.GameEvent.Type; /** GameEvent origin. */ public origin: string[]; + /** GameEvent createdTimestamp. */ + public createdTimestamp: (number|Long); + /** GameEvent ballLeftFieldTouchLine. */ public ballLeftFieldTouchLine?: (proto.GameEvent.IBallLeftField|null); @@ -5326,6 +5519,9 @@ export namespace proto { /** GameEvent botTippedOver. */ public botTippedOver?: (proto.GameEvent.IBotTippedOver|null); + /** GameEvent botDroppedParts. */ + public botDroppedParts?: (proto.GameEvent.IBotDroppedParts|null); + /** GameEvent attackerTouchedBallInDefenseArea. */ public attackerTouchedBallInDefenseArea?: (proto.GameEvent.IAttackerTouchedBallInDefenseArea|null); @@ -5386,6 +5582,9 @@ export namespace proto { /** GameEvent challengeFlag. */ public challengeFlag?: (proto.GameEvent.IChallengeFlag|null); + /** GameEvent challengeFlagHandled. */ + public challengeFlagHandled?: (proto.GameEvent.IChallengeFlagHandled|null); + /** GameEvent emergencyStop. */ public emergencyStop?: (proto.GameEvent.IEmergencyStop|null); @@ -5396,7 +5595,7 @@ export namespace proto { public unsportingBehaviorMajor?: (proto.GameEvent.IUnsportingBehaviorMajor|null); /** GameEvent event. */ - public event?: ("ballLeftFieldTouchLine"|"ballLeftFieldGoalLine"|"aimlessKick"|"attackerTooCloseToDefenseArea"|"defenderInDefenseArea"|"boundaryCrossing"|"keeperHeldBall"|"botDribbledBallTooFar"|"botPushedBot"|"botHeldBallDeliberately"|"botTippedOver"|"attackerTouchedBallInDefenseArea"|"botKickedBallTooFast"|"botCrashUnique"|"botCrashDrawn"|"defenderTooCloseToKickPoint"|"botTooFastInStop"|"botInterferedPlacement"|"possibleGoal"|"goal"|"invalidGoal"|"attackerDoubleTouchedBall"|"placementSucceeded"|"penaltyKickFailed"|"noProgressInGame"|"placementFailed"|"multipleCards"|"multipleFouls"|"botSubstitution"|"tooManyRobots"|"challengeFlag"|"emergencyStop"|"unsportingBehaviorMinor"|"unsportingBehaviorMajor"); + public event?: ("ballLeftFieldTouchLine"|"ballLeftFieldGoalLine"|"aimlessKick"|"attackerTooCloseToDefenseArea"|"defenderInDefenseArea"|"boundaryCrossing"|"keeperHeldBall"|"botDribbledBallTooFar"|"botPushedBot"|"botHeldBallDeliberately"|"botTippedOver"|"botDroppedParts"|"attackerTouchedBallInDefenseArea"|"botKickedBallTooFast"|"botCrashUnique"|"botCrashDrawn"|"defenderTooCloseToKickPoint"|"botTooFastInStop"|"botInterferedPlacement"|"possibleGoal"|"goal"|"invalidGoal"|"attackerDoubleTouchedBall"|"placementSucceeded"|"penaltyKickFailed"|"noProgressInGame"|"placementFailed"|"multipleCards"|"multipleFouls"|"botSubstitution"|"tooManyRobots"|"challengeFlag"|"challengeFlagHandled"|"emergencyStop"|"unsportingBehaviorMinor"|"unsportingBehaviorMajor"); /** * Creates a new GameEvent instance using the specified properties. @@ -6809,6 +7008,121 @@ export namespace proto { public static getTypeUrl(typeUrlPrefix?: string): string; } + /** Properties of a BotDroppedParts. */ + interface IBotDroppedParts { + + /** BotDroppedParts byTeam */ + byTeam: proto.Team; + + /** BotDroppedParts byBot */ + byBot?: (number|null); + + /** BotDroppedParts location */ + location?: (proto.IVector2|null); + + /** BotDroppedParts ballLocation */ + ballLocation?: (proto.IVector2|null); + } + + /** Represents a BotDroppedParts. */ + class BotDroppedParts implements IBotDroppedParts { + + /** + * Constructs a new BotDroppedParts. + * @param [properties] Properties to set + */ + constructor(properties?: proto.GameEvent.IBotDroppedParts); + + /** BotDroppedParts byTeam. */ + public byTeam: proto.Team; + + /** BotDroppedParts byBot. */ + public byBot: number; + + /** BotDroppedParts location. */ + public location?: (proto.IVector2|null); + + /** BotDroppedParts ballLocation. */ + public ballLocation?: (proto.IVector2|null); + + /** + * Creates a new BotDroppedParts instance using the specified properties. + * @param [properties] Properties to set + * @returns BotDroppedParts instance + */ + public static create(properties?: proto.GameEvent.IBotDroppedParts): proto.GameEvent.BotDroppedParts; + + /** + * Encodes the specified BotDroppedParts message. Does not implicitly {@link proto.GameEvent.BotDroppedParts.verify|verify} messages. + * @param message BotDroppedParts message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encode(message: proto.GameEvent.IBotDroppedParts, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Encodes the specified BotDroppedParts message, length delimited. Does not implicitly {@link proto.GameEvent.BotDroppedParts.verify|verify} messages. + * @param message BotDroppedParts message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encodeDelimited(message: proto.GameEvent.IBotDroppedParts, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Decodes a BotDroppedParts message from the specified reader or buffer. + * @param reader Reader or buffer to decode from + * @param [length] Message length if known beforehand + * @returns BotDroppedParts + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.GameEvent.BotDroppedParts; + + /** + * Decodes a BotDroppedParts message from the specified reader or buffer, length delimited. + * @param reader Reader or buffer to decode from + * @returns BotDroppedParts + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.GameEvent.BotDroppedParts; + + /** + * Verifies a BotDroppedParts message. + * @param message Plain object to verify + * @returns `null` if valid, otherwise the reason why it is not + */ + public static verify(message: { [k: string]: any }): (string|null); + + /** + * Creates a BotDroppedParts message from a plain object. Also converts values to their respective internal types. + * @param object Plain object + * @returns BotDroppedParts + */ + public static fromObject(object: { [k: string]: any }): proto.GameEvent.BotDroppedParts; + + /** + * Creates a plain object from a BotDroppedParts message. Also converts values to other types if specified. + * @param message BotDroppedParts + * @param [options] Conversion options + * @returns Plain object + */ + public static toObject(message: proto.GameEvent.BotDroppedParts, options?: $protobuf.IConversionOptions): { [k: string]: any }; + + /** + * Converts this BotDroppedParts to JSON. + * @returns JSON object + */ + public toJSON(): { [k: string]: any }; + + /** + * Gets the default type url for BotDroppedParts + * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns The default type url + */ + public static getTypeUrl(typeUrlPrefix?: string): string; + } + /** Properties of a DefenderInDefenseArea. */ interface IDefenderInDefenseArea { @@ -8067,6 +8381,9 @@ export namespace proto { /** MultipleFouls byTeam */ byTeam: proto.Team; + + /** MultipleFouls causedGameEvents */ + causedGameEvents?: (proto.IGameEvent[]|null); } /** Represents a MultipleFouls. */ @@ -8081,6 +8398,9 @@ export namespace proto { /** MultipleFouls byTeam. */ public byTeam: proto.Team; + /** MultipleFouls causedGameEvents. */ + public causedGameEvents: proto.IGameEvent[]; + /** * Creates a new MultipleFouls instance using the specified properties. * @param [properties] Properties to set @@ -9188,104 +9508,207 @@ export namespace proto { public toJSON(): { [k: string]: any }; /** - * Gets the default type url for BotSubstitution + * Gets the default type url for BotSubstitution + * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns The default type url + */ + public static getTypeUrl(typeUrlPrefix?: string): string; + } + + /** Properties of a ChallengeFlag. */ + interface IChallengeFlag { + + /** ChallengeFlag byTeam */ + byTeam: proto.Team; + } + + /** Represents a ChallengeFlag. */ + class ChallengeFlag implements IChallengeFlag { + + /** + * Constructs a new ChallengeFlag. + * @param [properties] Properties to set + */ + constructor(properties?: proto.GameEvent.IChallengeFlag); + + /** ChallengeFlag byTeam. */ + public byTeam: proto.Team; + + /** + * Creates a new ChallengeFlag instance using the specified properties. + * @param [properties] Properties to set + * @returns ChallengeFlag instance + */ + public static create(properties?: proto.GameEvent.IChallengeFlag): proto.GameEvent.ChallengeFlag; + + /** + * Encodes the specified ChallengeFlag message. Does not implicitly {@link proto.GameEvent.ChallengeFlag.verify|verify} messages. + * @param message ChallengeFlag message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encode(message: proto.GameEvent.IChallengeFlag, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Encodes the specified ChallengeFlag message, length delimited. Does not implicitly {@link proto.GameEvent.ChallengeFlag.verify|verify} messages. + * @param message ChallengeFlag message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encodeDelimited(message: proto.GameEvent.IChallengeFlag, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Decodes a ChallengeFlag message from the specified reader or buffer. + * @param reader Reader or buffer to decode from + * @param [length] Message length if known beforehand + * @returns ChallengeFlag + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.GameEvent.ChallengeFlag; + + /** + * Decodes a ChallengeFlag message from the specified reader or buffer, length delimited. + * @param reader Reader or buffer to decode from + * @returns ChallengeFlag + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.GameEvent.ChallengeFlag; + + /** + * Verifies a ChallengeFlag message. + * @param message Plain object to verify + * @returns `null` if valid, otherwise the reason why it is not + */ + public static verify(message: { [k: string]: any }): (string|null); + + /** + * Creates a ChallengeFlag message from a plain object. Also converts values to their respective internal types. + * @param object Plain object + * @returns ChallengeFlag + */ + public static fromObject(object: { [k: string]: any }): proto.GameEvent.ChallengeFlag; + + /** + * Creates a plain object from a ChallengeFlag message. Also converts values to other types if specified. + * @param message ChallengeFlag + * @param [options] Conversion options + * @returns Plain object + */ + public static toObject(message: proto.GameEvent.ChallengeFlag, options?: $protobuf.IConversionOptions): { [k: string]: any }; + + /** + * Converts this ChallengeFlag to JSON. + * @returns JSON object + */ + public toJSON(): { [k: string]: any }; + + /** + * Gets the default type url for ChallengeFlag * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns The default type url */ public static getTypeUrl(typeUrlPrefix?: string): string; } - /** Properties of a ChallengeFlag. */ - interface IChallengeFlag { + /** Properties of a ChallengeFlagHandled. */ + interface IChallengeFlagHandled { - /** ChallengeFlag byTeam */ + /** ChallengeFlagHandled byTeam */ byTeam: proto.Team; + + /** ChallengeFlagHandled accepted */ + accepted: boolean; } - /** Represents a ChallengeFlag. */ - class ChallengeFlag implements IChallengeFlag { + /** Represents a ChallengeFlagHandled. */ + class ChallengeFlagHandled implements IChallengeFlagHandled { /** - * Constructs a new ChallengeFlag. + * Constructs a new ChallengeFlagHandled. * @param [properties] Properties to set */ - constructor(properties?: proto.GameEvent.IChallengeFlag); + constructor(properties?: proto.GameEvent.IChallengeFlagHandled); - /** ChallengeFlag byTeam. */ + /** ChallengeFlagHandled byTeam. */ public byTeam: proto.Team; + /** ChallengeFlagHandled accepted. */ + public accepted: boolean; + /** - * Creates a new ChallengeFlag instance using the specified properties. + * Creates a new ChallengeFlagHandled instance using the specified properties. * @param [properties] Properties to set - * @returns ChallengeFlag instance + * @returns ChallengeFlagHandled instance */ - public static create(properties?: proto.GameEvent.IChallengeFlag): proto.GameEvent.ChallengeFlag; + public static create(properties?: proto.GameEvent.IChallengeFlagHandled): proto.GameEvent.ChallengeFlagHandled; /** - * Encodes the specified ChallengeFlag message. Does not implicitly {@link proto.GameEvent.ChallengeFlag.verify|verify} messages. - * @param message ChallengeFlag message or plain object to encode + * Encodes the specified ChallengeFlagHandled message. Does not implicitly {@link proto.GameEvent.ChallengeFlagHandled.verify|verify} messages. + * @param message ChallengeFlagHandled message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encode(message: proto.GameEvent.IChallengeFlag, writer?: $protobuf.Writer): $protobuf.Writer; + public static encode(message: proto.GameEvent.IChallengeFlagHandled, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Encodes the specified ChallengeFlag message, length delimited. Does not implicitly {@link proto.GameEvent.ChallengeFlag.verify|verify} messages. - * @param message ChallengeFlag message or plain object to encode + * Encodes the specified ChallengeFlagHandled message, length delimited. Does not implicitly {@link proto.GameEvent.ChallengeFlagHandled.verify|verify} messages. + * @param message ChallengeFlagHandled message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encodeDelimited(message: proto.GameEvent.IChallengeFlag, writer?: $protobuf.Writer): $protobuf.Writer; + public static encodeDelimited(message: proto.GameEvent.IChallengeFlagHandled, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Decodes a ChallengeFlag message from the specified reader or buffer. + * Decodes a ChallengeFlagHandled message from the specified reader or buffer. * @param reader Reader or buffer to decode from * @param [length] Message length if known beforehand - * @returns ChallengeFlag + * @returns ChallengeFlagHandled * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.GameEvent.ChallengeFlag; + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.GameEvent.ChallengeFlagHandled; /** - * Decodes a ChallengeFlag message from the specified reader or buffer, length delimited. + * Decodes a ChallengeFlagHandled message from the specified reader or buffer, length delimited. * @param reader Reader or buffer to decode from - * @returns ChallengeFlag + * @returns ChallengeFlagHandled * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.GameEvent.ChallengeFlag; + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.GameEvent.ChallengeFlagHandled; /** - * Verifies a ChallengeFlag message. + * Verifies a ChallengeFlagHandled message. * @param message Plain object to verify * @returns `null` if valid, otherwise the reason why it is not */ public static verify(message: { [k: string]: any }): (string|null); /** - * Creates a ChallengeFlag message from a plain object. Also converts values to their respective internal types. + * Creates a ChallengeFlagHandled message from a plain object. Also converts values to their respective internal types. * @param object Plain object - * @returns ChallengeFlag + * @returns ChallengeFlagHandled */ - public static fromObject(object: { [k: string]: any }): proto.GameEvent.ChallengeFlag; + public static fromObject(object: { [k: string]: any }): proto.GameEvent.ChallengeFlagHandled; /** - * Creates a plain object from a ChallengeFlag message. Also converts values to other types if specified. - * @param message ChallengeFlag + * Creates a plain object from a ChallengeFlagHandled message. Also converts values to other types if specified. + * @param message ChallengeFlagHandled * @param [options] Conversion options * @returns Plain object */ - public static toObject(message: proto.GameEvent.ChallengeFlag, options?: $protobuf.IConversionOptions): { [k: string]: any }; + public static toObject(message: proto.GameEvent.ChallengeFlagHandled, options?: $protobuf.IConversionOptions): { [k: string]: any }; /** - * Converts this ChallengeFlag to JSON. + * Converts this ChallengeFlagHandled to JSON. * @returns JSON object */ public toJSON(): { [k: string]: any }; /** - * Gets the default type url for ChallengeFlag + * Gets the default type url for ChallengeFlagHandled * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns The default type url */ @@ -9615,6 +10038,9 @@ export namespace proto { /** PenaltyKickFailed location */ location?: (proto.IVector2|null); + + /** PenaltyKickFailed reason */ + reason?: (string|null); } /** Represents a PenaltyKickFailed. */ @@ -9632,6 +10058,9 @@ export namespace proto { /** PenaltyKickFailed location. */ public location?: (proto.IVector2|null); + /** PenaltyKickFailed reason. */ + public reason: string; + /** * Creates a new PenaltyKickFailed instance using the specified properties. * @param [properties] Properties to set @@ -9724,6 +10153,7 @@ export namespace proto { BOT_PUSHED_BOT = 24, BOT_HELD_BALL_DELIBERATELY = 26, BOT_TIPPED_OVER = 27, + BOT_DROPPED_PARTS = 47, ATTACKER_TOUCHED_BALL_IN_DEFENSE_AREA = 15, BOT_KICKED_BALL_TOO_FAST = 18, BOT_CRASH_UNIQUE = 22, @@ -9744,6 +10174,7 @@ export namespace proto { BOT_SUBSTITUTION = 37, TOO_MANY_ROBOTS = 38, CHALLENGE_FLAG = 44, + CHALLENGE_FLAG_HANDLED = 46, EMERGENCY_STOP = 45, UNSPORTING_BEHAVIOR_MINOR = 35, UNSPORTING_BEHAVIOR_MAJOR = 36 @@ -9771,886 +10202,580 @@ export namespace proto { class RobotId implements IRobotId { /** - * Constructs a new RobotId. - * @param [properties] Properties to set - */ - constructor(properties?: proto.IRobotId); - - /** RobotId id. */ - public id: number; - - /** RobotId team. */ - public team: proto.Team; - - /** - * Creates a new RobotId instance using the specified properties. - * @param [properties] Properties to set - * @returns RobotId instance - */ - public static create(properties?: proto.IRobotId): proto.RobotId; - - /** - * Encodes the specified RobotId message. Does not implicitly {@link proto.RobotId.verify|verify} messages. - * @param message RobotId message or plain object to encode - * @param [writer] Writer to encode to - * @returns Writer - */ - public static encode(message: proto.IRobotId, writer?: $protobuf.Writer): $protobuf.Writer; - - /** - * Encodes the specified RobotId message, length delimited. Does not implicitly {@link proto.RobotId.verify|verify} messages. - * @param message RobotId message or plain object to encode - * @param [writer] Writer to encode to - * @returns Writer - */ - public static encodeDelimited(message: proto.IRobotId, writer?: $protobuf.Writer): $protobuf.Writer; - - /** - * Decodes a RobotId message from the specified reader or buffer. - * @param reader Reader or buffer to decode from - * @param [length] Message length if known beforehand - * @returns RobotId - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.RobotId; - - /** - * Decodes a RobotId message from the specified reader or buffer, length delimited. - * @param reader Reader or buffer to decode from - * @returns RobotId - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.RobotId; - - /** - * Verifies a RobotId message. - * @param message Plain object to verify - * @returns `null` if valid, otherwise the reason why it is not - */ - public static verify(message: { [k: string]: any }): (string|null); - - /** - * Creates a RobotId message from a plain object. Also converts values to their respective internal types. - * @param object Plain object - * @returns RobotId - */ - public static fromObject(object: { [k: string]: any }): proto.RobotId; - - /** - * Creates a plain object from a RobotId message. Also converts values to other types if specified. - * @param message RobotId - * @param [options] Conversion options - * @returns Plain object - */ - public static toObject(message: proto.RobotId, options?: $protobuf.IConversionOptions): { [k: string]: any }; - - /** - * Converts this RobotId to JSON. - * @returns JSON object - */ - public toJSON(): { [k: string]: any }; - - /** - * Gets the default type url for RobotId - * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") - * @returns The default type url - */ - public static getTypeUrl(typeUrlPrefix?: string): string; - } - - /** Division enum. */ - enum Division { - DIV_UNKNOWN = 0, - DIV_A = 1, - DIV_B = 2 - } - - /** Properties of a Vector2. */ - interface IVector2 { - - /** Vector2 x */ - x: number; - - /** Vector2 y */ - y: number; - } - - /** Represents a Vector2. */ - class Vector2 implements IVector2 { - - /** - * Constructs a new Vector2. - * @param [properties] Properties to set - */ - constructor(properties?: proto.IVector2); - - /** Vector2 x. */ - public x: number; - - /** Vector2 y. */ - public y: number; - - /** - * Creates a new Vector2 instance using the specified properties. - * @param [properties] Properties to set - * @returns Vector2 instance - */ - public static create(properties?: proto.IVector2): proto.Vector2; - - /** - * Encodes the specified Vector2 message. Does not implicitly {@link proto.Vector2.verify|verify} messages. - * @param message Vector2 message or plain object to encode - * @param [writer] Writer to encode to - * @returns Writer - */ - public static encode(message: proto.IVector2, writer?: $protobuf.Writer): $protobuf.Writer; - - /** - * Encodes the specified Vector2 message, length delimited. Does not implicitly {@link proto.Vector2.verify|verify} messages. - * @param message Vector2 message or plain object to encode - * @param [writer] Writer to encode to - * @returns Writer - */ - public static encodeDelimited(message: proto.IVector2, writer?: $protobuf.Writer): $protobuf.Writer; - - /** - * Decodes a Vector2 message from the specified reader or buffer. - * @param reader Reader or buffer to decode from - * @param [length] Message length if known beforehand - * @returns Vector2 - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.Vector2; - - /** - * Decodes a Vector2 message from the specified reader or buffer, length delimited. - * @param reader Reader or buffer to decode from - * @returns Vector2 - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.Vector2; - - /** - * Verifies a Vector2 message. - * @param message Plain object to verify - * @returns `null` if valid, otherwise the reason why it is not - */ - public static verify(message: { [k: string]: any }): (string|null); - - /** - * Creates a Vector2 message from a plain object. Also converts values to their respective internal types. - * @param object Plain object - * @returns Vector2 - */ - public static fromObject(object: { [k: string]: any }): proto.Vector2; - - /** - * Creates a plain object from a Vector2 message. Also converts values to other types if specified. - * @param message Vector2 - * @param [options] Conversion options - * @returns Plain object - */ - public static toObject(message: proto.Vector2, options?: $protobuf.IConversionOptions): { [k: string]: any }; - - /** - * Converts this Vector2 to JSON. - * @returns JSON object - */ - public toJSON(): { [k: string]: any }; - - /** - * Gets the default type url for Vector2 - * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") - * @returns The default type url - */ - public static getTypeUrl(typeUrlPrefix?: string): string; - } - - /** Properties of a Vector3. */ - interface IVector3 { - - /** Vector3 x */ - x: number; - - /** Vector3 y */ - y: number; - - /** Vector3 z */ - z: number; - } - - /** Represents a Vector3. */ - class Vector3 implements IVector3 { - - /** - * Constructs a new Vector3. + * Constructs a new RobotId. * @param [properties] Properties to set */ - constructor(properties?: proto.IVector3); - - /** Vector3 x. */ - public x: number; + constructor(properties?: proto.IRobotId); - /** Vector3 y. */ - public y: number; + /** RobotId id. */ + public id: number; - /** Vector3 z. */ - public z: number; + /** RobotId team. */ + public team: proto.Team; /** - * Creates a new Vector3 instance using the specified properties. + * Creates a new RobotId instance using the specified properties. * @param [properties] Properties to set - * @returns Vector3 instance + * @returns RobotId instance */ - public static create(properties?: proto.IVector3): proto.Vector3; + public static create(properties?: proto.IRobotId): proto.RobotId; /** - * Encodes the specified Vector3 message. Does not implicitly {@link proto.Vector3.verify|verify} messages. - * @param message Vector3 message or plain object to encode + * Encodes the specified RobotId message. Does not implicitly {@link proto.RobotId.verify|verify} messages. + * @param message RobotId message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encode(message: proto.IVector3, writer?: $protobuf.Writer): $protobuf.Writer; + public static encode(message: proto.IRobotId, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Encodes the specified Vector3 message, length delimited. Does not implicitly {@link proto.Vector3.verify|verify} messages. - * @param message Vector3 message or plain object to encode + * Encodes the specified RobotId message, length delimited. Does not implicitly {@link proto.RobotId.verify|verify} messages. + * @param message RobotId message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encodeDelimited(message: proto.IVector3, writer?: $protobuf.Writer): $protobuf.Writer; + public static encodeDelimited(message: proto.IRobotId, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Decodes a Vector3 message from the specified reader or buffer. + * Decodes a RobotId message from the specified reader or buffer. * @param reader Reader or buffer to decode from * @param [length] Message length if known beforehand - * @returns Vector3 + * @returns RobotId * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.Vector3; + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.RobotId; /** - * Decodes a Vector3 message from the specified reader or buffer, length delimited. + * Decodes a RobotId message from the specified reader or buffer, length delimited. * @param reader Reader or buffer to decode from - * @returns Vector3 + * @returns RobotId * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.Vector3; + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.RobotId; /** - * Verifies a Vector3 message. + * Verifies a RobotId message. * @param message Plain object to verify * @returns `null` if valid, otherwise the reason why it is not */ public static verify(message: { [k: string]: any }): (string|null); /** - * Creates a Vector3 message from a plain object. Also converts values to their respective internal types. + * Creates a RobotId message from a plain object. Also converts values to their respective internal types. * @param object Plain object - * @returns Vector3 + * @returns RobotId */ - public static fromObject(object: { [k: string]: any }): proto.Vector3; + public static fromObject(object: { [k: string]: any }): proto.RobotId; /** - * Creates a plain object from a Vector3 message. Also converts values to other types if specified. - * @param message Vector3 + * Creates a plain object from a RobotId message. Also converts values to other types if specified. + * @param message RobotId * @param [options] Conversion options * @returns Plain object */ - public static toObject(message: proto.Vector3, options?: $protobuf.IConversionOptions): { [k: string]: any }; + public static toObject(message: proto.RobotId, options?: $protobuf.IConversionOptions): { [k: string]: any }; /** - * Converts this Vector3 to JSON. + * Converts this RobotId to JSON. * @returns JSON object */ public toJSON(): { [k: string]: any }; /** - * Gets the default type url for Vector3 + * Gets the default type url for RobotId * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns The default type url */ public static getTypeUrl(typeUrlPrefix?: string): string; } - /** RobotTeam enum. */ - enum RobotTeam { - YELLOW_TEAM = 0, - BLUE_TEAM = 1 - } - - /** RobotFeedbackSource enum. */ - enum RobotFeedbackSource { - SIMULATOR = 0, - BASESTATION = 1 + /** Division enum. */ + enum Division { + DIV_UNKNOWN = 0, + DIV_A = 1, + DIV_B = 2 } - /** Properties of a RobotFeedback. */ - interface IRobotFeedback { - - /** RobotFeedback id */ - id?: (number|null); - - /** RobotFeedback ballSensorSeesBall */ - ballSensorSeesBall?: (boolean|null); - - /** RobotFeedback ballPosition */ - ballPosition?: (number|null); - - /** RobotFeedback ballSensorIsWorking */ - ballSensorIsWorking?: (boolean|null); - - /** RobotFeedback dribblerSeesBall */ - dribblerSeesBall?: (boolean|null); - - /** RobotFeedback estimatedVelocityX */ - estimatedVelocityX?: (number|null); - - /** RobotFeedback estimatedVelocityY */ - estimatedVelocityY?: (number|null); - - /** RobotFeedback estimatedAngle */ - estimatedAngle?: (number|null); - - /** RobotFeedback xsensIsCalibrated */ - xsensIsCalibrated?: (boolean|null); - - /** RobotFeedback capacitorIsCharged */ - capacitorIsCharged?: (boolean|null); - - /** RobotFeedback wheelsLocked */ - wheelsLocked?: (number|null); - - /** RobotFeedback wheelsBraking */ - wheelsBraking?: (number|null); + /** Properties of a Vector2. */ + interface IVector2 { - /** RobotFeedback batteryLevel */ - batteryLevel?: (number|null); + /** Vector2 x */ + x: number; - /** RobotFeedback signalStrength */ - signalStrength?: (number|null); + /** Vector2 y */ + y: number; } - /** Represents a RobotFeedback. */ - class RobotFeedback implements IRobotFeedback { + /** Represents a Vector2. */ + class Vector2 implements IVector2 { /** - * Constructs a new RobotFeedback. + * Constructs a new Vector2. * @param [properties] Properties to set */ - constructor(properties?: proto.IRobotFeedback); - - /** RobotFeedback id. */ - public id: number; - - /** RobotFeedback ballSensorSeesBall. */ - public ballSensorSeesBall: boolean; - - /** RobotFeedback ballPosition. */ - public ballPosition: number; - - /** RobotFeedback ballSensorIsWorking. */ - public ballSensorIsWorking: boolean; - - /** RobotFeedback dribblerSeesBall. */ - public dribblerSeesBall: boolean; - - /** RobotFeedback estimatedVelocityX. */ - public estimatedVelocityX: number; - - /** RobotFeedback estimatedVelocityY. */ - public estimatedVelocityY: number; - - /** RobotFeedback estimatedAngle. */ - public estimatedAngle: number; - - /** RobotFeedback xsensIsCalibrated. */ - public xsensIsCalibrated: boolean; - - /** RobotFeedback capacitorIsCharged. */ - public capacitorIsCharged: boolean; - - /** RobotFeedback wheelsLocked. */ - public wheelsLocked: number; - - /** RobotFeedback wheelsBraking. */ - public wheelsBraking: number; + constructor(properties?: proto.IVector2); - /** RobotFeedback batteryLevel. */ - public batteryLevel: number; + /** Vector2 x. */ + public x: number; - /** RobotFeedback signalStrength. */ - public signalStrength: number; + /** Vector2 y. */ + public y: number; /** - * Creates a new RobotFeedback instance using the specified properties. + * Creates a new Vector2 instance using the specified properties. * @param [properties] Properties to set - * @returns RobotFeedback instance + * @returns Vector2 instance */ - public static create(properties?: proto.IRobotFeedback): proto.RobotFeedback; + public static create(properties?: proto.IVector2): proto.Vector2; /** - * Encodes the specified RobotFeedback message. Does not implicitly {@link proto.RobotFeedback.verify|verify} messages. - * @param message RobotFeedback message or plain object to encode + * Encodes the specified Vector2 message. Does not implicitly {@link proto.Vector2.verify|verify} messages. + * @param message Vector2 message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encode(message: proto.IRobotFeedback, writer?: $protobuf.Writer): $protobuf.Writer; + public static encode(message: proto.IVector2, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Encodes the specified RobotFeedback message, length delimited. Does not implicitly {@link proto.RobotFeedback.verify|verify} messages. - * @param message RobotFeedback message or plain object to encode + * Encodes the specified Vector2 message, length delimited. Does not implicitly {@link proto.Vector2.verify|verify} messages. + * @param message Vector2 message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encodeDelimited(message: proto.IRobotFeedback, writer?: $protobuf.Writer): $protobuf.Writer; + public static encodeDelimited(message: proto.IVector2, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Decodes a RobotFeedback message from the specified reader or buffer. + * Decodes a Vector2 message from the specified reader or buffer. * @param reader Reader or buffer to decode from * @param [length] Message length if known beforehand - * @returns RobotFeedback + * @returns Vector2 * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.RobotFeedback; + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.Vector2; /** - * Decodes a RobotFeedback message from the specified reader or buffer, length delimited. + * Decodes a Vector2 message from the specified reader or buffer, length delimited. * @param reader Reader or buffer to decode from - * @returns RobotFeedback + * @returns Vector2 * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.RobotFeedback; + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.Vector2; /** - * Verifies a RobotFeedback message. + * Verifies a Vector2 message. * @param message Plain object to verify * @returns `null` if valid, otherwise the reason why it is not */ public static verify(message: { [k: string]: any }): (string|null); /** - * Creates a RobotFeedback message from a plain object. Also converts values to their respective internal types. + * Creates a Vector2 message from a plain object. Also converts values to their respective internal types. * @param object Plain object - * @returns RobotFeedback + * @returns Vector2 */ - public static fromObject(object: { [k: string]: any }): proto.RobotFeedback; + public static fromObject(object: { [k: string]: any }): proto.Vector2; /** - * Creates a plain object from a RobotFeedback message. Also converts values to other types if specified. - * @param message RobotFeedback + * Creates a plain object from a Vector2 message. Also converts values to other types if specified. + * @param message Vector2 * @param [options] Conversion options * @returns Plain object */ - public static toObject(message: proto.RobotFeedback, options?: $protobuf.IConversionOptions): { [k: string]: any }; + public static toObject(message: proto.Vector2, options?: $protobuf.IConversionOptions): { [k: string]: any }; /** - * Converts this RobotFeedback to JSON. + * Converts this Vector2 to JSON. * @returns JSON object */ public toJSON(): { [k: string]: any }; /** - * Gets the default type url for RobotFeedback + * Gets the default type url for Vector2 * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns The default type url */ public static getTypeUrl(typeUrlPrefix?: string): string; } - /** Properties of a RobotsFeedback. */ - interface IRobotsFeedback { + /** Properties of a Vector3. */ + interface IVector3 { - /** RobotsFeedback team */ - team?: (proto.RobotTeam|null); + /** Vector3 x */ + x: number; - /** RobotsFeedback source */ - source?: (proto.RobotFeedbackSource|null); + /** Vector3 y */ + y: number; - /** RobotsFeedback robotsFeedback */ - robotsFeedback?: (proto.IRobotFeedback[]|null); + /** Vector3 z */ + z: number; } - /** Represents a RobotsFeedback. */ - class RobotsFeedback implements IRobotsFeedback { + /** Represents a Vector3. */ + class Vector3 implements IVector3 { /** - * Constructs a new RobotsFeedback. + * Constructs a new Vector3. * @param [properties] Properties to set */ - constructor(properties?: proto.IRobotsFeedback); + constructor(properties?: proto.IVector3); - /** RobotsFeedback team. */ - public team: proto.RobotTeam; + /** Vector3 x. */ + public x: number; - /** RobotsFeedback source. */ - public source: proto.RobotFeedbackSource; + /** Vector3 y. */ + public y: number; - /** RobotsFeedback robotsFeedback. */ - public robotsFeedback: proto.IRobotFeedback[]; + /** Vector3 z. */ + public z: number; /** - * Creates a new RobotsFeedback instance using the specified properties. + * Creates a new Vector3 instance using the specified properties. * @param [properties] Properties to set - * @returns RobotsFeedback instance + * @returns Vector3 instance */ - public static create(properties?: proto.IRobotsFeedback): proto.RobotsFeedback; + public static create(properties?: proto.IVector3): proto.Vector3; /** - * Encodes the specified RobotsFeedback message. Does not implicitly {@link proto.RobotsFeedback.verify|verify} messages. - * @param message RobotsFeedback message or plain object to encode + * Encodes the specified Vector3 message. Does not implicitly {@link proto.Vector3.verify|verify} messages. + * @param message Vector3 message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encode(message: proto.IRobotsFeedback, writer?: $protobuf.Writer): $protobuf.Writer; + public static encode(message: proto.IVector3, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Encodes the specified RobotsFeedback message, length delimited. Does not implicitly {@link proto.RobotsFeedback.verify|verify} messages. - * @param message RobotsFeedback message or plain object to encode + * Encodes the specified Vector3 message, length delimited. Does not implicitly {@link proto.Vector3.verify|verify} messages. + * @param message Vector3 message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encodeDelimited(message: proto.IRobotsFeedback, writer?: $protobuf.Writer): $protobuf.Writer; + public static encodeDelimited(message: proto.IVector3, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Decodes a RobotsFeedback message from the specified reader or buffer. + * Decodes a Vector3 message from the specified reader or buffer. * @param reader Reader or buffer to decode from * @param [length] Message length if known beforehand - * @returns RobotsFeedback + * @returns Vector3 * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.RobotsFeedback; + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.Vector3; /** - * Decodes a RobotsFeedback message from the specified reader or buffer, length delimited. + * Decodes a Vector3 message from the specified reader or buffer, length delimited. * @param reader Reader or buffer to decode from - * @returns RobotsFeedback + * @returns Vector3 * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.RobotsFeedback; + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.Vector3; /** - * Verifies a RobotsFeedback message. + * Verifies a Vector3 message. * @param message Plain object to verify * @returns `null` if valid, otherwise the reason why it is not */ public static verify(message: { [k: string]: any }): (string|null); /** - * Creates a RobotsFeedback message from a plain object. Also converts values to their respective internal types. + * Creates a Vector3 message from a plain object. Also converts values to their respective internal types. * @param object Plain object - * @returns RobotsFeedback + * @returns Vector3 */ - public static fromObject(object: { [k: string]: any }): proto.RobotsFeedback; + public static fromObject(object: { [k: string]: any }): proto.Vector3; /** - * Creates a plain object from a RobotsFeedback message. Also converts values to other types if specified. - * @param message RobotsFeedback + * Creates a plain object from a Vector3 message. Also converts values to other types if specified. + * @param message Vector3 * @param [options] Conversion options * @returns Plain object */ - public static toObject(message: proto.RobotsFeedback, options?: $protobuf.IConversionOptions): { [k: string]: any }; + public static toObject(message: proto.Vector3, options?: $protobuf.IConversionOptions): { [k: string]: any }; /** - * Converts this RobotsFeedback to JSON. + * Converts this Vector3 to JSON. * @returns JSON object */ public toJSON(): { [k: string]: any }; /** - * Gets the default type url for RobotsFeedback + * Gets the default type url for Vector3 * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns The default type url */ public static getTypeUrl(typeUrlPrefix?: string): string; } - /** Properties of a RobotCommand. */ - interface IRobotCommand { - - /** RobotCommand id */ - id?: (number|null); - - /** RobotCommand velocityX */ - velocityX?: (number|null); + /** RobotTeam enum. */ + enum RobotTeam { + YELLOW_TEAM = 0, + BLUE_TEAM = 1 + } - /** RobotCommand velocityY */ - velocityY?: (number|null); + /** RobotFeedbackSource enum. */ + enum RobotFeedbackSource { + SIMULATOR = 0, + BASESTATION = 1 + } - /** RobotCommand angle */ - angle?: (number|null); + /** Properties of a RobotFeedback. */ + interface IRobotFeedback { - /** RobotCommand angularVelocity */ - angularVelocity?: (number|null); + /** RobotFeedback id */ + id?: (number|null); - /** RobotCommand useAngularVelocity */ - useAngularVelocity?: (boolean|null); + /** RobotFeedback ballSensorSeesBall */ + ballSensorSeesBall?: (boolean|null); - /** RobotCommand cameraAngleOfRobot */ - cameraAngleOfRobot?: (number|null); + /** RobotFeedback ballSensorIsWorking */ + ballSensorIsWorking?: (boolean|null); - /** RobotCommand cameraAngleOfRobotIsSet */ - cameraAngleOfRobotIsSet?: (boolean|null); + /** RobotFeedback dribblerSeesBall */ + dribblerSeesBall?: (boolean|null); - /** RobotCommand kickSpeed */ - kickSpeed?: (number|null); + /** RobotFeedback estimatedVelocityX */ + estimatedVelocityX?: (number|null); - /** RobotCommand waitForBall */ - waitForBall?: (boolean|null); + /** RobotFeedback estimatedVelocityY */ + estimatedVelocityY?: (number|null); - /** RobotCommand kickAtAngle */ - kickAtAngle?: (boolean|null); + /** RobotFeedback estimatedYaw */ + estimatedYaw?: (number|null); - /** RobotCommand kickType */ - kickType?: (proto.RobotCommand.KickType|null); + /** RobotFeedback xsensIsCalibrated */ + xsensIsCalibrated?: (boolean|null); - /** RobotCommand dribblerSpeed */ - dribblerSpeed?: (number|null); + /** RobotFeedback capacitorIsCharged */ + capacitorIsCharged?: (boolean|null); - /** RobotCommand ignorePacket */ - ignorePacket?: (boolean|null); + /** RobotFeedback batteryLevel */ + batteryLevel?: (number|null); } - /** Represents a RobotCommand. */ - class RobotCommand implements IRobotCommand { + /** Represents a RobotFeedback. */ + class RobotFeedback implements IRobotFeedback { /** - * Constructs a new RobotCommand. + * Constructs a new RobotFeedback. * @param [properties] Properties to set */ - constructor(properties?: proto.IRobotCommand); + constructor(properties?: proto.IRobotFeedback); - /** RobotCommand id. */ + /** RobotFeedback id. */ public id: number; - /** RobotCommand velocityX. */ - public velocityX: number; - - /** RobotCommand velocityY. */ - public velocityY: number; - - /** RobotCommand angle. */ - public angle: number; - - /** RobotCommand angularVelocity. */ - public angularVelocity: number; - - /** RobotCommand useAngularVelocity. */ - public useAngularVelocity: boolean; + /** RobotFeedback ballSensorSeesBall. */ + public ballSensorSeesBall: boolean; - /** RobotCommand cameraAngleOfRobot. */ - public cameraAngleOfRobot: number; + /** RobotFeedback ballSensorIsWorking. */ + public ballSensorIsWorking: boolean; - /** RobotCommand cameraAngleOfRobotIsSet. */ - public cameraAngleOfRobotIsSet: boolean; + /** RobotFeedback dribblerSeesBall. */ + public dribblerSeesBall: boolean; - /** RobotCommand kickSpeed. */ - public kickSpeed: number; + /** RobotFeedback estimatedVelocityX. */ + public estimatedVelocityX: number; - /** RobotCommand waitForBall. */ - public waitForBall: boolean; + /** RobotFeedback estimatedVelocityY. */ + public estimatedVelocityY: number; - /** RobotCommand kickAtAngle. */ - public kickAtAngle: boolean; + /** RobotFeedback estimatedYaw. */ + public estimatedYaw: number; - /** RobotCommand kickType. */ - public kickType: proto.RobotCommand.KickType; + /** RobotFeedback xsensIsCalibrated. */ + public xsensIsCalibrated: boolean; - /** RobotCommand dribblerSpeed. */ - public dribblerSpeed: number; + /** RobotFeedback capacitorIsCharged. */ + public capacitorIsCharged: boolean; - /** RobotCommand ignorePacket. */ - public ignorePacket: boolean; + /** RobotFeedback batteryLevel. */ + public batteryLevel: number; /** - * Creates a new RobotCommand instance using the specified properties. + * Creates a new RobotFeedback instance using the specified properties. * @param [properties] Properties to set - * @returns RobotCommand instance + * @returns RobotFeedback instance */ - public static create(properties?: proto.IRobotCommand): proto.RobotCommand; + public static create(properties?: proto.IRobotFeedback): proto.RobotFeedback; /** - * Encodes the specified RobotCommand message. Does not implicitly {@link proto.RobotCommand.verify|verify} messages. - * @param message RobotCommand message or plain object to encode + * Encodes the specified RobotFeedback message. Does not implicitly {@link proto.RobotFeedback.verify|verify} messages. + * @param message RobotFeedback message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encode(message: proto.IRobotCommand, writer?: $protobuf.Writer): $protobuf.Writer; + public static encode(message: proto.IRobotFeedback, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Encodes the specified RobotCommand message, length delimited. Does not implicitly {@link proto.RobotCommand.verify|verify} messages. - * @param message RobotCommand message or plain object to encode + * Encodes the specified RobotFeedback message, length delimited. Does not implicitly {@link proto.RobotFeedback.verify|verify} messages. + * @param message RobotFeedback message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encodeDelimited(message: proto.IRobotCommand, writer?: $protobuf.Writer): $protobuf.Writer; + public static encodeDelimited(message: proto.IRobotFeedback, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Decodes a RobotCommand message from the specified reader or buffer. + * Decodes a RobotFeedback message from the specified reader or buffer. * @param reader Reader or buffer to decode from * @param [length] Message length if known beforehand - * @returns RobotCommand + * @returns RobotFeedback * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.RobotCommand; + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.RobotFeedback; /** - * Decodes a RobotCommand message from the specified reader or buffer, length delimited. + * Decodes a RobotFeedback message from the specified reader or buffer, length delimited. * @param reader Reader or buffer to decode from - * @returns RobotCommand + * @returns RobotFeedback * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.RobotCommand; + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.RobotFeedback; /** - * Verifies a RobotCommand message. + * Verifies a RobotFeedback message. * @param message Plain object to verify * @returns `null` if valid, otherwise the reason why it is not */ public static verify(message: { [k: string]: any }): (string|null); /** - * Creates a RobotCommand message from a plain object. Also converts values to their respective internal types. + * Creates a RobotFeedback message from a plain object. Also converts values to their respective internal types. * @param object Plain object - * @returns RobotCommand + * @returns RobotFeedback */ - public static fromObject(object: { [k: string]: any }): proto.RobotCommand; + public static fromObject(object: { [k: string]: any }): proto.RobotFeedback; /** - * Creates a plain object from a RobotCommand message. Also converts values to other types if specified. - * @param message RobotCommand + * Creates a plain object from a RobotFeedback message. Also converts values to other types if specified. + * @param message RobotFeedback * @param [options] Conversion options * @returns Plain object */ - public static toObject(message: proto.RobotCommand, options?: $protobuf.IConversionOptions): { [k: string]: any }; + public static toObject(message: proto.RobotFeedback, options?: $protobuf.IConversionOptions): { [k: string]: any }; /** - * Converts this RobotCommand to JSON. + * Converts this RobotFeedback to JSON. * @returns JSON object */ public toJSON(): { [k: string]: any }; /** - * Gets the default type url for RobotCommand + * Gets the default type url for RobotFeedback * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns The default type url */ public static getTypeUrl(typeUrlPrefix?: string): string; } - namespace RobotCommand { + /** Properties of a RobotsFeedback. */ + interface IRobotsFeedback { - /** KickType enum. */ - enum KickType { - NO_KICK = 0, - KICK = 1, - CHIP = 2 - } - } + /** RobotsFeedback team */ + team?: (proto.RobotTeam|null); - /** Properties of a RobotCommands. */ - interface IRobotCommands { + /** RobotsFeedback source */ + source?: (proto.RobotFeedbackSource|null); - /** RobotCommands robotCommands */ - robotCommands?: (proto.IRobotCommand[]|null); + /** RobotsFeedback robotsFeedback */ + robotsFeedback?: (proto.IRobotFeedback[]|null); } - /** Represents a RobotCommands. */ - class RobotCommands implements IRobotCommands { + /** Represents a RobotsFeedback. */ + class RobotsFeedback implements IRobotsFeedback { /** - * Constructs a new RobotCommands. + * Constructs a new RobotsFeedback. * @param [properties] Properties to set */ - constructor(properties?: proto.IRobotCommands); + constructor(properties?: proto.IRobotsFeedback); - /** RobotCommands robotCommands. */ - public robotCommands: proto.IRobotCommand[]; + /** RobotsFeedback team. */ + public team: proto.RobotTeam; + + /** RobotsFeedback source. */ + public source: proto.RobotFeedbackSource; + + /** RobotsFeedback robotsFeedback. */ + public robotsFeedback: proto.IRobotFeedback[]; /** - * Creates a new RobotCommands instance using the specified properties. + * Creates a new RobotsFeedback instance using the specified properties. * @param [properties] Properties to set - * @returns RobotCommands instance + * @returns RobotsFeedback instance */ - public static create(properties?: proto.IRobotCommands): proto.RobotCommands; + public static create(properties?: proto.IRobotsFeedback): proto.RobotsFeedback; /** - * Encodes the specified RobotCommands message. Does not implicitly {@link proto.RobotCommands.verify|verify} messages. - * @param message RobotCommands message or plain object to encode + * Encodes the specified RobotsFeedback message. Does not implicitly {@link proto.RobotsFeedback.verify|verify} messages. + * @param message RobotsFeedback message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encode(message: proto.IRobotCommands, writer?: $protobuf.Writer): $protobuf.Writer; + public static encode(message: proto.IRobotsFeedback, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Encodes the specified RobotCommands message, length delimited. Does not implicitly {@link proto.RobotCommands.verify|verify} messages. - * @param message RobotCommands message or plain object to encode + * Encodes the specified RobotsFeedback message, length delimited. Does not implicitly {@link proto.RobotsFeedback.verify|verify} messages. + * @param message RobotsFeedback message or plain object to encode * @param [writer] Writer to encode to * @returns Writer */ - public static encodeDelimited(message: proto.IRobotCommands, writer?: $protobuf.Writer): $protobuf.Writer; + public static encodeDelimited(message: proto.IRobotsFeedback, writer?: $protobuf.Writer): $protobuf.Writer; /** - * Decodes a RobotCommands message from the specified reader or buffer. + * Decodes a RobotsFeedback message from the specified reader or buffer. * @param reader Reader or buffer to decode from * @param [length] Message length if known beforehand - * @returns RobotCommands + * @returns RobotsFeedback * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.RobotCommands; + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.RobotsFeedback; /** - * Decodes a RobotCommands message from the specified reader or buffer, length delimited. + * Decodes a RobotsFeedback message from the specified reader or buffer, length delimited. * @param reader Reader or buffer to decode from - * @returns RobotCommands + * @returns RobotsFeedback * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.RobotCommands; + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.RobotsFeedback; /** - * Verifies a RobotCommands message. + * Verifies a RobotsFeedback message. * @param message Plain object to verify * @returns `null` if valid, otherwise the reason why it is not */ public static verify(message: { [k: string]: any }): (string|null); /** - * Creates a RobotCommands message from a plain object. Also converts values to their respective internal types. + * Creates a RobotsFeedback message from a plain object. Also converts values to their respective internal types. * @param object Plain object - * @returns RobotCommands + * @returns RobotsFeedback */ - public static fromObject(object: { [k: string]: any }): proto.RobotCommands; + public static fromObject(object: { [k: string]: any }): proto.RobotsFeedback; /** - * Creates a plain object from a RobotCommands message. Also converts values to other types if specified. - * @param message RobotCommands + * Creates a plain object from a RobotsFeedback message. Also converts values to other types if specified. + * @param message RobotsFeedback * @param [options] Conversion options * @returns Plain object */ - public static toObject(message: proto.RobotCommands, options?: $protobuf.IConversionOptions): { [k: string]: any }; + public static toObject(message: proto.RobotsFeedback, options?: $protobuf.IConversionOptions): { [k: string]: any }; /** - * Converts this RobotCommands to JSON. + * Converts this RobotsFeedback to JSON. * @returns JSON object */ public toJSON(): { [k: string]: any }; /** - * Gets the default type url for RobotCommands + * Gets the default type url for RobotsFeedback * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns The default type url */ @@ -10905,149 +11030,431 @@ export namespace proto { */ public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.RoboCup2014Legacy.Geometry.SSL_GeometryData; - /** - * Verifies a SSL_GeometryData message. - * @param message Plain object to verify - * @returns `null` if valid, otherwise the reason why it is not - */ - public static verify(message: { [k: string]: any }): (string|null); + /** + * Verifies a SSL_GeometryData message. + * @param message Plain object to verify + * @returns `null` if valid, otherwise the reason why it is not + */ + public static verify(message: { [k: string]: any }): (string|null); + + /** + * Creates a SSL_GeometryData message from a plain object. Also converts values to their respective internal types. + * @param object Plain object + * @returns SSL_GeometryData + */ + public static fromObject(object: { [k: string]: any }): proto.RoboCup2014Legacy.Geometry.SSL_GeometryData; + + /** + * Creates a plain object from a SSL_GeometryData message. Also converts values to other types if specified. + * @param message SSL_GeometryData + * @param [options] Conversion options + * @returns Plain object + */ + public static toObject(message: proto.RoboCup2014Legacy.Geometry.SSL_GeometryData, options?: $protobuf.IConversionOptions): { [k: string]: any }; + + /** + * Converts this SSL_GeometryData to JSON. + * @returns JSON object + */ + public toJSON(): { [k: string]: any }; + + /** + * Gets the default type url for SSL_GeometryData + * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns The default type url + */ + public static getTypeUrl(typeUrlPrefix?: string): string; + } + } + + /** Namespace Wrapper. */ + namespace Wrapper { + + /** Properties of a SSL_WrapperPacket. */ + interface ISSL_WrapperPacket { + + /** SSL_WrapperPacket detection */ + detection?: (proto.ISSL_DetectionFrame|null); + + /** SSL_WrapperPacket geometry */ + geometry?: (proto.RoboCup2014Legacy.Geometry.ISSL_GeometryData|null); + } + + /** Represents a SSL_WrapperPacket. */ + class SSL_WrapperPacket implements ISSL_WrapperPacket { + + /** + * Constructs a new SSL_WrapperPacket. + * @param [properties] Properties to set + */ + constructor(properties?: proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket); + + /** SSL_WrapperPacket detection. */ + public detection?: (proto.ISSL_DetectionFrame|null); + + /** SSL_WrapperPacket geometry. */ + public geometry?: (proto.RoboCup2014Legacy.Geometry.ISSL_GeometryData|null); + + /** + * Creates a new SSL_WrapperPacket instance using the specified properties. + * @param [properties] Properties to set + * @returns SSL_WrapperPacket instance + */ + public static create(properties?: proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket): proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket; + + /** + * Encodes the specified SSL_WrapperPacket message. Does not implicitly {@link proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket.verify|verify} messages. + * @param message SSL_WrapperPacket message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encode(message: proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Encodes the specified SSL_WrapperPacket message, length delimited. Does not implicitly {@link proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket.verify|verify} messages. + * @param message SSL_WrapperPacket message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encodeDelimited(message: proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Decodes a SSL_WrapperPacket message from the specified reader or buffer. + * @param reader Reader or buffer to decode from + * @param [length] Message length if known beforehand + * @returns SSL_WrapperPacket + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket; + + /** + * Decodes a SSL_WrapperPacket message from the specified reader or buffer, length delimited. + * @param reader Reader or buffer to decode from + * @returns SSL_WrapperPacket + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket; + + /** + * Verifies a SSL_WrapperPacket message. + * @param message Plain object to verify + * @returns `null` if valid, otherwise the reason why it is not + */ + public static verify(message: { [k: string]: any }): (string|null); + + /** + * Creates a SSL_WrapperPacket message from a plain object. Also converts values to their respective internal types. + * @param object Plain object + * @returns SSL_WrapperPacket + */ + public static fromObject(object: { [k: string]: any }): proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket; + + /** + * Creates a plain object from a SSL_WrapperPacket message. Also converts values to other types if specified. + * @param message SSL_WrapperPacket + * @param [options] Conversion options + * @returns Plain object + */ + public static toObject(message: proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket, options?: $protobuf.IConversionOptions): { [k: string]: any }; + + /** + * Converts this SSL_WrapperPacket to JSON. + * @returns JSON object + */ + public toJSON(): { [k: string]: any }; + + /** + * Gets the default type url for SSL_WrapperPacket + * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns The default type url + */ + public static getTypeUrl(typeUrlPrefix?: string): string; + } + } + } + + /** Properties of a RobotCommand. */ + interface IRobotCommand { + + /** RobotCommand id */ + id?: (number|null); + + /** RobotCommand velocityX */ + velocityX?: (number|null); + + /** RobotCommand velocityY */ + velocityY?: (number|null); + + /** RobotCommand yaw */ + yaw?: (number|null); + + /** RobotCommand angularVelocity */ + angularVelocity?: (number|null); + + /** RobotCommand useAngularVelocity */ + useAngularVelocity?: (boolean|null); + + /** RobotCommand cameraYawOfRobot */ + cameraYawOfRobot?: (number|null); + + /** RobotCommand cameraYawOfRobotIsSet */ + cameraYawOfRobotIsSet?: (boolean|null); + + /** RobotCommand kickSpeed */ + kickSpeed?: (number|null); + + /** RobotCommand waitForBall */ + waitForBall?: (boolean|null); + + /** RobotCommand kickAtYaw */ + kickAtYaw?: (boolean|null); + + /** RobotCommand kickType */ + kickType?: (proto.RobotCommand.KickType|null); + + /** RobotCommand dribblerOn */ + dribblerOn?: (boolean|null); + + /** RobotCommand wheelsOff */ + wheelsOff?: (boolean|null); + } + + /** Represents a RobotCommand. */ + class RobotCommand implements IRobotCommand { + + /** + * Constructs a new RobotCommand. + * @param [properties] Properties to set + */ + constructor(properties?: proto.IRobotCommand); + + /** RobotCommand id. */ + public id: number; + + /** RobotCommand velocityX. */ + public velocityX: number; + + /** RobotCommand velocityY. */ + public velocityY: number; + + /** RobotCommand yaw. */ + public yaw: number; + + /** RobotCommand angularVelocity. */ + public angularVelocity: number; + + /** RobotCommand useAngularVelocity. */ + public useAngularVelocity: boolean; + + /** RobotCommand cameraYawOfRobot. */ + public cameraYawOfRobot: number; + + /** RobotCommand cameraYawOfRobotIsSet. */ + public cameraYawOfRobotIsSet: boolean; + + /** RobotCommand kickSpeed. */ + public kickSpeed: number; + + /** RobotCommand waitForBall. */ + public waitForBall: boolean; + + /** RobotCommand kickAtYaw. */ + public kickAtYaw: boolean; + + /** RobotCommand kickType. */ + public kickType: proto.RobotCommand.KickType; + + /** RobotCommand dribblerOn. */ + public dribblerOn: boolean; + + /** RobotCommand wheelsOff. */ + public wheelsOff: boolean; + + /** + * Creates a new RobotCommand instance using the specified properties. + * @param [properties] Properties to set + * @returns RobotCommand instance + */ + public static create(properties?: proto.IRobotCommand): proto.RobotCommand; + + /** + * Encodes the specified RobotCommand message. Does not implicitly {@link proto.RobotCommand.verify|verify} messages. + * @param message RobotCommand message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encode(message: proto.IRobotCommand, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Encodes the specified RobotCommand message, length delimited. Does not implicitly {@link proto.RobotCommand.verify|verify} messages. + * @param message RobotCommand message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encodeDelimited(message: proto.IRobotCommand, writer?: $protobuf.Writer): $protobuf.Writer; + + /** + * Decodes a RobotCommand message from the specified reader or buffer. + * @param reader Reader or buffer to decode from + * @param [length] Message length if known beforehand + * @returns RobotCommand + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.RobotCommand; + + /** + * Decodes a RobotCommand message from the specified reader or buffer, length delimited. + * @param reader Reader or buffer to decode from + * @returns RobotCommand + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.RobotCommand; - /** - * Creates a SSL_GeometryData message from a plain object. Also converts values to their respective internal types. - * @param object Plain object - * @returns SSL_GeometryData - */ - public static fromObject(object: { [k: string]: any }): proto.RoboCup2014Legacy.Geometry.SSL_GeometryData; + /** + * Verifies a RobotCommand message. + * @param message Plain object to verify + * @returns `null` if valid, otherwise the reason why it is not + */ + public static verify(message: { [k: string]: any }): (string|null); - /** - * Creates a plain object from a SSL_GeometryData message. Also converts values to other types if specified. - * @param message SSL_GeometryData - * @param [options] Conversion options - * @returns Plain object - */ - public static toObject(message: proto.RoboCup2014Legacy.Geometry.SSL_GeometryData, options?: $protobuf.IConversionOptions): { [k: string]: any }; + /** + * Creates a RobotCommand message from a plain object. Also converts values to their respective internal types. + * @param object Plain object + * @returns RobotCommand + */ + public static fromObject(object: { [k: string]: any }): proto.RobotCommand; - /** - * Converts this SSL_GeometryData to JSON. - * @returns JSON object - */ - public toJSON(): { [k: string]: any }; + /** + * Creates a plain object from a RobotCommand message. Also converts values to other types if specified. + * @param message RobotCommand + * @param [options] Conversion options + * @returns Plain object + */ + public static toObject(message: proto.RobotCommand, options?: $protobuf.IConversionOptions): { [k: string]: any }; - /** - * Gets the default type url for SSL_GeometryData - * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") - * @returns The default type url - */ - public static getTypeUrl(typeUrlPrefix?: string): string; - } - } + /** + * Converts this RobotCommand to JSON. + * @returns JSON object + */ + public toJSON(): { [k: string]: any }; - /** Namespace Wrapper. */ - namespace Wrapper { + /** + * Gets the default type url for RobotCommand + * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns The default type url + */ + public static getTypeUrl(typeUrlPrefix?: string): string; + } - /** Properties of a SSL_WrapperPacket. */ - interface ISSL_WrapperPacket { + namespace RobotCommand { - /** SSL_WrapperPacket detection */ - detection?: (proto.ISSL_DetectionFrame|null); + /** KickType enum. */ + enum KickType { + NO_KICK = 0, + KICK = 1, + CHIP = 2 + } + } - /** SSL_WrapperPacket geometry */ - geometry?: (proto.RoboCup2014Legacy.Geometry.ISSL_GeometryData|null); - } + /** Properties of a RobotCommands. */ + interface IRobotCommands { - /** Represents a SSL_WrapperPacket. */ - class SSL_WrapperPacket implements ISSL_WrapperPacket { + /** RobotCommands robotCommands */ + robotCommands?: (proto.IRobotCommand[]|null); + } - /** - * Constructs a new SSL_WrapperPacket. - * @param [properties] Properties to set - */ - constructor(properties?: proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket); + /** Represents a RobotCommands. */ + class RobotCommands implements IRobotCommands { - /** SSL_WrapperPacket detection. */ - public detection?: (proto.ISSL_DetectionFrame|null); + /** + * Constructs a new RobotCommands. + * @param [properties] Properties to set + */ + constructor(properties?: proto.IRobotCommands); - /** SSL_WrapperPacket geometry. */ - public geometry?: (proto.RoboCup2014Legacy.Geometry.ISSL_GeometryData|null); + /** RobotCommands robotCommands. */ + public robotCommands: proto.IRobotCommand[]; - /** - * Creates a new SSL_WrapperPacket instance using the specified properties. - * @param [properties] Properties to set - * @returns SSL_WrapperPacket instance - */ - public static create(properties?: proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket): proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket; + /** + * Creates a new RobotCommands instance using the specified properties. + * @param [properties] Properties to set + * @returns RobotCommands instance + */ + public static create(properties?: proto.IRobotCommands): proto.RobotCommands; - /** - * Encodes the specified SSL_WrapperPacket message. Does not implicitly {@link proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket.verify|verify} messages. - * @param message SSL_WrapperPacket message or plain object to encode - * @param [writer] Writer to encode to - * @returns Writer - */ - public static encode(message: proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket, writer?: $protobuf.Writer): $protobuf.Writer; + /** + * Encodes the specified RobotCommands message. Does not implicitly {@link proto.RobotCommands.verify|verify} messages. + * @param message RobotCommands message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encode(message: proto.IRobotCommands, writer?: $protobuf.Writer): $protobuf.Writer; - /** - * Encodes the specified SSL_WrapperPacket message, length delimited. Does not implicitly {@link proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket.verify|verify} messages. - * @param message SSL_WrapperPacket message or plain object to encode - * @param [writer] Writer to encode to - * @returns Writer - */ - public static encodeDelimited(message: proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket, writer?: $protobuf.Writer): $protobuf.Writer; + /** + * Encodes the specified RobotCommands message, length delimited. Does not implicitly {@link proto.RobotCommands.verify|verify} messages. + * @param message RobotCommands message or plain object to encode + * @param [writer] Writer to encode to + * @returns Writer + */ + public static encodeDelimited(message: proto.IRobotCommands, writer?: $protobuf.Writer): $protobuf.Writer; - /** - * Decodes a SSL_WrapperPacket message from the specified reader or buffer. - * @param reader Reader or buffer to decode from - * @param [length] Message length if known beforehand - * @returns SSL_WrapperPacket - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket; + /** + * Decodes a RobotCommands message from the specified reader or buffer. + * @param reader Reader or buffer to decode from + * @param [length] Message length if known beforehand + * @returns RobotCommands + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decode(reader: ($protobuf.Reader|Uint8Array), length?: number): proto.RobotCommands; - /** - * Decodes a SSL_WrapperPacket message from the specified reader or buffer, length delimited. - * @param reader Reader or buffer to decode from - * @returns SSL_WrapperPacket - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket; + /** + * Decodes a RobotCommands message from the specified reader or buffer, length delimited. + * @param reader Reader or buffer to decode from + * @returns RobotCommands + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + public static decodeDelimited(reader: ($protobuf.Reader|Uint8Array)): proto.RobotCommands; - /** - * Verifies a SSL_WrapperPacket message. - * @param message Plain object to verify - * @returns `null` if valid, otherwise the reason why it is not - */ - public static verify(message: { [k: string]: any }): (string|null); + /** + * Verifies a RobotCommands message. + * @param message Plain object to verify + * @returns `null` if valid, otherwise the reason why it is not + */ + public static verify(message: { [k: string]: any }): (string|null); - /** - * Creates a SSL_WrapperPacket message from a plain object. Also converts values to their respective internal types. - * @param object Plain object - * @returns SSL_WrapperPacket - */ - public static fromObject(object: { [k: string]: any }): proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket; + /** + * Creates a RobotCommands message from a plain object. Also converts values to their respective internal types. + * @param object Plain object + * @returns RobotCommands + */ + public static fromObject(object: { [k: string]: any }): proto.RobotCommands; - /** - * Creates a plain object from a SSL_WrapperPacket message. Also converts values to other types if specified. - * @param message SSL_WrapperPacket - * @param [options] Conversion options - * @returns Plain object - */ - public static toObject(message: proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket, options?: $protobuf.IConversionOptions): { [k: string]: any }; + /** + * Creates a plain object from a RobotCommands message. Also converts values to other types if specified. + * @param message RobotCommands + * @param [options] Conversion options + * @returns Plain object + */ + public static toObject(message: proto.RobotCommands, options?: $protobuf.IConversionOptions): { [k: string]: any }; - /** - * Converts this SSL_WrapperPacket to JSON. - * @returns JSON object - */ - public toJSON(): { [k: string]: any }; + /** + * Converts this RobotCommands to JSON. + * @returns JSON object + */ + public toJSON(): { [k: string]: any }; - /** - * Gets the default type url for SSL_WrapperPacket - * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") - * @returns The default type url - */ - public static getTypeUrl(typeUrlPrefix?: string): string; - } - } + /** + * Gets the default type url for RobotCommands + * @param [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns The default type url + */ + public static getTypeUrl(typeUrlPrefix?: string): string; } } @@ -12606,6 +13013,24 @@ export class SSL_GeometryFieldSize implements ISSL_GeometryFieldSize { /** SSL_GeometryFieldSize penaltyAreaWidth. */ public penaltyAreaWidth: number; + /** SSL_GeometryFieldSize centerCircleRadius. */ + public centerCircleRadius: number; + + /** SSL_GeometryFieldSize lineThickness. */ + public lineThickness: number; + + /** SSL_GeometryFieldSize goalCenterToPenaltyMark. */ + public goalCenterToPenaltyMark: number; + + /** SSL_GeometryFieldSize goalHeight. */ + public goalHeight: number; + + /** SSL_GeometryFieldSize ballRadius. */ + public ballRadius: number; + + /** SSL_GeometryFieldSize maxRobotRadius. */ + public maxRobotRadius: number; + /** * Creates a new SSL_GeometryFieldSize instance using the specified properties. * @param [properties] Properties to set diff --git a/roboteam_interface/src/generated/proto.js b/roboteam_interface/src/generated/proto.js index b31e85b9c..829d45b68 100644 --- a/roboteam_interface/src/generated/proto.js +++ b/roboteam_interface/src/generated/proto.js @@ -16,6 +16,319 @@ export const proto = $root.proto = (() => { */ const proto = {}; + proto.GameSettings = (function() { + + /** + * Properties of a GameSettings. + * @memberof proto + * @interface IGameSettings + * @property {boolean|null} [isPrimaryAi] GameSettings isPrimaryAi + * @property {boolean|null} [isYellow] GameSettings isYellow + * @property {boolean|null} [isLeft] GameSettings isLeft + * @property {proto.GameSettings.RobotHubMode|null} [robotHubMode] GameSettings robotHubMode + */ + + /** + * Constructs a new GameSettings. + * @memberof proto + * @classdesc Represents a GameSettings. + * @implements IGameSettings + * @constructor + * @param {proto.IGameSettings=} [properties] Properties to set + */ + function GameSettings(properties) { + if (properties) + for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) + if (properties[keys[i]] != null) + this[keys[i]] = properties[keys[i]]; + } + + /** + * GameSettings isPrimaryAi. + * @member {boolean} isPrimaryAi + * @memberof proto.GameSettings + * @instance + */ + GameSettings.prototype.isPrimaryAi = false; + + /** + * GameSettings isYellow. + * @member {boolean} isYellow + * @memberof proto.GameSettings + * @instance + */ + GameSettings.prototype.isYellow = false; + + /** + * GameSettings isLeft. + * @member {boolean} isLeft + * @memberof proto.GameSettings + * @instance + */ + GameSettings.prototype.isLeft = false; + + /** + * GameSettings robotHubMode. + * @member {proto.GameSettings.RobotHubMode} robotHubMode + * @memberof proto.GameSettings + * @instance + */ + GameSettings.prototype.robotHubMode = 0; + + /** + * Creates a new GameSettings instance using the specified properties. + * @function create + * @memberof proto.GameSettings + * @static + * @param {proto.IGameSettings=} [properties] Properties to set + * @returns {proto.GameSettings} GameSettings instance + */ + GameSettings.create = function create(properties) { + return new GameSettings(properties); + }; + + /** + * Encodes the specified GameSettings message. Does not implicitly {@link proto.GameSettings.verify|verify} messages. + * @function encode + * @memberof proto.GameSettings + * @static + * @param {proto.IGameSettings} message GameSettings message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + GameSettings.encode = function encode(message, writer) { + if (!writer) + writer = $Writer.create(); + if (message.isPrimaryAi != null && Object.hasOwnProperty.call(message, "isPrimaryAi")) + writer.uint32(/* id 1, wireType 0 =*/8).bool(message.isPrimaryAi); + if (message.isYellow != null && Object.hasOwnProperty.call(message, "isYellow")) + writer.uint32(/* id 2, wireType 0 =*/16).bool(message.isYellow); + if (message.isLeft != null && Object.hasOwnProperty.call(message, "isLeft")) + writer.uint32(/* id 3, wireType 0 =*/24).bool(message.isLeft); + if (message.robotHubMode != null && Object.hasOwnProperty.call(message, "robotHubMode")) + writer.uint32(/* id 4, wireType 0 =*/32).int32(message.robotHubMode); + return writer; + }; + + /** + * Encodes the specified GameSettings message, length delimited. Does not implicitly {@link proto.GameSettings.verify|verify} messages. + * @function encodeDelimited + * @memberof proto.GameSettings + * @static + * @param {proto.IGameSettings} message GameSettings message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + GameSettings.encodeDelimited = function encodeDelimited(message, writer) { + return this.encode(message, writer).ldelim(); + }; + + /** + * Decodes a GameSettings message from the specified reader or buffer. + * @function decode + * @memberof proto.GameSettings + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @param {number} [length] Message length if known beforehand + * @returns {proto.GameSettings} GameSettings + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + GameSettings.decode = function decode(reader, length) { + if (!(reader instanceof $Reader)) + reader = $Reader.create(reader); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.GameSettings(); + while (reader.pos < end) { + let tag = reader.uint32(); + switch (tag >>> 3) { + case 1: { + message.isPrimaryAi = reader.bool(); + break; + } + case 2: { + message.isYellow = reader.bool(); + break; + } + case 3: { + message.isLeft = reader.bool(); + break; + } + case 4: { + message.robotHubMode = reader.int32(); + break; + } + default: + reader.skipType(tag & 7); + break; + } + } + return message; + }; + + /** + * Decodes a GameSettings message from the specified reader or buffer, length delimited. + * @function decodeDelimited + * @memberof proto.GameSettings + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @returns {proto.GameSettings} GameSettings + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + GameSettings.decodeDelimited = function decodeDelimited(reader) { + if (!(reader instanceof $Reader)) + reader = new $Reader(reader); + return this.decode(reader, reader.uint32()); + }; + + /** + * Verifies a GameSettings message. + * @function verify + * @memberof proto.GameSettings + * @static + * @param {Object.} message Plain object to verify + * @returns {string|null} `null` if valid, otherwise the reason why it is not + */ + GameSettings.verify = function verify(message) { + if (typeof message !== "object" || message === null) + return "object expected"; + if (message.isPrimaryAi != null && message.hasOwnProperty("isPrimaryAi")) + if (typeof message.isPrimaryAi !== "boolean") + return "isPrimaryAi: boolean expected"; + if (message.isYellow != null && message.hasOwnProperty("isYellow")) + if (typeof message.isYellow !== "boolean") + return "isYellow: boolean expected"; + if (message.isLeft != null && message.hasOwnProperty("isLeft")) + if (typeof message.isLeft !== "boolean") + return "isLeft: boolean expected"; + if (message.robotHubMode != null && message.hasOwnProperty("robotHubMode")) + switch (message.robotHubMode) { + default: + return "robotHubMode: enum value expected"; + case 0: + case 1: + case 2: + break; + } + return null; + }; + + /** + * Creates a GameSettings message from a plain object. Also converts values to their respective internal types. + * @function fromObject + * @memberof proto.GameSettings + * @static + * @param {Object.} object Plain object + * @returns {proto.GameSettings} GameSettings + */ + GameSettings.fromObject = function fromObject(object) { + if (object instanceof $root.proto.GameSettings) + return object; + let message = new $root.proto.GameSettings(); + if (object.isPrimaryAi != null) + message.isPrimaryAi = Boolean(object.isPrimaryAi); + if (object.isYellow != null) + message.isYellow = Boolean(object.isYellow); + if (object.isLeft != null) + message.isLeft = Boolean(object.isLeft); + switch (object.robotHubMode) { + default: + if (typeof object.robotHubMode === "number") { + message.robotHubMode = object.robotHubMode; + break; + } + break; + case "UNKNOWN": + case 0: + message.robotHubMode = 0; + break; + case "BASESTATION": + case 1: + message.robotHubMode = 1; + break; + case "SIMULATOR": + case 2: + message.robotHubMode = 2; + break; + } + return message; + }; + + /** + * Creates a plain object from a GameSettings message. Also converts values to other types if specified. + * @function toObject + * @memberof proto.GameSettings + * @static + * @param {proto.GameSettings} message GameSettings + * @param {$protobuf.IConversionOptions} [options] Conversion options + * @returns {Object.} Plain object + */ + GameSettings.toObject = function toObject(message, options) { + if (!options) + options = {}; + let object = {}; + if (options.defaults) { + object.isPrimaryAi = false; + object.isYellow = false; + object.isLeft = false; + object.robotHubMode = options.enums === String ? "UNKNOWN" : 0; + } + if (message.isPrimaryAi != null && message.hasOwnProperty("isPrimaryAi")) + object.isPrimaryAi = message.isPrimaryAi; + if (message.isYellow != null && message.hasOwnProperty("isYellow")) + object.isYellow = message.isYellow; + if (message.isLeft != null && message.hasOwnProperty("isLeft")) + object.isLeft = message.isLeft; + if (message.robotHubMode != null && message.hasOwnProperty("robotHubMode")) + object.robotHubMode = options.enums === String ? $root.proto.GameSettings.RobotHubMode[message.robotHubMode] === undefined ? message.robotHubMode : $root.proto.GameSettings.RobotHubMode[message.robotHubMode] : message.robotHubMode; + return object; + }; + + /** + * Converts this GameSettings to JSON. + * @function toJSON + * @memberof proto.GameSettings + * @instance + * @returns {Object.} JSON object + */ + GameSettings.prototype.toJSON = function toJSON() { + return this.constructor.toObject(this, $protobuf.util.toJSONOptions); + }; + + /** + * Gets the default type url for GameSettings + * @function getTypeUrl + * @memberof proto.GameSettings + * @static + * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns {string} The default type url + */ + GameSettings.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + if (typeUrlPrefix === undefined) { + typeUrlPrefix = "type.googleapis.com"; + } + return typeUrlPrefix + "/proto.GameSettings"; + }; + + /** + * RobotHubMode enum. + * @name proto.GameSettings.RobotHubMode + * @enum {number} + * @property {number} UNKNOWN=0 UNKNOWN value + * @property {number} BASESTATION=1 BASESTATION value + * @property {number} SIMULATOR=2 SIMULATOR value + */ + GameSettings.RobotHubMode = (function() { + const valuesById = {}, values = Object.create(valuesById); + values[valuesById[0] = "UNKNOWN"] = 0; + values[valuesById[1] = "BASESTATION"] = 1; + values[valuesById[2] = "SIMULATOR"] = 2; + return values; + })(); + + return GameSettings; + })(); + proto.Drawing = (function() { /** @@ -289,6 +602,7 @@ export const proto = $root.proto = (() => { case 5: case 6: case 7: + case 8: break; } if (message.method != null && message.hasOwnProperty("method")) @@ -317,6 +631,7 @@ export const proto = $root.proto = (() => { return "category: enum value expected"; case 0: case 1: + case 2: break; } if (message.forRobotId != null && message.hasOwnProperty("forRobotId")) @@ -382,10 +697,14 @@ export const proto = $root.proto = (() => { case 6: message.color = 6; break; - case "BLACK": + case "GREY": case 7: message.color = 7; break; + case "BLACK": + case 8: + message.color = 8; + break; } switch (object.method) { default: @@ -440,7 +759,7 @@ export const proto = $root.proto = (() => { case 1: message.category = 1; break; - case "MARGIN": + case "MARGINS": case 2: message.category = 2; break; @@ -560,7 +879,8 @@ export const proto = $root.proto = (() => { * @property {number} CYAN=4 CYAN value * @property {number} MAGENTA=5 MAGENTA value * @property {number} WHITE=6 WHITE value - * @property {number} BLACK=7 BLACK value + * @property {number} GREY=7 GREY value + * @property {number} BLACK=8 BLACK value */ Drawing.Color = (function() { const valuesById = {}, values = Object.create(valuesById); @@ -571,7 +891,8 @@ export const proto = $root.proto = (() => { values[valuesById[4] = "CYAN"] = 4; values[valuesById[5] = "MAGENTA"] = 5; values[valuesById[6] = "WHITE"] = 6; - values[valuesById[7] = "BLACK"] = 7; + values[valuesById[7] = "GREY"] = 7; + values[valuesById[8] = "BLACK"] = 8; return values; })(); @@ -3719,6 +4040,9 @@ export const proto = $root.proto = (() => { * @property {string|null} [playName] PlayInfo playName * @property {string|null} [rulesetName] PlayInfo rulesetName * @property {number|null} [keeperId] PlayInfo keeperId + * @property {number|null} [timeleft] PlayInfo timeleft + * @property {string|null} [followupcommandfromrefName] PlayInfo followupcommandfromrefName + * @property {string|null} [commandfromrefName] PlayInfo commandfromrefName */ /** @@ -3760,6 +4084,30 @@ export const proto = $root.proto = (() => { */ PlayInfo.prototype.keeperId = 0; + /** + * PlayInfo timeleft. + * @member {number} timeleft + * @memberof proto.PlayInfo + * @instance + */ + PlayInfo.prototype.timeleft = 0; + + /** + * PlayInfo followupcommandfromrefName. + * @member {string} followupcommandfromrefName + * @memberof proto.PlayInfo + * @instance + */ + PlayInfo.prototype.followupcommandfromrefName = ""; + + /** + * PlayInfo commandfromrefName. + * @member {string} commandfromrefName + * @memberof proto.PlayInfo + * @instance + */ + PlayInfo.prototype.commandfromrefName = ""; + /** * Creates a new PlayInfo instance using the specified properties. * @function create @@ -3790,12 +4138,12 @@ export const proto = $root.proto = (() => { writer.uint32(/* id 2, wireType 2 =*/18).string(message.rulesetName); if (message.keeperId != null && Object.hasOwnProperty.call(message, "keeperId")) writer.uint32(/* id 3, wireType 0 =*/24).int32(message.keeperId); - if (message.timeLeft != null && Object.hasOwnProperty.call(message, "timeLeft")) - writer.uint32(/* id 4, wireType 0 =*/30).double(message.timeLeft); - if (message.commandFromRef != null && Object.hasOwnProperty.call(message, "commandFromRef")) - writer.uint32(/* id 5, wireType 2 =*/36).string(message.commandFromRef); - if (message.followUpCommandFromRef != null && Object.hasOwnProperty.call(message, "followUpCommandFromRef")) - writer.uint32(/* id 6, wireType 2 =*/42).string(message.followUpCommandFromRef); + if (message.timeleft != null && Object.hasOwnProperty.call(message, "timeleft")) + writer.uint32(/* id 4, wireType 1 =*/33).double(message.timeleft); + if (message.followupcommandfromrefName != null && Object.hasOwnProperty.call(message, "followupcommandfromrefName")) + writer.uint32(/* id 5, wireType 2 =*/42).string(message.followupcommandfromrefName); + if (message.commandfromrefName != null && Object.hasOwnProperty.call(message, "commandfromrefName")) + writer.uint32(/* id 6, wireType 2 =*/50).string(message.commandfromrefName); return writer; }; @@ -3843,15 +4191,15 @@ export const proto = $root.proto = (() => { break; } case 4: { - message.timeLeft = reader.double(); + message.timeleft = reader.double(); break; } case 5: { - message.followUpCommandFromRef = reader.string(); + message.followupcommandfromrefName = reader.string(); break; } case 6: { - message.commandFromRef = reader.string(); + message.commandfromrefName = reader.string(); break; } default: @@ -3898,6 +4246,15 @@ export const proto = $root.proto = (() => { if (message.keeperId != null && message.hasOwnProperty("keeperId")) if (!$util.isInteger(message.keeperId)) return "keeperId: integer expected"; + if (message.timeleft != null && message.hasOwnProperty("timeleft")) + if (typeof message.timeleft !== "number") + return "timeleft: number expected"; + if (message.followupcommandfromrefName != null && message.hasOwnProperty("followupcommandfromrefName")) + if (!$util.isString(message.followupcommandfromrefName)) + return "followupcommandfromrefName: string expected"; + if (message.commandfromrefName != null && message.hasOwnProperty("commandfromrefName")) + if (!$util.isString(message.commandfromrefName)) + return "commandfromrefName: string expected"; return null; }; @@ -3919,6 +4276,12 @@ export const proto = $root.proto = (() => { message.rulesetName = String(object.rulesetName); if (object.keeperId != null) message.keeperId = object.keeperId | 0; + if (object.timeleft != null) + message.timeleft = Number(object.timeleft); + if (object.followupcommandfromrefName != null) + message.followupcommandfromrefName = String(object.followupcommandfromrefName); + if (object.commandfromrefName != null) + message.commandfromrefName = String(object.commandfromrefName); return message; }; @@ -3939,6 +4302,9 @@ export const proto = $root.proto = (() => { object.playName = ""; object.rulesetName = ""; object.keeperId = 0; + object.timeleft = 0; + object.followupcommandfromrefName = ""; + object.commandfromrefName = ""; } if (message.playName != null && message.hasOwnProperty("playName")) object.playName = message.playName; @@ -3946,6 +4312,12 @@ export const proto = $root.proto = (() => { object.rulesetName = message.rulesetName; if (message.keeperId != null && message.hasOwnProperty("keeperId")) object.keeperId = message.keeperId; + if (message.timeleft != null && message.hasOwnProperty("timeleft")) + object.timeleft = options.json && !isFinite(message.timeleft) ? String(message.timeleft) : message.timeleft; + if (message.followupcommandfromrefName != null && message.hasOwnProperty("followupcommandfromrefName")) + object.followupcommandfromrefName = message.followupcommandfromrefName; + if (message.commandfromrefName != null && message.hasOwnProperty("commandfromrefName")) + object.commandfromrefName = message.commandfromrefName; return object; }; @@ -4975,319 +5347,6 @@ export const proto = $root.proto = (() => { return MsgFromInterface; })(); - proto.GameSettings = (function() { - - /** - * Properties of a GameSettings. - * @memberof proto - * @interface IGameSettings - * @property {boolean|null} [isPrimaryAi] GameSettings isPrimaryAi - * @property {boolean|null} [isYellow] GameSettings isYellow - * @property {boolean|null} [isLeft] GameSettings isLeft - * @property {proto.GameSettings.RobotHubMode|null} [robotHubMode] GameSettings robotHubMode - */ - - /** - * Constructs a new GameSettings. - * @memberof proto - * @classdesc Represents a GameSettings. - * @implements IGameSettings - * @constructor - * @param {proto.IGameSettings=} [properties] Properties to set - */ - function GameSettings(properties) { - if (properties) - for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) - if (properties[keys[i]] != null) - this[keys[i]] = properties[keys[i]]; - } - - /** - * GameSettings isPrimaryAi. - * @member {boolean} isPrimaryAi - * @memberof proto.GameSettings - * @instance - */ - GameSettings.prototype.isPrimaryAi = false; - - /** - * GameSettings isYellow. - * @member {boolean} isYellow - * @memberof proto.GameSettings - * @instance - */ - GameSettings.prototype.isYellow = false; - - /** - * GameSettings isLeft. - * @member {boolean} isLeft - * @memberof proto.GameSettings - * @instance - */ - GameSettings.prototype.isLeft = false; - - /** - * GameSettings robotHubMode. - * @member {proto.GameSettings.RobotHubMode} robotHubMode - * @memberof proto.GameSettings - * @instance - */ - GameSettings.prototype.robotHubMode = 0; - - /** - * Creates a new GameSettings instance using the specified properties. - * @function create - * @memberof proto.GameSettings - * @static - * @param {proto.IGameSettings=} [properties] Properties to set - * @returns {proto.GameSettings} GameSettings instance - */ - GameSettings.create = function create(properties) { - return new GameSettings(properties); - }; - - /** - * Encodes the specified GameSettings message. Does not implicitly {@link proto.GameSettings.verify|verify} messages. - * @function encode - * @memberof proto.GameSettings - * @static - * @param {proto.IGameSettings} message GameSettings message or plain object to encode - * @param {$protobuf.Writer} [writer] Writer to encode to - * @returns {$protobuf.Writer} Writer - */ - GameSettings.encode = function encode(message, writer) { - if (!writer) - writer = $Writer.create(); - if (message.isPrimaryAi != null && Object.hasOwnProperty.call(message, "isPrimaryAi")) - writer.uint32(/* id 1, wireType 0 =*/8).bool(message.isPrimaryAi); - if (message.isYellow != null && Object.hasOwnProperty.call(message, "isYellow")) - writer.uint32(/* id 2, wireType 0 =*/16).bool(message.isYellow); - if (message.isLeft != null && Object.hasOwnProperty.call(message, "isLeft")) - writer.uint32(/* id 3, wireType 0 =*/24).bool(message.isLeft); - if (message.robotHubMode != null && Object.hasOwnProperty.call(message, "robotHubMode")) - writer.uint32(/* id 4, wireType 0 =*/32).int32(message.robotHubMode); - return writer; - }; - - /** - * Encodes the specified GameSettings message, length delimited. Does not implicitly {@link proto.GameSettings.verify|verify} messages. - * @function encodeDelimited - * @memberof proto.GameSettings - * @static - * @param {proto.IGameSettings} message GameSettings message or plain object to encode - * @param {$protobuf.Writer} [writer] Writer to encode to - * @returns {$protobuf.Writer} Writer - */ - GameSettings.encodeDelimited = function encodeDelimited(message, writer) { - return this.encode(message, writer).ldelim(); - }; - - /** - * Decodes a GameSettings message from the specified reader or buffer. - * @function decode - * @memberof proto.GameSettings - * @static - * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @param {number} [length] Message length if known beforehand - * @returns {proto.GameSettings} GameSettings - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - GameSettings.decode = function decode(reader, length) { - if (!(reader instanceof $Reader)) - reader = $Reader.create(reader); - let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.GameSettings(); - while (reader.pos < end) { - let tag = reader.uint32(); - switch (tag >>> 3) { - case 1: { - message.isPrimaryAi = reader.bool(); - break; - } - case 2: { - message.isYellow = reader.bool(); - break; - } - case 3: { - message.isLeft = reader.bool(); - break; - } - case 4: { - message.robotHubMode = reader.int32(); - break; - } - default: - reader.skipType(tag & 7); - break; - } - } - return message; - }; - - /** - * Decodes a GameSettings message from the specified reader or buffer, length delimited. - * @function decodeDelimited - * @memberof proto.GameSettings - * @static - * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @returns {proto.GameSettings} GameSettings - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - GameSettings.decodeDelimited = function decodeDelimited(reader) { - if (!(reader instanceof $Reader)) - reader = new $Reader(reader); - return this.decode(reader, reader.uint32()); - }; - - /** - * Verifies a GameSettings message. - * @function verify - * @memberof proto.GameSettings - * @static - * @param {Object.} message Plain object to verify - * @returns {string|null} `null` if valid, otherwise the reason why it is not - */ - GameSettings.verify = function verify(message) { - if (typeof message !== "object" || message === null) - return "object expected"; - if (message.isPrimaryAi != null && message.hasOwnProperty("isPrimaryAi")) - if (typeof message.isPrimaryAi !== "boolean") - return "isPrimaryAi: boolean expected"; - if (message.isYellow != null && message.hasOwnProperty("isYellow")) - if (typeof message.isYellow !== "boolean") - return "isYellow: boolean expected"; - if (message.isLeft != null && message.hasOwnProperty("isLeft")) - if (typeof message.isLeft !== "boolean") - return "isLeft: boolean expected"; - if (message.robotHubMode != null && message.hasOwnProperty("robotHubMode")) - switch (message.robotHubMode) { - default: - return "robotHubMode: enum value expected"; - case 0: - case 1: - case 2: - break; - } - return null; - }; - - /** - * Creates a GameSettings message from a plain object. Also converts values to their respective internal types. - * @function fromObject - * @memberof proto.GameSettings - * @static - * @param {Object.} object Plain object - * @returns {proto.GameSettings} GameSettings - */ - GameSettings.fromObject = function fromObject(object) { - if (object instanceof $root.proto.GameSettings) - return object; - let message = new $root.proto.GameSettings(); - if (object.isPrimaryAi != null) - message.isPrimaryAi = Boolean(object.isPrimaryAi); - if (object.isYellow != null) - message.isYellow = Boolean(object.isYellow); - if (object.isLeft != null) - message.isLeft = Boolean(object.isLeft); - switch (object.robotHubMode) { - default: - if (typeof object.robotHubMode === "number") { - message.robotHubMode = object.robotHubMode; - break; - } - break; - case "UNKNOWN": - case 0: - message.robotHubMode = 0; - break; - case "BASESTATION": - case 1: - message.robotHubMode = 1; - break; - case "SIMULATOR": - case 2: - message.robotHubMode = 2; - break; - } - return message; - }; - - /** - * Creates a plain object from a GameSettings message. Also converts values to other types if specified. - * @function toObject - * @memberof proto.GameSettings - * @static - * @param {proto.GameSettings} message GameSettings - * @param {$protobuf.IConversionOptions} [options] Conversion options - * @returns {Object.} Plain object - */ - GameSettings.toObject = function toObject(message, options) { - if (!options) - options = {}; - let object = {}; - if (options.defaults) { - object.isPrimaryAi = false; - object.isYellow = false; - object.isLeft = false; - object.robotHubMode = options.enums === String ? "UNKNOWN" : 0; - } - if (message.isPrimaryAi != null && message.hasOwnProperty("isPrimaryAi")) - object.isPrimaryAi = message.isPrimaryAi; - if (message.isYellow != null && message.hasOwnProperty("isYellow")) - object.isYellow = message.isYellow; - if (message.isLeft != null && message.hasOwnProperty("isLeft")) - object.isLeft = message.isLeft; - if (message.robotHubMode != null && message.hasOwnProperty("robotHubMode")) - object.robotHubMode = options.enums === String ? $root.proto.GameSettings.RobotHubMode[message.robotHubMode] === undefined ? message.robotHubMode : $root.proto.GameSettings.RobotHubMode[message.robotHubMode] : message.robotHubMode; - return object; - }; - - /** - * Converts this GameSettings to JSON. - * @function toJSON - * @memberof proto.GameSettings - * @instance - * @returns {Object.} JSON object - */ - GameSettings.prototype.toJSON = function toJSON() { - return this.constructor.toObject(this, $protobuf.util.toJSONOptions); - }; - - /** - * Gets the default type url for GameSettings - * @function getTypeUrl - * @memberof proto.GameSettings - * @static - * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") - * @returns {string} The default type url - */ - GameSettings.getTypeUrl = function getTypeUrl(typeUrlPrefix) { - if (typeUrlPrefix === undefined) { - typeUrlPrefix = "type.googleapis.com"; - } - return typeUrlPrefix + "/proto.GameSettings"; - }; - - /** - * RobotHubMode enum. - * @name proto.GameSettings.RobotHubMode - * @enum {number} - * @property {number} UNKNOWN=0 UNKNOWN value - * @property {number} BASESTATION=1 BASESTATION value - * @property {number} SIMULATOR=2 SIMULATOR value - */ - GameSettings.RobotHubMode = (function() { - const valuesById = {}, values = Object.create(valuesById); - values[valuesById[0] = "UNKNOWN"] = 0; - values[valuesById[1] = "BASESTATION"] = 1; - values[valuesById[2] = "SIMULATOR"] = 2; - return values; - })(); - - return GameSettings; - })(); - proto.State = (function() { /** @@ -5300,9 +5359,9 @@ export const proto = $root.proto = (() => { * @property {proto.ITeamParameters|null} [blueRobotParameters] State blueRobotParameters * @property {proto.ITeamParameters|null} [yellowRobotParameters] State yellowRobotParameters * @property {proto.ISSL_GeometryData|null} [field] State field - * @property {proto.ISSL_Referee|null} [referee] State referee + * @property {proto.IReferee|null} [referee] State referee * @property {Array.|null} [processedVisionPackets] State processedVisionPackets - * @property {Array.|null} [processedRefereePackets] State processedRefereePackets + * @property {Array.|null} [processedRefereePackets] State processedRefereePackets * @property {Array.|null} [processedFeedbackPackets] State processedFeedbackPackets */ @@ -5374,7 +5433,7 @@ export const proto = $root.proto = (() => { /** * State referee. - * @member {proto.ISSL_Referee|null|undefined} referee + * @member {proto.IReferee|null|undefined} referee * @memberof proto.State * @instance */ @@ -5390,7 +5449,7 @@ export const proto = $root.proto = (() => { /** * State processedRefereePackets. - * @member {Array.} processedRefereePackets + * @member {Array.} processedRefereePackets * @memberof proto.State * @instance */ @@ -5441,13 +5500,13 @@ export const proto = $root.proto = (() => { if (message.field != null && Object.hasOwnProperty.call(message, "field")) $root.proto.SSL_GeometryData.encode(message.field, writer.uint32(/* id 6, wireType 2 =*/50).fork()).ldelim(); if (message.referee != null && Object.hasOwnProperty.call(message, "referee")) - $root.proto.SSL_Referee.encode(message.referee, writer.uint32(/* id 7, wireType 2 =*/58).fork()).ldelim(); + $root.proto.Referee.encode(message.referee, writer.uint32(/* id 7, wireType 2 =*/58).fork()).ldelim(); if (message.processedVisionPackets != null && message.processedVisionPackets.length) for (let i = 0; i < message.processedVisionPackets.length; ++i) $root.proto.SSL_WrapperPacket.encode(message.processedVisionPackets[i], writer.uint32(/* id 10, wireType 2 =*/82).fork()).ldelim(); if (message.processedRefereePackets != null && message.processedRefereePackets.length) for (let i = 0; i < message.processedRefereePackets.length; ++i) - $root.proto.SSL_Referee.encode(message.processedRefereePackets[i], writer.uint32(/* id 11, wireType 2 =*/90).fork()).ldelim(); + $root.proto.Referee.encode(message.processedRefereePackets[i], writer.uint32(/* id 11, wireType 2 =*/90).fork()).ldelim(); if (message.processedFeedbackPackets != null && message.processedFeedbackPackets.length) for (let i = 0; i < message.processedFeedbackPackets.length; ++i) $root.proto.RobotsFeedback.encode(message.processedFeedbackPackets[i], writer.uint32(/* id 12, wireType 2 =*/98).fork()).ldelim(); @@ -5510,7 +5569,7 @@ export const proto = $root.proto = (() => { break; } case 7: { - message.referee = $root.proto.SSL_Referee.decode(reader, reader.uint32()); + message.referee = $root.proto.Referee.decode(reader, reader.uint32()); break; } case 10: { @@ -5522,7 +5581,7 @@ export const proto = $root.proto = (() => { case 11: { if (!(message.processedRefereePackets && message.processedRefereePackets.length)) message.processedRefereePackets = []; - message.processedRefereePackets.push($root.proto.SSL_Referee.decode(reader, reader.uint32())); + message.processedRefereePackets.push($root.proto.Referee.decode(reader, reader.uint32())); break; } case 12: { @@ -5597,7 +5656,7 @@ export const proto = $root.proto = (() => { return "field." + error; } if (message.referee != null && message.hasOwnProperty("referee")) { - let error = $root.proto.SSL_Referee.verify(message.referee); + let error = $root.proto.Referee.verify(message.referee); if (error) return "referee." + error; } @@ -5614,7 +5673,7 @@ export const proto = $root.proto = (() => { if (!Array.isArray(message.processedRefereePackets)) return "processedRefereePackets: array expected"; for (let i = 0; i < message.processedRefereePackets.length; ++i) { - let error = $root.proto.SSL_Referee.verify(message.processedRefereePackets[i]); + let error = $root.proto.Referee.verify(message.processedRefereePackets[i]); if (error) return "processedRefereePackets." + error; } @@ -5676,7 +5735,7 @@ export const proto = $root.proto = (() => { if (object.referee != null) { if (typeof object.referee !== "object") throw TypeError(".proto.State.referee: object expected"); - message.referee = $root.proto.SSL_Referee.fromObject(object.referee); + message.referee = $root.proto.Referee.fromObject(object.referee); } if (object.processedVisionPackets) { if (!Array.isArray(object.processedVisionPackets)) @@ -5695,7 +5754,7 @@ export const proto = $root.proto = (() => { for (let i = 0; i < object.processedRefereePackets.length; ++i) { if (typeof object.processedRefereePackets[i] !== "object") throw TypeError(".proto.State.processedRefereePackets: object expected"); - message.processedRefereePackets[i] = $root.proto.SSL_Referee.fromObject(object.processedRefereePackets[i]); + message.processedRefereePackets[i] = $root.proto.Referee.fromObject(object.processedRefereePackets[i]); } } if (object.processedFeedbackPackets) { @@ -5751,7 +5810,7 @@ export const proto = $root.proto = (() => { if (message.field != null && message.hasOwnProperty("field")) object.field = $root.proto.SSL_GeometryData.toObject(message.field, options); if (message.referee != null && message.hasOwnProperty("referee")) - object.referee = $root.proto.SSL_Referee.toObject(message.referee, options); + object.referee = $root.proto.Referee.toObject(message.referee, options); if (message.processedVisionPackets && message.processedVisionPackets.length) { object.processedVisionPackets = []; for (let j = 0; j < message.processedVisionPackets.length; ++j) @@ -5760,7 +5819,7 @@ export const proto = $root.proto = (() => { if (message.processedRefereePackets && message.processedRefereePackets.length) { object.processedRefereePackets = []; for (let j = 0; j < message.processedRefereePackets.length; ++j) - object.processedRefereePackets[j] = $root.proto.SSL_Referee.toObject(message.processedRefereePackets[j], options); + object.processedRefereePackets[j] = $root.proto.Referee.toObject(message.processedRefereePackets[j], options); } if (message.processedFeedbackPackets && message.processedFeedbackPackets.length) { object.processedFeedbackPackets = []; @@ -6810,7 +6869,7 @@ export const proto = $root.proto = (() => { * @interface IWorldRobot * @property {number|null} [id] WorldRobot id * @property {proto.IVector2f|null} [pos] WorldRobot pos - * @property {number|null} [angle] WorldRobot angle + * @property {number|null} [yaw] WorldRobot yaw * @property {proto.IVector2f|null} [vel] WorldRobot vel * @property {number|null} [w] WorldRobot w * @property {proto.IRobotProcessedFeedback|null} [feedbackInfo] WorldRobot feedbackInfo @@ -6848,12 +6907,12 @@ export const proto = $root.proto = (() => { WorldRobot.prototype.pos = null; /** - * WorldRobot angle. - * @member {number} angle + * WorldRobot yaw. + * @member {number} yaw * @memberof proto.WorldRobot * @instance */ - WorldRobot.prototype.angle = 0; + WorldRobot.prototype.yaw = 0; /** * WorldRobot vel. @@ -6907,8 +6966,8 @@ export const proto = $root.proto = (() => { writer.uint32(/* id 1, wireType 0 =*/8).uint32(message.id); if (message.pos != null && Object.hasOwnProperty.call(message, "pos")) $root.proto.Vector2f.encode(message.pos, writer.uint32(/* id 2, wireType 2 =*/18).fork()).ldelim(); - if (message.angle != null && Object.hasOwnProperty.call(message, "angle")) - writer.uint32(/* id 3, wireType 5 =*/29).float(message.angle); + if (message.yaw != null && Object.hasOwnProperty.call(message, "yaw")) + writer.uint32(/* id 3, wireType 5 =*/29).float(message.yaw); if (message.vel != null && Object.hasOwnProperty.call(message, "vel")) $root.proto.Vector2f.encode(message.vel, writer.uint32(/* id 4, wireType 2 =*/34).fork()).ldelim(); if (message.w != null && Object.hasOwnProperty.call(message, "w")) @@ -6958,7 +7017,7 @@ export const proto = $root.proto = (() => { break; } case 3: { - message.angle = reader.float(); + message.yaw = reader.float(); break; } case 4: { @@ -7016,9 +7075,9 @@ export const proto = $root.proto = (() => { if (error) return "pos." + error; } - if (message.angle != null && message.hasOwnProperty("angle")) - if (typeof message.angle !== "number") - return "angle: number expected"; + if (message.yaw != null && message.hasOwnProperty("yaw")) + if (typeof message.yaw !== "number") + return "yaw: number expected"; if (message.vel != null && message.hasOwnProperty("vel")) { let error = $root.proto.Vector2f.verify(message.vel); if (error) @@ -7054,8 +7113,8 @@ export const proto = $root.proto = (() => { throw TypeError(".proto.WorldRobot.pos: object expected"); message.pos = $root.proto.Vector2f.fromObject(object.pos); } - if (object.angle != null) - message.angle = Number(object.angle); + if (object.yaw != null) + message.yaw = Number(object.yaw); if (object.vel != null) { if (typeof object.vel !== "object") throw TypeError(".proto.WorldRobot.vel: object expected"); @@ -7087,7 +7146,7 @@ export const proto = $root.proto = (() => { if (options.defaults) { object.id = 0; object.pos = null; - object.angle = 0; + object.yaw = 0; object.vel = null; object.w = 0; object.feedbackInfo = null; @@ -7096,8 +7155,8 @@ export const proto = $root.proto = (() => { object.id = message.id; if (message.pos != null && message.hasOwnProperty("pos")) object.pos = $root.proto.Vector2f.toObject(message.pos, options); - if (message.angle != null && message.hasOwnProperty("angle")) - object.angle = options.json && !isFinite(message.angle) ? String(message.angle) : message.angle; + if (message.yaw != null && message.hasOwnProperty("yaw")) + object.yaw = options.json && !isFinite(message.yaw) ? String(message.yaw) : message.yaw; if (message.vel != null && message.hasOwnProperty("vel")) object.vel = $root.proto.Vector2f.toObject(message.vel, options); if (message.w != null && message.hasOwnProperty("w")) @@ -7136,526 +7195,6 @@ export const proto = $root.proto = (() => { return WorldRobot; })(); - proto.RobotWheel = (function() { - - /** - * Properties of a RobotWheel. - * @memberof proto - * @interface IRobotWheel - * @property {boolean|null} [locked] RobotWheel locked - * @property {boolean|null} [braking] RobotWheel braking - */ - - /** - * Constructs a new RobotWheel. - * @memberof proto - * @classdesc Represents a RobotWheel. - * @implements IRobotWheel - * @constructor - * @param {proto.IRobotWheel=} [properties] Properties to set - */ - function RobotWheel(properties) { - if (properties) - for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) - if (properties[keys[i]] != null) - this[keys[i]] = properties[keys[i]]; - } - - /** - * RobotWheel locked. - * @member {boolean} locked - * @memberof proto.RobotWheel - * @instance - */ - RobotWheel.prototype.locked = false; - - /** - * RobotWheel braking. - * @member {boolean} braking - * @memberof proto.RobotWheel - * @instance - */ - RobotWheel.prototype.braking = false; - - /** - * Creates a new RobotWheel instance using the specified properties. - * @function create - * @memberof proto.RobotWheel - * @static - * @param {proto.IRobotWheel=} [properties] Properties to set - * @returns {proto.RobotWheel} RobotWheel instance - */ - RobotWheel.create = function create(properties) { - return new RobotWheel(properties); - }; - - /** - * Encodes the specified RobotWheel message. Does not implicitly {@link proto.RobotWheel.verify|verify} messages. - * @function encode - * @memberof proto.RobotWheel - * @static - * @param {proto.IRobotWheel} message RobotWheel message or plain object to encode - * @param {$protobuf.Writer} [writer] Writer to encode to - * @returns {$protobuf.Writer} Writer - */ - RobotWheel.encode = function encode(message, writer) { - if (!writer) - writer = $Writer.create(); - if (message.locked != null && Object.hasOwnProperty.call(message, "locked")) - writer.uint32(/* id 1, wireType 0 =*/8).bool(message.locked); - if (message.braking != null && Object.hasOwnProperty.call(message, "braking")) - writer.uint32(/* id 2, wireType 0 =*/16).bool(message.braking); - return writer; - }; - - /** - * Encodes the specified RobotWheel message, length delimited. Does not implicitly {@link proto.RobotWheel.verify|verify} messages. - * @function encodeDelimited - * @memberof proto.RobotWheel - * @static - * @param {proto.IRobotWheel} message RobotWheel message or plain object to encode - * @param {$protobuf.Writer} [writer] Writer to encode to - * @returns {$protobuf.Writer} Writer - */ - RobotWheel.encodeDelimited = function encodeDelimited(message, writer) { - return this.encode(message, writer).ldelim(); - }; - - /** - * Decodes a RobotWheel message from the specified reader or buffer. - * @function decode - * @memberof proto.RobotWheel - * @static - * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @param {number} [length] Message length if known beforehand - * @returns {proto.RobotWheel} RobotWheel - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - RobotWheel.decode = function decode(reader, length) { - if (!(reader instanceof $Reader)) - reader = $Reader.create(reader); - let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.RobotWheel(); - while (reader.pos < end) { - let tag = reader.uint32(); - switch (tag >>> 3) { - case 1: { - message.locked = reader.bool(); - break; - } - case 2: { - message.braking = reader.bool(); - break; - } - default: - reader.skipType(tag & 7); - break; - } - } - return message; - }; - - /** - * Decodes a RobotWheel message from the specified reader or buffer, length delimited. - * @function decodeDelimited - * @memberof proto.RobotWheel - * @static - * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @returns {proto.RobotWheel} RobotWheel - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - RobotWheel.decodeDelimited = function decodeDelimited(reader) { - if (!(reader instanceof $Reader)) - reader = new $Reader(reader); - return this.decode(reader, reader.uint32()); - }; - - /** - * Verifies a RobotWheel message. - * @function verify - * @memberof proto.RobotWheel - * @static - * @param {Object.} message Plain object to verify - * @returns {string|null} `null` if valid, otherwise the reason why it is not - */ - RobotWheel.verify = function verify(message) { - if (typeof message !== "object" || message === null) - return "object expected"; - if (message.locked != null && message.hasOwnProperty("locked")) - if (typeof message.locked !== "boolean") - return "locked: boolean expected"; - if (message.braking != null && message.hasOwnProperty("braking")) - if (typeof message.braking !== "boolean") - return "braking: boolean expected"; - return null; - }; - - /** - * Creates a RobotWheel message from a plain object. Also converts values to their respective internal types. - * @function fromObject - * @memberof proto.RobotWheel - * @static - * @param {Object.} object Plain object - * @returns {proto.RobotWheel} RobotWheel - */ - RobotWheel.fromObject = function fromObject(object) { - if (object instanceof $root.proto.RobotWheel) - return object; - let message = new $root.proto.RobotWheel(); - if (object.locked != null) - message.locked = Boolean(object.locked); - if (object.braking != null) - message.braking = Boolean(object.braking); - return message; - }; - - /** - * Creates a plain object from a RobotWheel message. Also converts values to other types if specified. - * @function toObject - * @memberof proto.RobotWheel - * @static - * @param {proto.RobotWheel} message RobotWheel - * @param {$protobuf.IConversionOptions} [options] Conversion options - * @returns {Object.} Plain object - */ - RobotWheel.toObject = function toObject(message, options) { - if (!options) - options = {}; - let object = {}; - if (options.defaults) { - object.locked = false; - object.braking = false; - } - if (message.locked != null && message.hasOwnProperty("locked")) - object.locked = message.locked; - if (message.braking != null && message.hasOwnProperty("braking")) - object.braking = message.braking; - return object; - }; - - /** - * Converts this RobotWheel to JSON. - * @function toJSON - * @memberof proto.RobotWheel - * @instance - * @returns {Object.} JSON object - */ - RobotWheel.prototype.toJSON = function toJSON() { - return this.constructor.toObject(this, $protobuf.util.toJSONOptions); - }; - - /** - * Gets the default type url for RobotWheel - * @function getTypeUrl - * @memberof proto.RobotWheel - * @static - * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") - * @returns {string} The default type url - */ - RobotWheel.getTypeUrl = function getTypeUrl(typeUrlPrefix) { - if (typeUrlPrefix === undefined) { - typeUrlPrefix = "type.googleapis.com"; - } - return typeUrlPrefix + "/proto.RobotWheel"; - }; - - return RobotWheel; - })(); - - proto.RobotWheels = (function() { - - /** - * Properties of a RobotWheels. - * @memberof proto - * @interface IRobotWheels - * @property {proto.IRobotWheel|null} [rightFront] RobotWheels rightFront - * @property {proto.IRobotWheel|null} [rightBack] RobotWheels rightBack - * @property {proto.IRobotWheel|null} [leftBack] RobotWheels leftBack - * @property {proto.IRobotWheel|null} [leftFront] RobotWheels leftFront - */ - - /** - * Constructs a new RobotWheels. - * @memberof proto - * @classdesc Represents a RobotWheels. - * @implements IRobotWheels - * @constructor - * @param {proto.IRobotWheels=} [properties] Properties to set - */ - function RobotWheels(properties) { - if (properties) - for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) - if (properties[keys[i]] != null) - this[keys[i]] = properties[keys[i]]; - } - - /** - * RobotWheels rightFront. - * @member {proto.IRobotWheel|null|undefined} rightFront - * @memberof proto.RobotWheels - * @instance - */ - RobotWheels.prototype.rightFront = null; - - /** - * RobotWheels rightBack. - * @member {proto.IRobotWheel|null|undefined} rightBack - * @memberof proto.RobotWheels - * @instance - */ - RobotWheels.prototype.rightBack = null; - - /** - * RobotWheels leftBack. - * @member {proto.IRobotWheel|null|undefined} leftBack - * @memberof proto.RobotWheels - * @instance - */ - RobotWheels.prototype.leftBack = null; - - /** - * RobotWheels leftFront. - * @member {proto.IRobotWheel|null|undefined} leftFront - * @memberof proto.RobotWheels - * @instance - */ - RobotWheels.prototype.leftFront = null; - - /** - * Creates a new RobotWheels instance using the specified properties. - * @function create - * @memberof proto.RobotWheels - * @static - * @param {proto.IRobotWheels=} [properties] Properties to set - * @returns {proto.RobotWheels} RobotWheels instance - */ - RobotWheels.create = function create(properties) { - return new RobotWheels(properties); - }; - - /** - * Encodes the specified RobotWheels message. Does not implicitly {@link proto.RobotWheels.verify|verify} messages. - * @function encode - * @memberof proto.RobotWheels - * @static - * @param {proto.IRobotWheels} message RobotWheels message or plain object to encode - * @param {$protobuf.Writer} [writer] Writer to encode to - * @returns {$protobuf.Writer} Writer - */ - RobotWheels.encode = function encode(message, writer) { - if (!writer) - writer = $Writer.create(); - if (message.rightFront != null && Object.hasOwnProperty.call(message, "rightFront")) - $root.proto.RobotWheel.encode(message.rightFront, writer.uint32(/* id 1, wireType 2 =*/10).fork()).ldelim(); - if (message.rightBack != null && Object.hasOwnProperty.call(message, "rightBack")) - $root.proto.RobotWheel.encode(message.rightBack, writer.uint32(/* id 2, wireType 2 =*/18).fork()).ldelim(); - if (message.leftBack != null && Object.hasOwnProperty.call(message, "leftBack")) - $root.proto.RobotWheel.encode(message.leftBack, writer.uint32(/* id 3, wireType 2 =*/26).fork()).ldelim(); - if (message.leftFront != null && Object.hasOwnProperty.call(message, "leftFront")) - $root.proto.RobotWheel.encode(message.leftFront, writer.uint32(/* id 4, wireType 2 =*/34).fork()).ldelim(); - return writer; - }; - - /** - * Encodes the specified RobotWheels message, length delimited. Does not implicitly {@link proto.RobotWheels.verify|verify} messages. - * @function encodeDelimited - * @memberof proto.RobotWheels - * @static - * @param {proto.IRobotWheels} message RobotWheels message or plain object to encode - * @param {$protobuf.Writer} [writer] Writer to encode to - * @returns {$protobuf.Writer} Writer - */ - RobotWheels.encodeDelimited = function encodeDelimited(message, writer) { - return this.encode(message, writer).ldelim(); - }; - - /** - * Decodes a RobotWheels message from the specified reader or buffer. - * @function decode - * @memberof proto.RobotWheels - * @static - * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @param {number} [length] Message length if known beforehand - * @returns {proto.RobotWheels} RobotWheels - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - RobotWheels.decode = function decode(reader, length) { - if (!(reader instanceof $Reader)) - reader = $Reader.create(reader); - let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.RobotWheels(); - while (reader.pos < end) { - let tag = reader.uint32(); - switch (tag >>> 3) { - case 1: { - message.rightFront = $root.proto.RobotWheel.decode(reader, reader.uint32()); - break; - } - case 2: { - message.rightBack = $root.proto.RobotWheel.decode(reader, reader.uint32()); - break; - } - case 3: { - message.leftBack = $root.proto.RobotWheel.decode(reader, reader.uint32()); - break; - } - case 4: { - message.leftFront = $root.proto.RobotWheel.decode(reader, reader.uint32()); - break; - } - default: - reader.skipType(tag & 7); - break; - } - } - return message; - }; - - /** - * Decodes a RobotWheels message from the specified reader or buffer, length delimited. - * @function decodeDelimited - * @memberof proto.RobotWheels - * @static - * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @returns {proto.RobotWheels} RobotWheels - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - RobotWheels.decodeDelimited = function decodeDelimited(reader) { - if (!(reader instanceof $Reader)) - reader = new $Reader(reader); - return this.decode(reader, reader.uint32()); - }; - - /** - * Verifies a RobotWheels message. - * @function verify - * @memberof proto.RobotWheels - * @static - * @param {Object.} message Plain object to verify - * @returns {string|null} `null` if valid, otherwise the reason why it is not - */ - RobotWheels.verify = function verify(message) { - if (typeof message !== "object" || message === null) - return "object expected"; - if (message.rightFront != null && message.hasOwnProperty("rightFront")) { - let error = $root.proto.RobotWheel.verify(message.rightFront); - if (error) - return "rightFront." + error; - } - if (message.rightBack != null && message.hasOwnProperty("rightBack")) { - let error = $root.proto.RobotWheel.verify(message.rightBack); - if (error) - return "rightBack." + error; - } - if (message.leftBack != null && message.hasOwnProperty("leftBack")) { - let error = $root.proto.RobotWheel.verify(message.leftBack); - if (error) - return "leftBack." + error; - } - if (message.leftFront != null && message.hasOwnProperty("leftFront")) { - let error = $root.proto.RobotWheel.verify(message.leftFront); - if (error) - return "leftFront." + error; - } - return null; - }; - - /** - * Creates a RobotWheels message from a plain object. Also converts values to their respective internal types. - * @function fromObject - * @memberof proto.RobotWheels - * @static - * @param {Object.} object Plain object - * @returns {proto.RobotWheels} RobotWheels - */ - RobotWheels.fromObject = function fromObject(object) { - if (object instanceof $root.proto.RobotWheels) - return object; - let message = new $root.proto.RobotWheels(); - if (object.rightFront != null) { - if (typeof object.rightFront !== "object") - throw TypeError(".proto.RobotWheels.rightFront: object expected"); - message.rightFront = $root.proto.RobotWheel.fromObject(object.rightFront); - } - if (object.rightBack != null) { - if (typeof object.rightBack !== "object") - throw TypeError(".proto.RobotWheels.rightBack: object expected"); - message.rightBack = $root.proto.RobotWheel.fromObject(object.rightBack); - } - if (object.leftBack != null) { - if (typeof object.leftBack !== "object") - throw TypeError(".proto.RobotWheels.leftBack: object expected"); - message.leftBack = $root.proto.RobotWheel.fromObject(object.leftBack); - } - if (object.leftFront != null) { - if (typeof object.leftFront !== "object") - throw TypeError(".proto.RobotWheels.leftFront: object expected"); - message.leftFront = $root.proto.RobotWheel.fromObject(object.leftFront); - } - return message; - }; - - /** - * Creates a plain object from a RobotWheels message. Also converts values to other types if specified. - * @function toObject - * @memberof proto.RobotWheels - * @static - * @param {proto.RobotWheels} message RobotWheels - * @param {$protobuf.IConversionOptions} [options] Conversion options - * @returns {Object.} Plain object - */ - RobotWheels.toObject = function toObject(message, options) { - if (!options) - options = {}; - let object = {}; - if (options.defaults) { - object.rightFront = null; - object.rightBack = null; - object.leftBack = null; - object.leftFront = null; - } - if (message.rightFront != null && message.hasOwnProperty("rightFront")) - object.rightFront = $root.proto.RobotWheel.toObject(message.rightFront, options); - if (message.rightBack != null && message.hasOwnProperty("rightBack")) - object.rightBack = $root.proto.RobotWheel.toObject(message.rightBack, options); - if (message.leftBack != null && message.hasOwnProperty("leftBack")) - object.leftBack = $root.proto.RobotWheel.toObject(message.leftBack, options); - if (message.leftFront != null && message.hasOwnProperty("leftFront")) - object.leftFront = $root.proto.RobotWheel.toObject(message.leftFront, options); - return object; - }; - - /** - * Converts this RobotWheels to JSON. - * @function toJSON - * @memberof proto.RobotWheels - * @instance - * @returns {Object.} JSON object - */ - RobotWheels.prototype.toJSON = function toJSON() { - return this.constructor.toObject(this, $protobuf.util.toJSONOptions); - }; - - /** - * Gets the default type url for RobotWheels - * @function getTypeUrl - * @memberof proto.RobotWheels - * @static - * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") - * @returns {string} The default type url - */ - RobotWheels.getTypeUrl = function getTypeUrl(typeUrlPrefix) { - if (typeUrlPrefix === undefined) { - typeUrlPrefix = "type.googleapis.com"; - } - return typeUrlPrefix + "/proto.RobotWheels"; - }; - - return RobotWheels; - })(); - proto.RobotProcessedFeedback = (function() { /** @@ -7663,14 +7202,11 @@ export const proto = $root.proto = (() => { * @memberof proto * @interface IRobotProcessedFeedback * @property {boolean|null} [ballSensorSeesBall] RobotProcessedFeedback ballSensorSeesBall - * @property {number|null} [ballPosition] RobotProcessedFeedback ballPosition * @property {boolean|null} [ballSensorIsWorking] RobotProcessedFeedback ballSensorIsWorking * @property {boolean|null} [dribblerSeesBall] RobotProcessedFeedback dribblerSeesBall * @property {boolean|null} [xsensIsCalibrated] RobotProcessedFeedback xsensIsCalibrated * @property {boolean|null} [capacitorIsCharged] RobotProcessedFeedback capacitorIsCharged - * @property {proto.IRobotWheels|null} [wheelInformation] RobotProcessedFeedback wheelInformation * @property {number|null} [batteryLevel] RobotProcessedFeedback batteryLevel - * @property {number|null} [signalStrength] RobotProcessedFeedback signalStrength */ /** @@ -7696,14 +7232,6 @@ export const proto = $root.proto = (() => { */ RobotProcessedFeedback.prototype.ballSensorSeesBall = false; - /** - * RobotProcessedFeedback ballPosition. - * @member {number} ballPosition - * @memberof proto.RobotProcessedFeedback - * @instance - */ - RobotProcessedFeedback.prototype.ballPosition = 0; - /** * RobotProcessedFeedback ballSensorIsWorking. * @member {boolean} ballSensorIsWorking @@ -7736,14 +7264,6 @@ export const proto = $root.proto = (() => { */ RobotProcessedFeedback.prototype.capacitorIsCharged = false; - /** - * RobotProcessedFeedback wheelInformation. - * @member {proto.IRobotWheels|null|undefined} wheelInformation - * @memberof proto.RobotProcessedFeedback - * @instance - */ - RobotProcessedFeedback.prototype.wheelInformation = null; - /** * RobotProcessedFeedback batteryLevel. * @member {number} batteryLevel @@ -7752,14 +7272,6 @@ export const proto = $root.proto = (() => { */ RobotProcessedFeedback.prototype.batteryLevel = 0; - /** - * RobotProcessedFeedback signalStrength. - * @member {number} signalStrength - * @memberof proto.RobotProcessedFeedback - * @instance - */ - RobotProcessedFeedback.prototype.signalStrength = 0; - /** * Creates a new RobotProcessedFeedback instance using the specified properties. * @function create @@ -7786,8 +7298,6 @@ export const proto = $root.proto = (() => { writer = $Writer.create(); if (message.ballSensorSeesBall != null && Object.hasOwnProperty.call(message, "ballSensorSeesBall")) writer.uint32(/* id 1, wireType 0 =*/8).bool(message.ballSensorSeesBall); - if (message.ballPosition != null && Object.hasOwnProperty.call(message, "ballPosition")) - writer.uint32(/* id 2, wireType 5 =*/21).float(message.ballPosition); if (message.ballSensorIsWorking != null && Object.hasOwnProperty.call(message, "ballSensorIsWorking")) writer.uint32(/* id 3, wireType 0 =*/24).bool(message.ballSensorIsWorking); if (message.dribblerSeesBall != null && Object.hasOwnProperty.call(message, "dribblerSeesBall")) @@ -7796,12 +7306,8 @@ export const proto = $root.proto = (() => { writer.uint32(/* id 5, wireType 0 =*/40).bool(message.xsensIsCalibrated); if (message.capacitorIsCharged != null && Object.hasOwnProperty.call(message, "capacitorIsCharged")) writer.uint32(/* id 6, wireType 0 =*/48).bool(message.capacitorIsCharged); - if (message.wheelInformation != null && Object.hasOwnProperty.call(message, "wheelInformation")) - $root.proto.RobotWheels.encode(message.wheelInformation, writer.uint32(/* id 7, wireType 2 =*/58).fork()).ldelim(); if (message.batteryLevel != null && Object.hasOwnProperty.call(message, "batteryLevel")) writer.uint32(/* id 8, wireType 5 =*/69).float(message.batteryLevel); - if (message.signalStrength != null && Object.hasOwnProperty.call(message, "signalStrength")) - writer.uint32(/* id 9, wireType 0 =*/72).int32(message.signalStrength); return writer; }; @@ -7840,10 +7346,6 @@ export const proto = $root.proto = (() => { message.ballSensorSeesBall = reader.bool(); break; } - case 2: { - message.ballPosition = reader.float(); - break; - } case 3: { message.ballSensorIsWorking = reader.bool(); break; @@ -7860,18 +7362,10 @@ export const proto = $root.proto = (() => { message.capacitorIsCharged = reader.bool(); break; } - case 7: { - message.wheelInformation = $root.proto.RobotWheels.decode(reader, reader.uint32()); - break; - } case 8: { message.batteryLevel = reader.float(); break; } - case 9: { - message.signalStrength = reader.int32(); - break; - } default: reader.skipType(tag & 7); break; @@ -7910,9 +7404,6 @@ export const proto = $root.proto = (() => { if (message.ballSensorSeesBall != null && message.hasOwnProperty("ballSensorSeesBall")) if (typeof message.ballSensorSeesBall !== "boolean") return "ballSensorSeesBall: boolean expected"; - if (message.ballPosition != null && message.hasOwnProperty("ballPosition")) - if (typeof message.ballPosition !== "number") - return "ballPosition: number expected"; if (message.ballSensorIsWorking != null && message.hasOwnProperty("ballSensorIsWorking")) if (typeof message.ballSensorIsWorking !== "boolean") return "ballSensorIsWorking: boolean expected"; @@ -7925,17 +7416,9 @@ export const proto = $root.proto = (() => { if (message.capacitorIsCharged != null && message.hasOwnProperty("capacitorIsCharged")) if (typeof message.capacitorIsCharged !== "boolean") return "capacitorIsCharged: boolean expected"; - if (message.wheelInformation != null && message.hasOwnProperty("wheelInformation")) { - let error = $root.proto.RobotWheels.verify(message.wheelInformation); - if (error) - return "wheelInformation." + error; - } if (message.batteryLevel != null && message.hasOwnProperty("batteryLevel")) if (typeof message.batteryLevel !== "number") return "batteryLevel: number expected"; - if (message.signalStrength != null && message.hasOwnProperty("signalStrength")) - if (!$util.isInteger(message.signalStrength)) - return "signalStrength: integer expected"; return null; }; @@ -7953,8 +7436,6 @@ export const proto = $root.proto = (() => { let message = new $root.proto.RobotProcessedFeedback(); if (object.ballSensorSeesBall != null) message.ballSensorSeesBall = Boolean(object.ballSensorSeesBall); - if (object.ballPosition != null) - message.ballPosition = Number(object.ballPosition); if (object.ballSensorIsWorking != null) message.ballSensorIsWorking = Boolean(object.ballSensorIsWorking); if (object.dribblerSeesBall != null) @@ -7963,15 +7444,8 @@ export const proto = $root.proto = (() => { message.xsensIsCalibrated = Boolean(object.xsensIsCalibrated); if (object.capacitorIsCharged != null) message.capacitorIsCharged = Boolean(object.capacitorIsCharged); - if (object.wheelInformation != null) { - if (typeof object.wheelInformation !== "object") - throw TypeError(".proto.RobotProcessedFeedback.wheelInformation: object expected"); - message.wheelInformation = $root.proto.RobotWheels.fromObject(object.wheelInformation); - } if (object.batteryLevel != null) message.batteryLevel = Number(object.batteryLevel); - if (object.signalStrength != null) - message.signalStrength = object.signalStrength | 0; return message; }; @@ -7990,19 +7464,14 @@ export const proto = $root.proto = (() => { let object = {}; if (options.defaults) { object.ballSensorSeesBall = false; - object.ballPosition = 0; object.ballSensorIsWorking = false; object.dribblerSeesBall = false; object.xsensIsCalibrated = false; object.capacitorIsCharged = false; - object.wheelInformation = null; object.batteryLevel = 0; - object.signalStrength = 0; } if (message.ballSensorSeesBall != null && message.hasOwnProperty("ballSensorSeesBall")) object.ballSensorSeesBall = message.ballSensorSeesBall; - if (message.ballPosition != null && message.hasOwnProperty("ballPosition")) - object.ballPosition = options.json && !isFinite(message.ballPosition) ? String(message.ballPosition) : message.ballPosition; if (message.ballSensorIsWorking != null && message.hasOwnProperty("ballSensorIsWorking")) object.ballSensorIsWorking = message.ballSensorIsWorking; if (message.dribblerSeesBall != null && message.hasOwnProperty("dribblerSeesBall")) @@ -8011,12 +7480,8 @@ export const proto = $root.proto = (() => { object.xsensIsCalibrated = message.xsensIsCalibrated; if (message.capacitorIsCharged != null && message.hasOwnProperty("capacitorIsCharged")) object.capacitorIsCharged = message.capacitorIsCharged; - if (message.wheelInformation != null && message.hasOwnProperty("wheelInformation")) - object.wheelInformation = $root.proto.RobotWheels.toObject(message.wheelInformation, options); if (message.batteryLevel != null && message.hasOwnProperty("batteryLevel")) object.batteryLevel = options.json && !isFinite(message.batteryLevel) ? String(message.batteryLevel) : message.batteryLevel; - if (message.signalStrength != null && message.hasOwnProperty("signalStrength")) - object.signalStrength = message.signalStrength; return object; }; @@ -8291,7 +7756,7 @@ export const proto = $root.proto = (() => { * @property {number|null} [height] RobotParameters height * @property {number|null} [frontWidth] RobotParameters frontWidth * @property {number|null} [dribblerWidth] RobotParameters dribblerWidth - * @property {number|null} [angleOffset] RobotParameters angleOffset + * @property {number|null} [yawOffset] RobotParameters yawOffset */ /** @@ -8342,12 +7807,12 @@ export const proto = $root.proto = (() => { RobotParameters.prototype.dribblerWidth = 0; /** - * RobotParameters angleOffset. - * @member {number} angleOffset + * RobotParameters yawOffset. + * @member {number} yawOffset * @memberof proto.RobotParameters * @instance */ - RobotParameters.prototype.angleOffset = 0; + RobotParameters.prototype.yawOffset = 0; /** * Creates a new RobotParameters instance using the specified properties. @@ -8381,8 +7846,8 @@ export const proto = $root.proto = (() => { writer.uint32(/* id 3, wireType 5 =*/29).float(message.frontWidth); if (message.dribblerWidth != null && Object.hasOwnProperty.call(message, "dribblerWidth")) writer.uint32(/* id 4, wireType 5 =*/37).float(message.dribblerWidth); - if (message.angleOffset != null && Object.hasOwnProperty.call(message, "angleOffset")) - writer.uint32(/* id 5, wireType 5 =*/45).float(message.angleOffset); + if (message.yawOffset != null && Object.hasOwnProperty.call(message, "yawOffset")) + writer.uint32(/* id 5, wireType 5 =*/45).float(message.yawOffset); return writer; }; @@ -8434,7 +7899,7 @@ export const proto = $root.proto = (() => { break; } case 5: { - message.angleOffset = reader.float(); + message.yawOffset = reader.float(); break; } default: @@ -8484,9 +7949,9 @@ export const proto = $root.proto = (() => { if (message.dribblerWidth != null && message.hasOwnProperty("dribblerWidth")) if (typeof message.dribblerWidth !== "number") return "dribblerWidth: number expected"; - if (message.angleOffset != null && message.hasOwnProperty("angleOffset")) - if (typeof message.angleOffset !== "number") - return "angleOffset: number expected"; + if (message.yawOffset != null && message.hasOwnProperty("yawOffset")) + if (typeof message.yawOffset !== "number") + return "yawOffset: number expected"; return null; }; @@ -8510,8 +7975,8 @@ export const proto = $root.proto = (() => { message.frontWidth = Number(object.frontWidth); if (object.dribblerWidth != null) message.dribblerWidth = Number(object.dribblerWidth); - if (object.angleOffset != null) - message.angleOffset = Number(object.angleOffset); + if (object.yawOffset != null) + message.yawOffset = Number(object.yawOffset); return message; }; @@ -8533,7 +7998,7 @@ export const proto = $root.proto = (() => { object.height = 0; object.frontWidth = 0; object.dribblerWidth = 0; - object.angleOffset = 0; + object.yawOffset = 0; } if (message.radius != null && message.hasOwnProperty("radius")) object.radius = options.json && !isFinite(message.radius) ? String(message.radius) : message.radius; @@ -8543,8 +8008,8 @@ export const proto = $root.proto = (() => { object.frontWidth = options.json && !isFinite(message.frontWidth) ? String(message.frontWidth) : message.frontWidth; if (message.dribblerWidth != null && message.hasOwnProperty("dribblerWidth")) object.dribblerWidth = options.json && !isFinite(message.dribblerWidth) ? String(message.dribblerWidth) : message.dribblerWidth; - if (message.angleOffset != null && message.hasOwnProperty("angleOffset")) - object.angleOffset = options.json && !isFinite(message.angleOffset) ? String(message.angleOffset) : message.angleOffset; + if (message.yawOffset != null && message.hasOwnProperty("yawOffset")) + object.yawOffset = options.json && !isFinite(message.yawOffset) ? String(message.yawOffset) : message.yawOffset; return object; }; @@ -10989,6 +10454,12 @@ export const proto = $root.proto = (() => { * @property {Array.|null} [fieldArcs] SSL_GeometryFieldSize fieldArcs * @property {number|null} [penaltyAreaDepth] SSL_GeometryFieldSize penaltyAreaDepth * @property {number|null} [penaltyAreaWidth] SSL_GeometryFieldSize penaltyAreaWidth + * @property {number|null} [centerCircleRadius] SSL_GeometryFieldSize centerCircleRadius + * @property {number|null} [lineThickness] SSL_GeometryFieldSize lineThickness + * @property {number|null} [goalCenterToPenaltyMark] SSL_GeometryFieldSize goalCenterToPenaltyMark + * @property {number|null} [goalHeight] SSL_GeometryFieldSize goalHeight + * @property {number|null} [ballRadius] SSL_GeometryFieldSize ballRadius + * @property {number|null} [maxRobotRadius] SSL_GeometryFieldSize maxRobotRadius */ /** @@ -11080,6 +10551,54 @@ export const proto = $root.proto = (() => { */ SSL_GeometryFieldSize.prototype.penaltyAreaWidth = 0; + /** + * SSL_GeometryFieldSize centerCircleRadius. + * @member {number} centerCircleRadius + * @memberof proto.SSL_GeometryFieldSize + * @instance + */ + SSL_GeometryFieldSize.prototype.centerCircleRadius = 0; + + /** + * SSL_GeometryFieldSize lineThickness. + * @member {number} lineThickness + * @memberof proto.SSL_GeometryFieldSize + * @instance + */ + SSL_GeometryFieldSize.prototype.lineThickness = 0; + + /** + * SSL_GeometryFieldSize goalCenterToPenaltyMark. + * @member {number} goalCenterToPenaltyMark + * @memberof proto.SSL_GeometryFieldSize + * @instance + */ + SSL_GeometryFieldSize.prototype.goalCenterToPenaltyMark = 0; + + /** + * SSL_GeometryFieldSize goalHeight. + * @member {number} goalHeight + * @memberof proto.SSL_GeometryFieldSize + * @instance + */ + SSL_GeometryFieldSize.prototype.goalHeight = 0; + + /** + * SSL_GeometryFieldSize ballRadius. + * @member {number} ballRadius + * @memberof proto.SSL_GeometryFieldSize + * @instance + */ + SSL_GeometryFieldSize.prototype.ballRadius = 0; + + /** + * SSL_GeometryFieldSize maxRobotRadius. + * @member {number} maxRobotRadius + * @memberof proto.SSL_GeometryFieldSize + * @instance + */ + SSL_GeometryFieldSize.prototype.maxRobotRadius = 0; + /** * Creates a new SSL_GeometryFieldSize instance using the specified properties. * @function create @@ -11119,6 +10638,18 @@ export const proto = $root.proto = (() => { writer.uint32(/* id 8, wireType 0 =*/64).int32(message.penaltyAreaDepth); if (message.penaltyAreaWidth != null && Object.hasOwnProperty.call(message, "penaltyAreaWidth")) writer.uint32(/* id 9, wireType 0 =*/72).int32(message.penaltyAreaWidth); + if (message.centerCircleRadius != null && Object.hasOwnProperty.call(message, "centerCircleRadius")) + writer.uint32(/* id 10, wireType 0 =*/80).int32(message.centerCircleRadius); + if (message.lineThickness != null && Object.hasOwnProperty.call(message, "lineThickness")) + writer.uint32(/* id 11, wireType 0 =*/88).int32(message.lineThickness); + if (message.goalCenterToPenaltyMark != null && Object.hasOwnProperty.call(message, "goalCenterToPenaltyMark")) + writer.uint32(/* id 12, wireType 0 =*/96).int32(message.goalCenterToPenaltyMark); + if (message.goalHeight != null && Object.hasOwnProperty.call(message, "goalHeight")) + writer.uint32(/* id 13, wireType 0 =*/104).int32(message.goalHeight); + if (message.ballRadius != null && Object.hasOwnProperty.call(message, "ballRadius")) + writer.uint32(/* id 14, wireType 5 =*/117).float(message.ballRadius); + if (message.maxRobotRadius != null && Object.hasOwnProperty.call(message, "maxRobotRadius")) + writer.uint32(/* id 15, wireType 5 =*/125).float(message.maxRobotRadius); return writer; }; @@ -11193,6 +10724,30 @@ export const proto = $root.proto = (() => { message.penaltyAreaWidth = reader.int32(); break; } + case 10: { + message.centerCircleRadius = reader.int32(); + break; + } + case 11: { + message.lineThickness = reader.int32(); + break; + } + case 12: { + message.goalCenterToPenaltyMark = reader.int32(); + break; + } + case 13: { + message.goalHeight = reader.int32(); + break; + } + case 14: { + message.ballRadius = reader.float(); + break; + } + case 15: { + message.maxRobotRadius = reader.float(); + break; + } default: reader.skipType(tag & 7); break; @@ -11272,6 +10827,24 @@ export const proto = $root.proto = (() => { if (message.penaltyAreaWidth != null && message.hasOwnProperty("penaltyAreaWidth")) if (!$util.isInteger(message.penaltyAreaWidth)) return "penaltyAreaWidth: integer expected"; + if (message.centerCircleRadius != null && message.hasOwnProperty("centerCircleRadius")) + if (!$util.isInteger(message.centerCircleRadius)) + return "centerCircleRadius: integer expected"; + if (message.lineThickness != null && message.hasOwnProperty("lineThickness")) + if (!$util.isInteger(message.lineThickness)) + return "lineThickness: integer expected"; + if (message.goalCenterToPenaltyMark != null && message.hasOwnProperty("goalCenterToPenaltyMark")) + if (!$util.isInteger(message.goalCenterToPenaltyMark)) + return "goalCenterToPenaltyMark: integer expected"; + if (message.goalHeight != null && message.hasOwnProperty("goalHeight")) + if (!$util.isInteger(message.goalHeight)) + return "goalHeight: integer expected"; + if (message.ballRadius != null && message.hasOwnProperty("ballRadius")) + if (typeof message.ballRadius !== "number") + return "ballRadius: number expected"; + if (message.maxRobotRadius != null && message.hasOwnProperty("maxRobotRadius")) + if (typeof message.maxRobotRadius !== "number") + return "maxRobotRadius: number expected"; return null; }; @@ -11321,6 +10894,18 @@ export const proto = $root.proto = (() => { message.penaltyAreaDepth = object.penaltyAreaDepth | 0; if (object.penaltyAreaWidth != null) message.penaltyAreaWidth = object.penaltyAreaWidth | 0; + if (object.centerCircleRadius != null) + message.centerCircleRadius = object.centerCircleRadius | 0; + if (object.lineThickness != null) + message.lineThickness = object.lineThickness | 0; + if (object.goalCenterToPenaltyMark != null) + message.goalCenterToPenaltyMark = object.goalCenterToPenaltyMark | 0; + if (object.goalHeight != null) + message.goalHeight = object.goalHeight | 0; + if (object.ballRadius != null) + message.ballRadius = Number(object.ballRadius); + if (object.maxRobotRadius != null) + message.maxRobotRadius = Number(object.maxRobotRadius); return message; }; @@ -11349,6 +10934,12 @@ export const proto = $root.proto = (() => { object.boundaryWidth = 0; object.penaltyAreaDepth = 0; object.penaltyAreaWidth = 0; + object.centerCircleRadius = 0; + object.lineThickness = 0; + object.goalCenterToPenaltyMark = 0; + object.goalHeight = 0; + object.ballRadius = 0; + object.maxRobotRadius = 0; } if (message.fieldLength != null && message.hasOwnProperty("fieldLength")) object.fieldLength = message.fieldLength; @@ -11374,6 +10965,18 @@ export const proto = $root.proto = (() => { object.penaltyAreaDepth = message.penaltyAreaDepth; if (message.penaltyAreaWidth != null && message.hasOwnProperty("penaltyAreaWidth")) object.penaltyAreaWidth = message.penaltyAreaWidth; + if (message.centerCircleRadius != null && message.hasOwnProperty("centerCircleRadius")) + object.centerCircleRadius = message.centerCircleRadius; + if (message.lineThickness != null && message.hasOwnProperty("lineThickness")) + object.lineThickness = message.lineThickness; + if (message.goalCenterToPenaltyMark != null && message.hasOwnProperty("goalCenterToPenaltyMark")) + object.goalCenterToPenaltyMark = message.goalCenterToPenaltyMark; + if (message.goalHeight != null && message.hasOwnProperty("goalHeight")) + object.goalHeight = message.goalHeight; + if (message.ballRadius != null && message.hasOwnProperty("ballRadius")) + object.ballRadius = options.json && !isFinite(message.ballRadius) ? String(message.ballRadius) : message.ballRadius; + if (message.maxRobotRadius != null && message.hasOwnProperty("maxRobotRadius")) + object.maxRobotRadius = options.json && !isFinite(message.maxRobotRadius) ? String(message.maxRobotRadius) : message.maxRobotRadius; return object; }; @@ -11978,26 +11581,26 @@ export const proto = $root.proto = (() => { return SSL_GeometryCameraCalibration; })(); - proto.SSL_GeometryData = (function() { + proto.SSL_BallModelStraightTwoPhase = (function() { /** - * Properties of a SSL_GeometryData. + * Properties of a SSL_BallModelStraightTwoPhase. * @memberof proto - * @interface ISSL_GeometryData - * @property {proto.ISSL_GeometryFieldSize} field SSL_GeometryData field - * @property {Array.|null} [calib] SSL_GeometryData calib + * @interface ISSL_BallModelStraightTwoPhase + * @property {number} accSlide SSL_BallModelStraightTwoPhase accSlide + * @property {number} accRoll SSL_BallModelStraightTwoPhase accRoll + * @property {number} kSwitch SSL_BallModelStraightTwoPhase kSwitch */ /** - * Constructs a new SSL_GeometryData. + * Constructs a new SSL_BallModelStraightTwoPhase. * @memberof proto - * @classdesc Represents a SSL_GeometryData. - * @implements ISSL_GeometryData + * @classdesc Represents a SSL_BallModelStraightTwoPhase. + * @implements ISSL_BallModelStraightTwoPhase * @constructor - * @param {proto.ISSL_GeometryData=} [properties] Properties to set + * @param {proto.ISSL_BallModelStraightTwoPhase=} [properties] Properties to set */ - function SSL_GeometryData(properties) { - this.calib = []; + function SSL_BallModelStraightTwoPhase(properties) { if (properties) for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) if (properties[keys[i]] != null) @@ -12005,91 +11608,100 @@ export const proto = $root.proto = (() => { } /** - * SSL_GeometryData field. - * @member {proto.ISSL_GeometryFieldSize} field - * @memberof proto.SSL_GeometryData + * SSL_BallModelStraightTwoPhase accSlide. + * @member {number} accSlide + * @memberof proto.SSL_BallModelStraightTwoPhase * @instance */ - SSL_GeometryData.prototype.field = null; + SSL_BallModelStraightTwoPhase.prototype.accSlide = 0; /** - * SSL_GeometryData calib. - * @member {Array.} calib - * @memberof proto.SSL_GeometryData + * SSL_BallModelStraightTwoPhase accRoll. + * @member {number} accRoll + * @memberof proto.SSL_BallModelStraightTwoPhase * @instance */ - SSL_GeometryData.prototype.calib = $util.emptyArray; + SSL_BallModelStraightTwoPhase.prototype.accRoll = 0; /** - * Creates a new SSL_GeometryData instance using the specified properties. + * SSL_BallModelStraightTwoPhase kSwitch. + * @member {number} kSwitch + * @memberof proto.SSL_BallModelStraightTwoPhase + * @instance + */ + SSL_BallModelStraightTwoPhase.prototype.kSwitch = 0; + + /** + * Creates a new SSL_BallModelStraightTwoPhase instance using the specified properties. * @function create - * @memberof proto.SSL_GeometryData + * @memberof proto.SSL_BallModelStraightTwoPhase * @static - * @param {proto.ISSL_GeometryData=} [properties] Properties to set - * @returns {proto.SSL_GeometryData} SSL_GeometryData instance + * @param {proto.ISSL_BallModelStraightTwoPhase=} [properties] Properties to set + * @returns {proto.SSL_BallModelStraightTwoPhase} SSL_BallModelStraightTwoPhase instance */ - SSL_GeometryData.create = function create(properties) { - return new SSL_GeometryData(properties); + SSL_BallModelStraightTwoPhase.create = function create(properties) { + return new SSL_BallModelStraightTwoPhase(properties); }; /** - * Encodes the specified SSL_GeometryData message. Does not implicitly {@link proto.SSL_GeometryData.verify|verify} messages. + * Encodes the specified SSL_BallModelStraightTwoPhase message. Does not implicitly {@link proto.SSL_BallModelStraightTwoPhase.verify|verify} messages. * @function encode - * @memberof proto.SSL_GeometryData + * @memberof proto.SSL_BallModelStraightTwoPhase * @static - * @param {proto.ISSL_GeometryData} message SSL_GeometryData message or plain object to encode + * @param {proto.ISSL_BallModelStraightTwoPhase} message SSL_BallModelStraightTwoPhase message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ - SSL_GeometryData.encode = function encode(message, writer) { + SSL_BallModelStraightTwoPhase.encode = function encode(message, writer) { if (!writer) writer = $Writer.create(); - $root.proto.SSL_GeometryFieldSize.encode(message.field, writer.uint32(/* id 1, wireType 2 =*/10).fork()).ldelim(); - if (message.calib != null && message.calib.length) - for (let i = 0; i < message.calib.length; ++i) - $root.proto.SSL_GeometryCameraCalibration.encode(message.calib[i], writer.uint32(/* id 2, wireType 2 =*/18).fork()).ldelim(); + writer.uint32(/* id 1, wireType 1 =*/9).double(message.accSlide); + writer.uint32(/* id 2, wireType 1 =*/17).double(message.accRoll); + writer.uint32(/* id 3, wireType 1 =*/25).double(message.kSwitch); return writer; }; /** - * Encodes the specified SSL_GeometryData message, length delimited. Does not implicitly {@link proto.SSL_GeometryData.verify|verify} messages. + * Encodes the specified SSL_BallModelStraightTwoPhase message, length delimited. Does not implicitly {@link proto.SSL_BallModelStraightTwoPhase.verify|verify} messages. * @function encodeDelimited - * @memberof proto.SSL_GeometryData + * @memberof proto.SSL_BallModelStraightTwoPhase * @static - * @param {proto.ISSL_GeometryData} message SSL_GeometryData message or plain object to encode + * @param {proto.ISSL_BallModelStraightTwoPhase} message SSL_BallModelStraightTwoPhase message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ - SSL_GeometryData.encodeDelimited = function encodeDelimited(message, writer) { + SSL_BallModelStraightTwoPhase.encodeDelimited = function encodeDelimited(message, writer) { return this.encode(message, writer).ldelim(); }; /** - * Decodes a SSL_GeometryData message from the specified reader or buffer. + * Decodes a SSL_BallModelStraightTwoPhase message from the specified reader or buffer. * @function decode - * @memberof proto.SSL_GeometryData + * @memberof proto.SSL_BallModelStraightTwoPhase * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from * @param {number} [length] Message length if known beforehand - * @returns {proto.SSL_GeometryData} SSL_GeometryData + * @returns {proto.SSL_BallModelStraightTwoPhase} SSL_BallModelStraightTwoPhase * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - SSL_GeometryData.decode = function decode(reader, length) { + SSL_BallModelStraightTwoPhase.decode = function decode(reader, length) { if (!(reader instanceof $Reader)) reader = $Reader.create(reader); - let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.SSL_GeometryData(); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.SSL_BallModelStraightTwoPhase(); while (reader.pos < end) { let tag = reader.uint32(); switch (tag >>> 3) { case 1: { - message.field = $root.proto.SSL_GeometryFieldSize.decode(reader, reader.uint32()); + message.accSlide = reader.double(); break; } case 2: { - if (!(message.calib && message.calib.length)) - message.calib = []; - message.calib.push($root.proto.SSL_GeometryCameraCalibration.decode(reader, reader.uint32())); + message.accRoll = reader.double(); + break; + } + case 3: { + message.kSwitch = reader.double(); break; } default: @@ -12097,212 +11709,148 @@ export const proto = $root.proto = (() => { break; } } - if (!message.hasOwnProperty("field")) - throw $util.ProtocolError("missing required 'field'", { instance: message }); + if (!message.hasOwnProperty("accSlide")) + throw $util.ProtocolError("missing required 'accSlide'", { instance: message }); + if (!message.hasOwnProperty("accRoll")) + throw $util.ProtocolError("missing required 'accRoll'", { instance: message }); + if (!message.hasOwnProperty("kSwitch")) + throw $util.ProtocolError("missing required 'kSwitch'", { instance: message }); return message; }; /** - * Decodes a SSL_GeometryData message from the specified reader or buffer, length delimited. + * Decodes a SSL_BallModelStraightTwoPhase message from the specified reader or buffer, length delimited. * @function decodeDelimited - * @memberof proto.SSL_GeometryData + * @memberof proto.SSL_BallModelStraightTwoPhase * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @returns {proto.SSL_GeometryData} SSL_GeometryData + * @returns {proto.SSL_BallModelStraightTwoPhase} SSL_BallModelStraightTwoPhase * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - SSL_GeometryData.decodeDelimited = function decodeDelimited(reader) { + SSL_BallModelStraightTwoPhase.decodeDelimited = function decodeDelimited(reader) { if (!(reader instanceof $Reader)) reader = new $Reader(reader); return this.decode(reader, reader.uint32()); }; /** - * Verifies a SSL_GeometryData message. + * Verifies a SSL_BallModelStraightTwoPhase message. * @function verify - * @memberof proto.SSL_GeometryData + * @memberof proto.SSL_BallModelStraightTwoPhase * @static * @param {Object.} message Plain object to verify * @returns {string|null} `null` if valid, otherwise the reason why it is not */ - SSL_GeometryData.verify = function verify(message) { + SSL_BallModelStraightTwoPhase.verify = function verify(message) { if (typeof message !== "object" || message === null) return "object expected"; - { - let error = $root.proto.SSL_GeometryFieldSize.verify(message.field); - if (error) - return "field." + error; - } - if (message.calib != null && message.hasOwnProperty("calib")) { - if (!Array.isArray(message.calib)) - return "calib: array expected"; - for (let i = 0; i < message.calib.length; ++i) { - let error = $root.proto.SSL_GeometryCameraCalibration.verify(message.calib[i]); - if (error) - return "calib." + error; - } - } + if (typeof message.accSlide !== "number") + return "accSlide: number expected"; + if (typeof message.accRoll !== "number") + return "accRoll: number expected"; + if (typeof message.kSwitch !== "number") + return "kSwitch: number expected"; return null; }; /** - * Creates a SSL_GeometryData message from a plain object. Also converts values to their respective internal types. + * Creates a SSL_BallModelStraightTwoPhase message from a plain object. Also converts values to their respective internal types. * @function fromObject - * @memberof proto.SSL_GeometryData + * @memberof proto.SSL_BallModelStraightTwoPhase * @static * @param {Object.} object Plain object - * @returns {proto.SSL_GeometryData} SSL_GeometryData + * @returns {proto.SSL_BallModelStraightTwoPhase} SSL_BallModelStraightTwoPhase */ - SSL_GeometryData.fromObject = function fromObject(object) { - if (object instanceof $root.proto.SSL_GeometryData) + SSL_BallModelStraightTwoPhase.fromObject = function fromObject(object) { + if (object instanceof $root.proto.SSL_BallModelStraightTwoPhase) return object; - let message = new $root.proto.SSL_GeometryData(); - if (object.field != null) { - if (typeof object.field !== "object") - throw TypeError(".proto.SSL_GeometryData.field: object expected"); - message.field = $root.proto.SSL_GeometryFieldSize.fromObject(object.field); - } - if (object.calib) { - if (!Array.isArray(object.calib)) - throw TypeError(".proto.SSL_GeometryData.calib: array expected"); - message.calib = []; - for (let i = 0; i < object.calib.length; ++i) { - if (typeof object.calib[i] !== "object") - throw TypeError(".proto.SSL_GeometryData.calib: object expected"); - message.calib[i] = $root.proto.SSL_GeometryCameraCalibration.fromObject(object.calib[i]); - } - } + let message = new $root.proto.SSL_BallModelStraightTwoPhase(); + if (object.accSlide != null) + message.accSlide = Number(object.accSlide); + if (object.accRoll != null) + message.accRoll = Number(object.accRoll); + if (object.kSwitch != null) + message.kSwitch = Number(object.kSwitch); return message; }; /** - * Creates a plain object from a SSL_GeometryData message. Also converts values to other types if specified. + * Creates a plain object from a SSL_BallModelStraightTwoPhase message. Also converts values to other types if specified. * @function toObject - * @memberof proto.SSL_GeometryData + * @memberof proto.SSL_BallModelStraightTwoPhase * @static - * @param {proto.SSL_GeometryData} message SSL_GeometryData + * @param {proto.SSL_BallModelStraightTwoPhase} message SSL_BallModelStraightTwoPhase * @param {$protobuf.IConversionOptions} [options] Conversion options * @returns {Object.} Plain object */ - SSL_GeometryData.toObject = function toObject(message, options) { + SSL_BallModelStraightTwoPhase.toObject = function toObject(message, options) { if (!options) options = {}; let object = {}; - if (options.arrays || options.defaults) - object.calib = []; - if (options.defaults) - object.field = null; - if (message.field != null && message.hasOwnProperty("field")) - object.field = $root.proto.SSL_GeometryFieldSize.toObject(message.field, options); - if (message.calib && message.calib.length) { - object.calib = []; - for (let j = 0; j < message.calib.length; ++j) - object.calib[j] = $root.proto.SSL_GeometryCameraCalibration.toObject(message.calib[j], options); - } + if (options.defaults) { + object.accSlide = 0; + object.accRoll = 0; + object.kSwitch = 0; + } + if (message.accSlide != null && message.hasOwnProperty("accSlide")) + object.accSlide = options.json && !isFinite(message.accSlide) ? String(message.accSlide) : message.accSlide; + if (message.accRoll != null && message.hasOwnProperty("accRoll")) + object.accRoll = options.json && !isFinite(message.accRoll) ? String(message.accRoll) : message.accRoll; + if (message.kSwitch != null && message.hasOwnProperty("kSwitch")) + object.kSwitch = options.json && !isFinite(message.kSwitch) ? String(message.kSwitch) : message.kSwitch; return object; }; /** - * Converts this SSL_GeometryData to JSON. + * Converts this SSL_BallModelStraightTwoPhase to JSON. * @function toJSON - * @memberof proto.SSL_GeometryData + * @memberof proto.SSL_BallModelStraightTwoPhase * @instance * @returns {Object.} JSON object */ - SSL_GeometryData.prototype.toJSON = function toJSON() { + SSL_BallModelStraightTwoPhase.prototype.toJSON = function toJSON() { return this.constructor.toObject(this, $protobuf.util.toJSONOptions); }; /** - * Gets the default type url for SSL_GeometryData + * Gets the default type url for SSL_BallModelStraightTwoPhase * @function getTypeUrl - * @memberof proto.SSL_GeometryData + * @memberof proto.SSL_BallModelStraightTwoPhase * @static * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns {string} The default type url */ - SSL_GeometryData.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + SSL_BallModelStraightTwoPhase.getTypeUrl = function getTypeUrl(typeUrlPrefix) { if (typeUrlPrefix === undefined) { typeUrlPrefix = "type.googleapis.com"; } - return typeUrlPrefix + "/proto.SSL_GeometryData"; + return typeUrlPrefix + "/proto.SSL_BallModelStraightTwoPhase"; }; - return SSL_GeometryData; - })(); - - /** - * SSL_FieldShapeType enum. - * @name proto.SSL_FieldShapeType - * @enum {number} - * @property {number} Undefined=0 Undefined value - * @property {number} CenterCircle=1 CenterCircle value - * @property {number} TopTouchLine=2 TopTouchLine value - * @property {number} BottomTouchLine=3 BottomTouchLine value - * @property {number} LeftGoalLine=4 LeftGoalLine value - * @property {number} RightGoalLine=5 RightGoalLine value - * @property {number} HalfwayLine=6 HalfwayLine value - * @property {number} CenterLine=7 CenterLine value - * @property {number} LeftPenaltyStretch=8 LeftPenaltyStretch value - * @property {number} RightPenaltyStretch=9 RightPenaltyStretch value - * @property {number} LeftFieldLeftPenaltyStretch=10 LeftFieldLeftPenaltyStretch value - * @property {number} LeftFieldRightPenaltyStretch=11 LeftFieldRightPenaltyStretch value - * @property {number} RightFieldLeftPenaltyStretch=12 RightFieldLeftPenaltyStretch value - * @property {number} RightFieldRightPenaltyStretch=13 RightFieldRightPenaltyStretch value - */ - proto.SSL_FieldShapeType = (function() { - const valuesById = {}, values = Object.create(valuesById); - values[valuesById[0] = "Undefined"] = 0; - values[valuesById[1] = "CenterCircle"] = 1; - values[valuesById[2] = "TopTouchLine"] = 2; - values[valuesById[3] = "BottomTouchLine"] = 3; - values[valuesById[4] = "LeftGoalLine"] = 4; - values[valuesById[5] = "RightGoalLine"] = 5; - values[valuesById[6] = "HalfwayLine"] = 6; - values[valuesById[7] = "CenterLine"] = 7; - values[valuesById[8] = "LeftPenaltyStretch"] = 8; - values[valuesById[9] = "RightPenaltyStretch"] = 9; - values[valuesById[10] = "LeftFieldLeftPenaltyStretch"] = 10; - values[valuesById[11] = "LeftFieldRightPenaltyStretch"] = 11; - values[valuesById[12] = "RightFieldLeftPenaltyStretch"] = 12; - values[valuesById[13] = "RightFieldRightPenaltyStretch"] = 13; - return values; + return SSL_BallModelStraightTwoPhase; })(); - proto.SSL_Referee = (function() { + proto.SSL_BallModelChipFixedLoss = (function() { /** - * Properties of a SSL_Referee. + * Properties of a SSL_BallModelChipFixedLoss. * @memberof proto - * @interface ISSL_Referee - * @property {number|Long} packetTimestamp SSL_Referee packetTimestamp - * @property {proto.SSL_Referee.Stage} stage SSL_Referee stage - * @property {number|null} [stageTimeLeft] SSL_Referee stageTimeLeft - * @property {proto.SSL_Referee.Command} command SSL_Referee command - * @property {number} commandCounter SSL_Referee commandCounter - * @property {number|Long} commandTimestamp SSL_Referee commandTimestamp - * @property {proto.SSL_Referee.ITeamInfo} yellow SSL_Referee yellow - * @property {proto.SSL_Referee.ITeamInfo} blue SSL_Referee blue - * @property {proto.SSL_Referee.IPoint|null} [designatedPosition] SSL_Referee designatedPosition - * @property {boolean|null} [blueTeamOnPositiveHalf] SSL_Referee blueTeamOnPositiveHalf - * @property {proto.SSL_Referee.Command|null} [nextCommand] SSL_Referee nextCommand - * @property {Array.|null} [gameEvents] SSL_Referee gameEvents - * @property {Array.|null} [gameEventProposals] SSL_Referee gameEventProposals - * @property {number|null} [currentActionTimeRemaining] SSL_Referee currentActionTimeRemaining - */ - - /** - * Constructs a new SSL_Referee. + * @interface ISSL_BallModelChipFixedLoss + * @property {number} dampingXyFirstHop SSL_BallModelChipFixedLoss dampingXyFirstHop + * @property {number} dampingXyOtherHops SSL_BallModelChipFixedLoss dampingXyOtherHops + * @property {number} dampingZ SSL_BallModelChipFixedLoss dampingZ + */ + + /** + * Constructs a new SSL_BallModelChipFixedLoss. * @memberof proto - * @classdesc Represents a SSL_Referee. - * @implements ISSL_Referee + * @classdesc Represents a SSL_BallModelChipFixedLoss. + * @implements ISSL_BallModelChipFixedLoss * @constructor - * @param {proto.ISSL_Referee=} [properties] Properties to set + * @param {proto.ISSL_BallModelChipFixedLoss=} [properties] Properties to set */ - function SSL_Referee(properties) { - this.gameEvents = []; - this.gameEventProposals = []; + function SSL_BallModelChipFixedLoss(properties) { if (properties) for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) if (properties[keys[i]] != null) @@ -12310,256 +11858,100 @@ export const proto = $root.proto = (() => { } /** - * SSL_Referee packetTimestamp. - * @member {number|Long} packetTimestamp - * @memberof proto.SSL_Referee - * @instance - */ - SSL_Referee.prototype.packetTimestamp = $util.Long ? $util.Long.fromBits(0,0,true) : 0; - - /** - * SSL_Referee stage. - * @member {proto.SSL_Referee.Stage} stage - * @memberof proto.SSL_Referee - * @instance - */ - SSL_Referee.prototype.stage = 0; - - /** - * SSL_Referee stageTimeLeft. - * @member {number} stageTimeLeft - * @memberof proto.SSL_Referee - * @instance - */ - SSL_Referee.prototype.stageTimeLeft = 0; - - /** - * SSL_Referee command. - * @member {proto.SSL_Referee.Command} command - * @memberof proto.SSL_Referee - * @instance - */ - SSL_Referee.prototype.command = 0; - - /** - * SSL_Referee commandCounter. - * @member {number} commandCounter - * @memberof proto.SSL_Referee - * @instance - */ - SSL_Referee.prototype.commandCounter = 0; - - /** - * SSL_Referee commandTimestamp. - * @member {number|Long} commandTimestamp - * @memberof proto.SSL_Referee - * @instance - */ - SSL_Referee.prototype.commandTimestamp = $util.Long ? $util.Long.fromBits(0,0,true) : 0; - - /** - * SSL_Referee yellow. - * @member {proto.SSL_Referee.ITeamInfo} yellow - * @memberof proto.SSL_Referee - * @instance - */ - SSL_Referee.prototype.yellow = null; - - /** - * SSL_Referee blue. - * @member {proto.SSL_Referee.ITeamInfo} blue - * @memberof proto.SSL_Referee - * @instance - */ - SSL_Referee.prototype.blue = null; - - /** - * SSL_Referee designatedPosition. - * @member {proto.SSL_Referee.IPoint|null|undefined} designatedPosition - * @memberof proto.SSL_Referee - * @instance - */ - SSL_Referee.prototype.designatedPosition = null; - - /** - * SSL_Referee blueTeamOnPositiveHalf. - * @member {boolean} blueTeamOnPositiveHalf - * @memberof proto.SSL_Referee - * @instance - */ - SSL_Referee.prototype.blueTeamOnPositiveHalf = false; - - /** - * SSL_Referee nextCommand. - * @member {proto.SSL_Referee.Command} nextCommand - * @memberof proto.SSL_Referee + * SSL_BallModelChipFixedLoss dampingXyFirstHop. + * @member {number} dampingXyFirstHop + * @memberof proto.SSL_BallModelChipFixedLoss * @instance */ - SSL_Referee.prototype.nextCommand = 0; + SSL_BallModelChipFixedLoss.prototype.dampingXyFirstHop = 0; /** - * SSL_Referee gameEvents. - * @member {Array.} gameEvents - * @memberof proto.SSL_Referee + * SSL_BallModelChipFixedLoss dampingXyOtherHops. + * @member {number} dampingXyOtherHops + * @memberof proto.SSL_BallModelChipFixedLoss * @instance */ - SSL_Referee.prototype.gameEvents = $util.emptyArray; + SSL_BallModelChipFixedLoss.prototype.dampingXyOtherHops = 0; /** - * SSL_Referee gameEventProposals. - * @member {Array.} gameEventProposals - * @memberof proto.SSL_Referee + * SSL_BallModelChipFixedLoss dampingZ. + * @member {number} dampingZ + * @memberof proto.SSL_BallModelChipFixedLoss * @instance */ - SSL_Referee.prototype.gameEventProposals = $util.emptyArray; + SSL_BallModelChipFixedLoss.prototype.dampingZ = 0; /** - * SSL_Referee currentActionTimeRemaining. - * @member {number} currentActionTimeRemaining - * @memberof proto.SSL_Referee - * @instance - */ - SSL_Referee.prototype.currentActionTimeRemaining = 0; - - /** - * Creates a new SSL_Referee instance using the specified properties. + * Creates a new SSL_BallModelChipFixedLoss instance using the specified properties. * @function create - * @memberof proto.SSL_Referee + * @memberof proto.SSL_BallModelChipFixedLoss * @static - * @param {proto.ISSL_Referee=} [properties] Properties to set - * @returns {proto.SSL_Referee} SSL_Referee instance + * @param {proto.ISSL_BallModelChipFixedLoss=} [properties] Properties to set + * @returns {proto.SSL_BallModelChipFixedLoss} SSL_BallModelChipFixedLoss instance */ - SSL_Referee.create = function create(properties) { - return new SSL_Referee(properties); + SSL_BallModelChipFixedLoss.create = function create(properties) { + return new SSL_BallModelChipFixedLoss(properties); }; /** - * Encodes the specified SSL_Referee message. Does not implicitly {@link proto.SSL_Referee.verify|verify} messages. + * Encodes the specified SSL_BallModelChipFixedLoss message. Does not implicitly {@link proto.SSL_BallModelChipFixedLoss.verify|verify} messages. * @function encode - * @memberof proto.SSL_Referee + * @memberof proto.SSL_BallModelChipFixedLoss * @static - * @param {proto.ISSL_Referee} message SSL_Referee message or plain object to encode + * @param {proto.ISSL_BallModelChipFixedLoss} message SSL_BallModelChipFixedLoss message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ - SSL_Referee.encode = function encode(message, writer) { + SSL_BallModelChipFixedLoss.encode = function encode(message, writer) { if (!writer) writer = $Writer.create(); - writer.uint32(/* id 1, wireType 0 =*/8).uint64(message.packetTimestamp); - writer.uint32(/* id 2, wireType 0 =*/16).int32(message.stage); - if (message.stageTimeLeft != null && Object.hasOwnProperty.call(message, "stageTimeLeft")) - writer.uint32(/* id 3, wireType 0 =*/24).sint32(message.stageTimeLeft); - writer.uint32(/* id 4, wireType 0 =*/32).int32(message.command); - writer.uint32(/* id 5, wireType 0 =*/40).uint32(message.commandCounter); - writer.uint32(/* id 6, wireType 0 =*/48).uint64(message.commandTimestamp); - $root.proto.SSL_Referee.TeamInfo.encode(message.yellow, writer.uint32(/* id 7, wireType 2 =*/58).fork()).ldelim(); - $root.proto.SSL_Referee.TeamInfo.encode(message.blue, writer.uint32(/* id 8, wireType 2 =*/66).fork()).ldelim(); - if (message.designatedPosition != null && Object.hasOwnProperty.call(message, "designatedPosition")) - $root.proto.SSL_Referee.Point.encode(message.designatedPosition, writer.uint32(/* id 9, wireType 2 =*/74).fork()).ldelim(); - if (message.blueTeamOnPositiveHalf != null && Object.hasOwnProperty.call(message, "blueTeamOnPositiveHalf")) - writer.uint32(/* id 10, wireType 0 =*/80).bool(message.blueTeamOnPositiveHalf); - if (message.nextCommand != null && Object.hasOwnProperty.call(message, "nextCommand")) - writer.uint32(/* id 12, wireType 0 =*/96).int32(message.nextCommand); - if (message.currentActionTimeRemaining != null && Object.hasOwnProperty.call(message, "currentActionTimeRemaining")) - writer.uint32(/* id 15, wireType 0 =*/120).int32(message.currentActionTimeRemaining); - if (message.gameEvents != null && message.gameEvents.length) - for (let i = 0; i < message.gameEvents.length; ++i) - $root.proto.GameEvent.encode(message.gameEvents[i], writer.uint32(/* id 16, wireType 2 =*/130).fork()).ldelim(); - if (message.gameEventProposals != null && message.gameEventProposals.length) - for (let i = 0; i < message.gameEventProposals.length; ++i) - $root.proto.GameEventProposalGroup.encode(message.gameEventProposals[i], writer.uint32(/* id 17, wireType 2 =*/138).fork()).ldelim(); + writer.uint32(/* id 1, wireType 1 =*/9).double(message.dampingXyFirstHop); + writer.uint32(/* id 2, wireType 1 =*/17).double(message.dampingXyOtherHops); + writer.uint32(/* id 3, wireType 1 =*/25).double(message.dampingZ); return writer; }; /** - * Encodes the specified SSL_Referee message, length delimited. Does not implicitly {@link proto.SSL_Referee.verify|verify} messages. + * Encodes the specified SSL_BallModelChipFixedLoss message, length delimited. Does not implicitly {@link proto.SSL_BallModelChipFixedLoss.verify|verify} messages. * @function encodeDelimited - * @memberof proto.SSL_Referee + * @memberof proto.SSL_BallModelChipFixedLoss * @static - * @param {proto.ISSL_Referee} message SSL_Referee message or plain object to encode + * @param {proto.ISSL_BallModelChipFixedLoss} message SSL_BallModelChipFixedLoss message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ - SSL_Referee.encodeDelimited = function encodeDelimited(message, writer) { + SSL_BallModelChipFixedLoss.encodeDelimited = function encodeDelimited(message, writer) { return this.encode(message, writer).ldelim(); }; /** - * Decodes a SSL_Referee message from the specified reader or buffer. + * Decodes a SSL_BallModelChipFixedLoss message from the specified reader or buffer. * @function decode - * @memberof proto.SSL_Referee + * @memberof proto.SSL_BallModelChipFixedLoss * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from * @param {number} [length] Message length if known beforehand - * @returns {proto.SSL_Referee} SSL_Referee + * @returns {proto.SSL_BallModelChipFixedLoss} SSL_BallModelChipFixedLoss * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - SSL_Referee.decode = function decode(reader, length) { + SSL_BallModelChipFixedLoss.decode = function decode(reader, length) { if (!(reader instanceof $Reader)) reader = $Reader.create(reader); - let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.SSL_Referee(); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.SSL_BallModelChipFixedLoss(); while (reader.pos < end) { let tag = reader.uint32(); switch (tag >>> 3) { case 1: { - message.packetTimestamp = reader.uint64(); + message.dampingXyFirstHop = reader.double(); break; } case 2: { - message.stage = reader.int32(); + message.dampingXyOtherHops = reader.double(); break; } case 3: { - message.stageTimeLeft = reader.sint32(); - break; - } - case 4: { - message.command = reader.int32(); - break; - } - case 5: { - message.commandCounter = reader.uint32(); - break; - } - case 6: { - message.commandTimestamp = reader.uint64(); - break; - } - case 7: { - message.yellow = $root.proto.SSL_Referee.TeamInfo.decode(reader, reader.uint32()); - break; - } - case 8: { - message.blue = $root.proto.SSL_Referee.TeamInfo.decode(reader, reader.uint32()); - break; - } - case 9: { - message.designatedPosition = $root.proto.SSL_Referee.Point.decode(reader, reader.uint32()); - break; - } - case 10: { - message.blueTeamOnPositiveHalf = reader.bool(); - break; - } - case 12: { - message.nextCommand = reader.int32(); - break; - } - case 16: { - if (!(message.gameEvents && message.gameEvents.length)) - message.gameEvents = []; - message.gameEvents.push($root.proto.GameEvent.decode(reader, reader.uint32())); - break; - } - case 17: { - if (!(message.gameEventProposals && message.gameEventProposals.length)) - message.gameEventProposals = []; - message.gameEventProposals.push($root.proto.GameEventProposalGroup.decode(reader, reader.uint32())); - break; - } - case 15: { - message.currentActionTimeRemaining = reader.int32(); + message.dampingZ = reader.double(); break; } default: @@ -12567,615 +11959,1696 @@ export const proto = $root.proto = (() => { break; } } - if (!message.hasOwnProperty("packetTimestamp")) - throw $util.ProtocolError("missing required 'packetTimestamp'", { instance: message }); - if (!message.hasOwnProperty("stage")) - throw $util.ProtocolError("missing required 'stage'", { instance: message }); - if (!message.hasOwnProperty("command")) - throw $util.ProtocolError("missing required 'command'", { instance: message }); - if (!message.hasOwnProperty("commandCounter")) - throw $util.ProtocolError("missing required 'commandCounter'", { instance: message }); - if (!message.hasOwnProperty("commandTimestamp")) - throw $util.ProtocolError("missing required 'commandTimestamp'", { instance: message }); - if (!message.hasOwnProperty("yellow")) - throw $util.ProtocolError("missing required 'yellow'", { instance: message }); - if (!message.hasOwnProperty("blue")) - throw $util.ProtocolError("missing required 'blue'", { instance: message }); + if (!message.hasOwnProperty("dampingXyFirstHop")) + throw $util.ProtocolError("missing required 'dampingXyFirstHop'", { instance: message }); + if (!message.hasOwnProperty("dampingXyOtherHops")) + throw $util.ProtocolError("missing required 'dampingXyOtherHops'", { instance: message }); + if (!message.hasOwnProperty("dampingZ")) + throw $util.ProtocolError("missing required 'dampingZ'", { instance: message }); return message; }; /** - * Decodes a SSL_Referee message from the specified reader or buffer, length delimited. + * Decodes a SSL_BallModelChipFixedLoss message from the specified reader or buffer, length delimited. * @function decodeDelimited - * @memberof proto.SSL_Referee + * @memberof proto.SSL_BallModelChipFixedLoss * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @returns {proto.SSL_Referee} SSL_Referee + * @returns {proto.SSL_BallModelChipFixedLoss} SSL_BallModelChipFixedLoss * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - SSL_Referee.decodeDelimited = function decodeDelimited(reader) { + SSL_BallModelChipFixedLoss.decodeDelimited = function decodeDelimited(reader) { if (!(reader instanceof $Reader)) reader = new $Reader(reader); return this.decode(reader, reader.uint32()); }; /** - * Verifies a SSL_Referee message. + * Verifies a SSL_BallModelChipFixedLoss message. * @function verify - * @memberof proto.SSL_Referee + * @memberof proto.SSL_BallModelChipFixedLoss * @static * @param {Object.} message Plain object to verify * @returns {string|null} `null` if valid, otherwise the reason why it is not */ - SSL_Referee.verify = function verify(message) { + SSL_BallModelChipFixedLoss.verify = function verify(message) { if (typeof message !== "object" || message === null) return "object expected"; - if (!$util.isInteger(message.packetTimestamp) && !(message.packetTimestamp && $util.isInteger(message.packetTimestamp.low) && $util.isInteger(message.packetTimestamp.high))) - return "packetTimestamp: integer|Long expected"; - switch (message.stage) { - default: - return "stage: enum value expected"; - case 0: - case 1: - case 2: - case 3: - case 4: - case 5: - case 6: - case 7: - case 8: - case 9: - case 10: - case 11: - case 12: - case 13: - break; - } - if (message.stageTimeLeft != null && message.hasOwnProperty("stageTimeLeft")) - if (!$util.isInteger(message.stageTimeLeft)) - return "stageTimeLeft: integer expected"; - switch (message.command) { - default: - return "command: enum value expected"; - case 0: - case 1: - case 2: - case 3: - case 4: - case 5: - case 6: - case 7: - case 8: - case 9: - case 10: - case 11: - case 12: - case 13: - case 16: - case 17: - break; - } - if (!$util.isInteger(message.commandCounter)) - return "commandCounter: integer expected"; - if (!$util.isInteger(message.commandTimestamp) && !(message.commandTimestamp && $util.isInteger(message.commandTimestamp.low) && $util.isInteger(message.commandTimestamp.high))) - return "commandTimestamp: integer|Long expected"; - { - let error = $root.proto.SSL_Referee.TeamInfo.verify(message.yellow); - if (error) - return "yellow." + error; - } - { - let error = $root.proto.SSL_Referee.TeamInfo.verify(message.blue); - if (error) - return "blue." + error; - } - if (message.designatedPosition != null && message.hasOwnProperty("designatedPosition")) { - let error = $root.proto.SSL_Referee.Point.verify(message.designatedPosition); - if (error) - return "designatedPosition." + error; - } - if (message.blueTeamOnPositiveHalf != null && message.hasOwnProperty("blueTeamOnPositiveHalf")) - if (typeof message.blueTeamOnPositiveHalf !== "boolean") - return "blueTeamOnPositiveHalf: boolean expected"; - if (message.nextCommand != null && message.hasOwnProperty("nextCommand")) - switch (message.nextCommand) { - default: - return "nextCommand: enum value expected"; - case 0: - case 1: - case 2: - case 3: - case 4: - case 5: - case 6: - case 7: - case 8: - case 9: - case 10: - case 11: - case 12: - case 13: - case 16: - case 17: - break; - } - if (message.gameEvents != null && message.hasOwnProperty("gameEvents")) { - if (!Array.isArray(message.gameEvents)) - return "gameEvents: array expected"; - for (let i = 0; i < message.gameEvents.length; ++i) { - let error = $root.proto.GameEvent.verify(message.gameEvents[i]); - if (error) - return "gameEvents." + error; - } - } - if (message.gameEventProposals != null && message.hasOwnProperty("gameEventProposals")) { - if (!Array.isArray(message.gameEventProposals)) - return "gameEventProposals: array expected"; - for (let i = 0; i < message.gameEventProposals.length; ++i) { - let error = $root.proto.GameEventProposalGroup.verify(message.gameEventProposals[i]); - if (error) - return "gameEventProposals." + error; - } - } - if (message.currentActionTimeRemaining != null && message.hasOwnProperty("currentActionTimeRemaining")) - if (!$util.isInteger(message.currentActionTimeRemaining)) - return "currentActionTimeRemaining: integer expected"; + if (typeof message.dampingXyFirstHop !== "number") + return "dampingXyFirstHop: number expected"; + if (typeof message.dampingXyOtherHops !== "number") + return "dampingXyOtherHops: number expected"; + if (typeof message.dampingZ !== "number") + return "dampingZ: number expected"; return null; }; /** - * Creates a SSL_Referee message from a plain object. Also converts values to their respective internal types. + * Creates a SSL_BallModelChipFixedLoss message from a plain object. Also converts values to their respective internal types. * @function fromObject - * @memberof proto.SSL_Referee + * @memberof proto.SSL_BallModelChipFixedLoss * @static * @param {Object.} object Plain object - * @returns {proto.SSL_Referee} SSL_Referee + * @returns {proto.SSL_BallModelChipFixedLoss} SSL_BallModelChipFixedLoss */ - SSL_Referee.fromObject = function fromObject(object) { - if (object instanceof $root.proto.SSL_Referee) + SSL_BallModelChipFixedLoss.fromObject = function fromObject(object) { + if (object instanceof $root.proto.SSL_BallModelChipFixedLoss) return object; - let message = new $root.proto.SSL_Referee(); - if (object.packetTimestamp != null) - if ($util.Long) - (message.packetTimestamp = $util.Long.fromValue(object.packetTimestamp)).unsigned = true; - else if (typeof object.packetTimestamp === "string") - message.packetTimestamp = parseInt(object.packetTimestamp, 10); - else if (typeof object.packetTimestamp === "number") - message.packetTimestamp = object.packetTimestamp; - else if (typeof object.packetTimestamp === "object") - message.packetTimestamp = new $util.LongBits(object.packetTimestamp.low >>> 0, object.packetTimestamp.high >>> 0).toNumber(true); - switch (object.stage) { - default: - if (typeof object.stage === "number") { - message.stage = object.stage; - break; - } - break; - case "NORMAL_FIRST_HALF_PRE": - case 0: - message.stage = 0; - break; - case "NORMAL_FIRST_HALF": - case 1: - message.stage = 1; - break; - case "NORMAL_HALF_TIME": - case 2: - message.stage = 2; - break; - case "NORMAL_SECOND_HALF_PRE": - case 3: - message.stage = 3; - break; - case "NORMAL_SECOND_HALF": - case 4: - message.stage = 4; - break; - case "EXTRA_TIME_BREAK": - case 5: - message.stage = 5; - break; - case "EXTRA_FIRST_HALF_PRE": - case 6: - message.stage = 6; - break; - case "EXTRA_FIRST_HALF": - case 7: - message.stage = 7; - break; - case "EXTRA_HALF_TIME": - case 8: - message.stage = 8; - break; - case "EXTRA_SECOND_HALF_PRE": - case 9: - message.stage = 9; - break; - case "EXTRA_SECOND_HALF": - case 10: - message.stage = 10; - break; - case "PENALTY_SHOOTOUT_BREAK": - case 11: - message.stage = 11; - break; - case "PENALTY_SHOOTOUT": - case 12: - message.stage = 12; - break; - case "POST_GAME": - case 13: - message.stage = 13; - break; - } - if (object.stageTimeLeft != null) - message.stageTimeLeft = object.stageTimeLeft | 0; - switch (object.command) { - default: - if (typeof object.command === "number") { - message.command = object.command; - break; - } - break; - case "HALT": - case 0: - message.command = 0; - break; - case "STOP": - case 1: - message.command = 1; - break; - case "NORMAL_START": - case 2: - message.command = 2; - break; - case "FORCE_START": - case 3: - message.command = 3; - break; - case "PREPARE_KICKOFF_YELLOW": - case 4: - message.command = 4; - break; - case "PREPARE_KICKOFF_BLUE": - case 5: - message.command = 5; - break; - case "PREPARE_PENALTY_YELLOW": - case 6: - message.command = 6; - break; - case "PREPARE_PENALTY_BLUE": - case 7: - message.command = 7; - break; - case "DIRECT_FREE_YELLOW": - case 8: - message.command = 8; - break; - case "DIRECT_FREE_BLUE": - case 9: - message.command = 9; - break; - case "INDIRECT_FREE_YELLOW": - case 10: - message.command = 10; - break; - case "INDIRECT_FREE_BLUE": - case 11: - message.command = 11; - break; - case "TIMEOUT_YELLOW": - case 12: - message.command = 12; - break; - case "TIMEOUT_BLUE": - case 13: - message.command = 13; - break; - case "BALL_PLACEMENT_YELLOW": - case 16: - message.command = 16; - break; - case "BALL_PLACEMENT_BLUE": - case 17: - message.command = 17; - break; - } - if (object.commandCounter != null) - message.commandCounter = object.commandCounter >>> 0; - if (object.commandTimestamp != null) - if ($util.Long) - (message.commandTimestamp = $util.Long.fromValue(object.commandTimestamp)).unsigned = true; - else if (typeof object.commandTimestamp === "string") - message.commandTimestamp = parseInt(object.commandTimestamp, 10); - else if (typeof object.commandTimestamp === "number") - message.commandTimestamp = object.commandTimestamp; - else if (typeof object.commandTimestamp === "object") - message.commandTimestamp = new $util.LongBits(object.commandTimestamp.low >>> 0, object.commandTimestamp.high >>> 0).toNumber(true); - if (object.yellow != null) { - if (typeof object.yellow !== "object") - throw TypeError(".proto.SSL_Referee.yellow: object expected"); - message.yellow = $root.proto.SSL_Referee.TeamInfo.fromObject(object.yellow); - } - if (object.blue != null) { - if (typeof object.blue !== "object") - throw TypeError(".proto.SSL_Referee.blue: object expected"); - message.blue = $root.proto.SSL_Referee.TeamInfo.fromObject(object.blue); - } - if (object.designatedPosition != null) { - if (typeof object.designatedPosition !== "object") - throw TypeError(".proto.SSL_Referee.designatedPosition: object expected"); - message.designatedPosition = $root.proto.SSL_Referee.Point.fromObject(object.designatedPosition); - } - if (object.blueTeamOnPositiveHalf != null) - message.blueTeamOnPositiveHalf = Boolean(object.blueTeamOnPositiveHalf); - switch (object.nextCommand) { - default: - if (typeof object.nextCommand === "number") { - message.nextCommand = object.nextCommand; - break; - } - break; - case "HALT": - case 0: - message.nextCommand = 0; - break; - case "STOP": - case 1: - message.nextCommand = 1; - break; - case "NORMAL_START": - case 2: - message.nextCommand = 2; - break; - case "FORCE_START": - case 3: - message.nextCommand = 3; - break; - case "PREPARE_KICKOFF_YELLOW": - case 4: - message.nextCommand = 4; - break; - case "PREPARE_KICKOFF_BLUE": - case 5: - message.nextCommand = 5; - break; - case "PREPARE_PENALTY_YELLOW": - case 6: - message.nextCommand = 6; - break; - case "PREPARE_PENALTY_BLUE": - case 7: - message.nextCommand = 7; - break; - case "DIRECT_FREE_YELLOW": - case 8: - message.nextCommand = 8; - break; - case "DIRECT_FREE_BLUE": - case 9: - message.nextCommand = 9; - break; - case "INDIRECT_FREE_YELLOW": - case 10: - message.nextCommand = 10; - break; - case "INDIRECT_FREE_BLUE": - case 11: - message.nextCommand = 11; - break; - case "TIMEOUT_YELLOW": - case 12: - message.nextCommand = 12; - break; - case "TIMEOUT_BLUE": - case 13: - message.nextCommand = 13; - break; - case "BALL_PLACEMENT_YELLOW": - case 16: - message.nextCommand = 16; - break; - case "BALL_PLACEMENT_BLUE": - case 17: - message.nextCommand = 17; - break; - } - if (object.gameEvents) { - if (!Array.isArray(object.gameEvents)) - throw TypeError(".proto.SSL_Referee.gameEvents: array expected"); - message.gameEvents = []; - for (let i = 0; i < object.gameEvents.length; ++i) { - if (typeof object.gameEvents[i] !== "object") - throw TypeError(".proto.SSL_Referee.gameEvents: object expected"); - message.gameEvents[i] = $root.proto.GameEvent.fromObject(object.gameEvents[i]); - } - } - if (object.gameEventProposals) { - if (!Array.isArray(object.gameEventProposals)) - throw TypeError(".proto.SSL_Referee.gameEventProposals: array expected"); - message.gameEventProposals = []; - for (let i = 0; i < object.gameEventProposals.length; ++i) { - if (typeof object.gameEventProposals[i] !== "object") - throw TypeError(".proto.SSL_Referee.gameEventProposals: object expected"); - message.gameEventProposals[i] = $root.proto.GameEventProposalGroup.fromObject(object.gameEventProposals[i]); - } - } - if (object.currentActionTimeRemaining != null) - message.currentActionTimeRemaining = object.currentActionTimeRemaining | 0; + let message = new $root.proto.SSL_BallModelChipFixedLoss(); + if (object.dampingXyFirstHop != null) + message.dampingXyFirstHop = Number(object.dampingXyFirstHop); + if (object.dampingXyOtherHops != null) + message.dampingXyOtherHops = Number(object.dampingXyOtherHops); + if (object.dampingZ != null) + message.dampingZ = Number(object.dampingZ); return message; }; /** - * Creates a plain object from a SSL_Referee message. Also converts values to other types if specified. + * Creates a plain object from a SSL_BallModelChipFixedLoss message. Also converts values to other types if specified. * @function toObject - * @memberof proto.SSL_Referee + * @memberof proto.SSL_BallModelChipFixedLoss * @static - * @param {proto.SSL_Referee} message SSL_Referee + * @param {proto.SSL_BallModelChipFixedLoss} message SSL_BallModelChipFixedLoss * @param {$protobuf.IConversionOptions} [options] Conversion options * @returns {Object.} Plain object */ - SSL_Referee.toObject = function toObject(message, options) { + SSL_BallModelChipFixedLoss.toObject = function toObject(message, options) { if (!options) options = {}; let object = {}; - if (options.arrays || options.defaults) { - object.gameEvents = []; - object.gameEventProposals = []; - } if (options.defaults) { - if ($util.Long) { - let long = new $util.Long(0, 0, true); - object.packetTimestamp = options.longs === String ? long.toString() : options.longs === Number ? long.toNumber() : long; - } else - object.packetTimestamp = options.longs === String ? "0" : 0; - object.stage = options.enums === String ? "NORMAL_FIRST_HALF_PRE" : 0; - object.stageTimeLeft = 0; - object.command = options.enums === String ? "HALT" : 0; - object.commandCounter = 0; - if ($util.Long) { - let long = new $util.Long(0, 0, true); - object.commandTimestamp = options.longs === String ? long.toString() : options.longs === Number ? long.toNumber() : long; - } else - object.commandTimestamp = options.longs === String ? "0" : 0; - object.yellow = null; - object.blue = null; - object.designatedPosition = null; - object.blueTeamOnPositiveHalf = false; - object.nextCommand = options.enums === String ? "HALT" : 0; - object.currentActionTimeRemaining = 0; - } - if (message.packetTimestamp != null && message.hasOwnProperty("packetTimestamp")) - if (typeof message.packetTimestamp === "number") - object.packetTimestamp = options.longs === String ? String(message.packetTimestamp) : message.packetTimestamp; - else - object.packetTimestamp = options.longs === String ? $util.Long.prototype.toString.call(message.packetTimestamp) : options.longs === Number ? new $util.LongBits(message.packetTimestamp.low >>> 0, message.packetTimestamp.high >>> 0).toNumber(true) : message.packetTimestamp; - if (message.stage != null && message.hasOwnProperty("stage")) - object.stage = options.enums === String ? $root.proto.SSL_Referee.Stage[message.stage] === undefined ? message.stage : $root.proto.SSL_Referee.Stage[message.stage] : message.stage; - if (message.stageTimeLeft != null && message.hasOwnProperty("stageTimeLeft")) - object.stageTimeLeft = message.stageTimeLeft; - if (message.command != null && message.hasOwnProperty("command")) - object.command = options.enums === String ? $root.proto.SSL_Referee.Command[message.command] === undefined ? message.command : $root.proto.SSL_Referee.Command[message.command] : message.command; - if (message.commandCounter != null && message.hasOwnProperty("commandCounter")) - object.commandCounter = message.commandCounter; - if (message.commandTimestamp != null && message.hasOwnProperty("commandTimestamp")) - if (typeof message.commandTimestamp === "number") - object.commandTimestamp = options.longs === String ? String(message.commandTimestamp) : message.commandTimestamp; - else - object.commandTimestamp = options.longs === String ? $util.Long.prototype.toString.call(message.commandTimestamp) : options.longs === Number ? new $util.LongBits(message.commandTimestamp.low >>> 0, message.commandTimestamp.high >>> 0).toNumber(true) : message.commandTimestamp; - if (message.yellow != null && message.hasOwnProperty("yellow")) - object.yellow = $root.proto.SSL_Referee.TeamInfo.toObject(message.yellow, options); - if (message.blue != null && message.hasOwnProperty("blue")) - object.blue = $root.proto.SSL_Referee.TeamInfo.toObject(message.blue, options); - if (message.designatedPosition != null && message.hasOwnProperty("designatedPosition")) - object.designatedPosition = $root.proto.SSL_Referee.Point.toObject(message.designatedPosition, options); - if (message.blueTeamOnPositiveHalf != null && message.hasOwnProperty("blueTeamOnPositiveHalf")) - object.blueTeamOnPositiveHalf = message.blueTeamOnPositiveHalf; - if (message.nextCommand != null && message.hasOwnProperty("nextCommand")) - object.nextCommand = options.enums === String ? $root.proto.SSL_Referee.Command[message.nextCommand] === undefined ? message.nextCommand : $root.proto.SSL_Referee.Command[message.nextCommand] : message.nextCommand; - if (message.currentActionTimeRemaining != null && message.hasOwnProperty("currentActionTimeRemaining")) - object.currentActionTimeRemaining = message.currentActionTimeRemaining; - if (message.gameEvents && message.gameEvents.length) { - object.gameEvents = []; - for (let j = 0; j < message.gameEvents.length; ++j) - object.gameEvents[j] = $root.proto.GameEvent.toObject(message.gameEvents[j], options); - } - if (message.gameEventProposals && message.gameEventProposals.length) { - object.gameEventProposals = []; - for (let j = 0; j < message.gameEventProposals.length; ++j) - object.gameEventProposals[j] = $root.proto.GameEventProposalGroup.toObject(message.gameEventProposals[j], options); - } + object.dampingXyFirstHop = 0; + object.dampingXyOtherHops = 0; + object.dampingZ = 0; + } + if (message.dampingXyFirstHop != null && message.hasOwnProperty("dampingXyFirstHop")) + object.dampingXyFirstHop = options.json && !isFinite(message.dampingXyFirstHop) ? String(message.dampingXyFirstHop) : message.dampingXyFirstHop; + if (message.dampingXyOtherHops != null && message.hasOwnProperty("dampingXyOtherHops")) + object.dampingXyOtherHops = options.json && !isFinite(message.dampingXyOtherHops) ? String(message.dampingXyOtherHops) : message.dampingXyOtherHops; + if (message.dampingZ != null && message.hasOwnProperty("dampingZ")) + object.dampingZ = options.json && !isFinite(message.dampingZ) ? String(message.dampingZ) : message.dampingZ; return object; }; /** - * Converts this SSL_Referee to JSON. + * Converts this SSL_BallModelChipFixedLoss to JSON. * @function toJSON - * @memberof proto.SSL_Referee + * @memberof proto.SSL_BallModelChipFixedLoss * @instance * @returns {Object.} JSON object */ - SSL_Referee.prototype.toJSON = function toJSON() { + SSL_BallModelChipFixedLoss.prototype.toJSON = function toJSON() { return this.constructor.toObject(this, $protobuf.util.toJSONOptions); }; /** - * Gets the default type url for SSL_Referee + * Gets the default type url for SSL_BallModelChipFixedLoss * @function getTypeUrl - * @memberof proto.SSL_Referee + * @memberof proto.SSL_BallModelChipFixedLoss * @static * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns {string} The default type url */ - SSL_Referee.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + SSL_BallModelChipFixedLoss.getTypeUrl = function getTypeUrl(typeUrlPrefix) { if (typeUrlPrefix === undefined) { typeUrlPrefix = "type.googleapis.com"; } - return typeUrlPrefix + "/proto.SSL_Referee"; + return typeUrlPrefix + "/proto.SSL_BallModelChipFixedLoss"; }; + return SSL_BallModelChipFixedLoss; + })(); + + proto.SSL_GeometryModels = (function() { + /** - * Stage enum. - * @name proto.SSL_Referee.Stage - * @enum {number} - * @property {number} NORMAL_FIRST_HALF_PRE=0 NORMAL_FIRST_HALF_PRE value - * @property {number} NORMAL_FIRST_HALF=1 NORMAL_FIRST_HALF value - * @property {number} NORMAL_HALF_TIME=2 NORMAL_HALF_TIME value - * @property {number} NORMAL_SECOND_HALF_PRE=3 NORMAL_SECOND_HALF_PRE value - * @property {number} NORMAL_SECOND_HALF=4 NORMAL_SECOND_HALF value - * @property {number} EXTRA_TIME_BREAK=5 EXTRA_TIME_BREAK value - * @property {number} EXTRA_FIRST_HALF_PRE=6 EXTRA_FIRST_HALF_PRE value - * @property {number} EXTRA_FIRST_HALF=7 EXTRA_FIRST_HALF value - * @property {number} EXTRA_HALF_TIME=8 EXTRA_HALF_TIME value - * @property {number} EXTRA_SECOND_HALF_PRE=9 EXTRA_SECOND_HALF_PRE value - * @property {number} EXTRA_SECOND_HALF=10 EXTRA_SECOND_HALF value - * @property {number} PENALTY_SHOOTOUT_BREAK=11 PENALTY_SHOOTOUT_BREAK value - * @property {number} PENALTY_SHOOTOUT=12 PENALTY_SHOOTOUT value - * @property {number} POST_GAME=13 POST_GAME value + * Properties of a SSL_GeometryModels. + * @memberof proto + * @interface ISSL_GeometryModels + * @property {proto.ISSL_BallModelStraightTwoPhase|null} [straightTwoPhase] SSL_GeometryModels straightTwoPhase + * @property {proto.ISSL_BallModelChipFixedLoss|null} [chipFixedLoss] SSL_GeometryModels chipFixedLoss */ - SSL_Referee.Stage = (function() { - const valuesById = {}, values = Object.create(valuesById); - values[valuesById[0] = "NORMAL_FIRST_HALF_PRE"] = 0; - values[valuesById[1] = "NORMAL_FIRST_HALF"] = 1; - values[valuesById[2] = "NORMAL_HALF_TIME"] = 2; - values[valuesById[3] = "NORMAL_SECOND_HALF_PRE"] = 3; - values[valuesById[4] = "NORMAL_SECOND_HALF"] = 4; - values[valuesById[5] = "EXTRA_TIME_BREAK"] = 5; - values[valuesById[6] = "EXTRA_FIRST_HALF_PRE"] = 6; - values[valuesById[7] = "EXTRA_FIRST_HALF"] = 7; - values[valuesById[8] = "EXTRA_HALF_TIME"] = 8; - values[valuesById[9] = "EXTRA_SECOND_HALF_PRE"] = 9; - values[valuesById[10] = "EXTRA_SECOND_HALF"] = 10; - values[valuesById[11] = "PENALTY_SHOOTOUT_BREAK"] = 11; - values[valuesById[12] = "PENALTY_SHOOTOUT"] = 12; - values[valuesById[13] = "POST_GAME"] = 13; - return values; - })(); /** - * Command enum. - * @name proto.SSL_Referee.Command - * @enum {number} - * @property {number} HALT=0 HALT value - * @property {number} STOP=1 STOP value - * @property {number} NORMAL_START=2 NORMAL_START value - * @property {number} FORCE_START=3 FORCE_START value - * @property {number} PREPARE_KICKOFF_YELLOW=4 PREPARE_KICKOFF_YELLOW value - * @property {number} PREPARE_KICKOFF_BLUE=5 PREPARE_KICKOFF_BLUE value + * Constructs a new SSL_GeometryModels. + * @memberof proto + * @classdesc Represents a SSL_GeometryModels. + * @implements ISSL_GeometryModels + * @constructor + * @param {proto.ISSL_GeometryModels=} [properties] Properties to set + */ + function SSL_GeometryModels(properties) { + if (properties) + for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) + if (properties[keys[i]] != null) + this[keys[i]] = properties[keys[i]]; + } + + /** + * SSL_GeometryModels straightTwoPhase. + * @member {proto.ISSL_BallModelStraightTwoPhase|null|undefined} straightTwoPhase + * @memberof proto.SSL_GeometryModels + * @instance + */ + SSL_GeometryModels.prototype.straightTwoPhase = null; + + /** + * SSL_GeometryModels chipFixedLoss. + * @member {proto.ISSL_BallModelChipFixedLoss|null|undefined} chipFixedLoss + * @memberof proto.SSL_GeometryModels + * @instance + */ + SSL_GeometryModels.prototype.chipFixedLoss = null; + + /** + * Creates a new SSL_GeometryModels instance using the specified properties. + * @function create + * @memberof proto.SSL_GeometryModels + * @static + * @param {proto.ISSL_GeometryModels=} [properties] Properties to set + * @returns {proto.SSL_GeometryModels} SSL_GeometryModels instance + */ + SSL_GeometryModels.create = function create(properties) { + return new SSL_GeometryModels(properties); + }; + + /** + * Encodes the specified SSL_GeometryModels message. Does not implicitly {@link proto.SSL_GeometryModels.verify|verify} messages. + * @function encode + * @memberof proto.SSL_GeometryModels + * @static + * @param {proto.ISSL_GeometryModels} message SSL_GeometryModels message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + SSL_GeometryModels.encode = function encode(message, writer) { + if (!writer) + writer = $Writer.create(); + if (message.straightTwoPhase != null && Object.hasOwnProperty.call(message, "straightTwoPhase")) + $root.proto.SSL_BallModelStraightTwoPhase.encode(message.straightTwoPhase, writer.uint32(/* id 1, wireType 2 =*/10).fork()).ldelim(); + if (message.chipFixedLoss != null && Object.hasOwnProperty.call(message, "chipFixedLoss")) + $root.proto.SSL_BallModelChipFixedLoss.encode(message.chipFixedLoss, writer.uint32(/* id 2, wireType 2 =*/18).fork()).ldelim(); + return writer; + }; + + /** + * Encodes the specified SSL_GeometryModels message, length delimited. Does not implicitly {@link proto.SSL_GeometryModels.verify|verify} messages. + * @function encodeDelimited + * @memberof proto.SSL_GeometryModels + * @static + * @param {proto.ISSL_GeometryModels} message SSL_GeometryModels message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + SSL_GeometryModels.encodeDelimited = function encodeDelimited(message, writer) { + return this.encode(message, writer).ldelim(); + }; + + /** + * Decodes a SSL_GeometryModels message from the specified reader or buffer. + * @function decode + * @memberof proto.SSL_GeometryModels + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @param {number} [length] Message length if known beforehand + * @returns {proto.SSL_GeometryModels} SSL_GeometryModels + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + SSL_GeometryModels.decode = function decode(reader, length) { + if (!(reader instanceof $Reader)) + reader = $Reader.create(reader); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.SSL_GeometryModels(); + while (reader.pos < end) { + let tag = reader.uint32(); + switch (tag >>> 3) { + case 1: { + message.straightTwoPhase = $root.proto.SSL_BallModelStraightTwoPhase.decode(reader, reader.uint32()); + break; + } + case 2: { + message.chipFixedLoss = $root.proto.SSL_BallModelChipFixedLoss.decode(reader, reader.uint32()); + break; + } + default: + reader.skipType(tag & 7); + break; + } + } + return message; + }; + + /** + * Decodes a SSL_GeometryModels message from the specified reader or buffer, length delimited. + * @function decodeDelimited + * @memberof proto.SSL_GeometryModels + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @returns {proto.SSL_GeometryModels} SSL_GeometryModels + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + SSL_GeometryModels.decodeDelimited = function decodeDelimited(reader) { + if (!(reader instanceof $Reader)) + reader = new $Reader(reader); + return this.decode(reader, reader.uint32()); + }; + + /** + * Verifies a SSL_GeometryModels message. + * @function verify + * @memberof proto.SSL_GeometryModels + * @static + * @param {Object.} message Plain object to verify + * @returns {string|null} `null` if valid, otherwise the reason why it is not + */ + SSL_GeometryModels.verify = function verify(message) { + if (typeof message !== "object" || message === null) + return "object expected"; + if (message.straightTwoPhase != null && message.hasOwnProperty("straightTwoPhase")) { + let error = $root.proto.SSL_BallModelStraightTwoPhase.verify(message.straightTwoPhase); + if (error) + return "straightTwoPhase." + error; + } + if (message.chipFixedLoss != null && message.hasOwnProperty("chipFixedLoss")) { + let error = $root.proto.SSL_BallModelChipFixedLoss.verify(message.chipFixedLoss); + if (error) + return "chipFixedLoss." + error; + } + return null; + }; + + /** + * Creates a SSL_GeometryModels message from a plain object. Also converts values to their respective internal types. + * @function fromObject + * @memberof proto.SSL_GeometryModels + * @static + * @param {Object.} object Plain object + * @returns {proto.SSL_GeometryModels} SSL_GeometryModels + */ + SSL_GeometryModels.fromObject = function fromObject(object) { + if (object instanceof $root.proto.SSL_GeometryModels) + return object; + let message = new $root.proto.SSL_GeometryModels(); + if (object.straightTwoPhase != null) { + if (typeof object.straightTwoPhase !== "object") + throw TypeError(".proto.SSL_GeometryModels.straightTwoPhase: object expected"); + message.straightTwoPhase = $root.proto.SSL_BallModelStraightTwoPhase.fromObject(object.straightTwoPhase); + } + if (object.chipFixedLoss != null) { + if (typeof object.chipFixedLoss !== "object") + throw TypeError(".proto.SSL_GeometryModels.chipFixedLoss: object expected"); + message.chipFixedLoss = $root.proto.SSL_BallModelChipFixedLoss.fromObject(object.chipFixedLoss); + } + return message; + }; + + /** + * Creates a plain object from a SSL_GeometryModels message. Also converts values to other types if specified. + * @function toObject + * @memberof proto.SSL_GeometryModels + * @static + * @param {proto.SSL_GeometryModels} message SSL_GeometryModels + * @param {$protobuf.IConversionOptions} [options] Conversion options + * @returns {Object.} Plain object + */ + SSL_GeometryModels.toObject = function toObject(message, options) { + if (!options) + options = {}; + let object = {}; + if (options.defaults) { + object.straightTwoPhase = null; + object.chipFixedLoss = null; + } + if (message.straightTwoPhase != null && message.hasOwnProperty("straightTwoPhase")) + object.straightTwoPhase = $root.proto.SSL_BallModelStraightTwoPhase.toObject(message.straightTwoPhase, options); + if (message.chipFixedLoss != null && message.hasOwnProperty("chipFixedLoss")) + object.chipFixedLoss = $root.proto.SSL_BallModelChipFixedLoss.toObject(message.chipFixedLoss, options); + return object; + }; + + /** + * Converts this SSL_GeometryModels to JSON. + * @function toJSON + * @memberof proto.SSL_GeometryModels + * @instance + * @returns {Object.} JSON object + */ + SSL_GeometryModels.prototype.toJSON = function toJSON() { + return this.constructor.toObject(this, $protobuf.util.toJSONOptions); + }; + + /** + * Gets the default type url for SSL_GeometryModels + * @function getTypeUrl + * @memberof proto.SSL_GeometryModels + * @static + * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns {string} The default type url + */ + SSL_GeometryModels.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + if (typeUrlPrefix === undefined) { + typeUrlPrefix = "type.googleapis.com"; + } + return typeUrlPrefix + "/proto.SSL_GeometryModels"; + }; + + return SSL_GeometryModels; + })(); + + proto.SSL_GeometryData = (function() { + + /** + * Properties of a SSL_GeometryData. + * @memberof proto + * @interface ISSL_GeometryData + * @property {proto.ISSL_GeometryFieldSize} field SSL_GeometryData field + * @property {Array.|null} [calib] SSL_GeometryData calib + * @property {proto.ISSL_GeometryModels|null} [models] SSL_GeometryData models + */ + + /** + * Constructs a new SSL_GeometryData. + * @memberof proto + * @classdesc Represents a SSL_GeometryData. + * @implements ISSL_GeometryData + * @constructor + * @param {proto.ISSL_GeometryData=} [properties] Properties to set + */ + function SSL_GeometryData(properties) { + this.calib = []; + if (properties) + for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) + if (properties[keys[i]] != null) + this[keys[i]] = properties[keys[i]]; + } + + /** + * SSL_GeometryData field. + * @member {proto.ISSL_GeometryFieldSize} field + * @memberof proto.SSL_GeometryData + * @instance + */ + SSL_GeometryData.prototype.field = null; + + /** + * SSL_GeometryData calib. + * @member {Array.} calib + * @memberof proto.SSL_GeometryData + * @instance + */ + SSL_GeometryData.prototype.calib = $util.emptyArray; + + /** + * SSL_GeometryData models. + * @member {proto.ISSL_GeometryModels|null|undefined} models + * @memberof proto.SSL_GeometryData + * @instance + */ + SSL_GeometryData.prototype.models = null; + + /** + * Creates a new SSL_GeometryData instance using the specified properties. + * @function create + * @memberof proto.SSL_GeometryData + * @static + * @param {proto.ISSL_GeometryData=} [properties] Properties to set + * @returns {proto.SSL_GeometryData} SSL_GeometryData instance + */ + SSL_GeometryData.create = function create(properties) { + return new SSL_GeometryData(properties); + }; + + /** + * Encodes the specified SSL_GeometryData message. Does not implicitly {@link proto.SSL_GeometryData.verify|verify} messages. + * @function encode + * @memberof proto.SSL_GeometryData + * @static + * @param {proto.ISSL_GeometryData} message SSL_GeometryData message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + SSL_GeometryData.encode = function encode(message, writer) { + if (!writer) + writer = $Writer.create(); + $root.proto.SSL_GeometryFieldSize.encode(message.field, writer.uint32(/* id 1, wireType 2 =*/10).fork()).ldelim(); + if (message.calib != null && message.calib.length) + for (let i = 0; i < message.calib.length; ++i) + $root.proto.SSL_GeometryCameraCalibration.encode(message.calib[i], writer.uint32(/* id 2, wireType 2 =*/18).fork()).ldelim(); + if (message.models != null && Object.hasOwnProperty.call(message, "models")) + $root.proto.SSL_GeometryModels.encode(message.models, writer.uint32(/* id 3, wireType 2 =*/26).fork()).ldelim(); + return writer; + }; + + /** + * Encodes the specified SSL_GeometryData message, length delimited. Does not implicitly {@link proto.SSL_GeometryData.verify|verify} messages. + * @function encodeDelimited + * @memberof proto.SSL_GeometryData + * @static + * @param {proto.ISSL_GeometryData} message SSL_GeometryData message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + SSL_GeometryData.encodeDelimited = function encodeDelimited(message, writer) { + return this.encode(message, writer).ldelim(); + }; + + /** + * Decodes a SSL_GeometryData message from the specified reader or buffer. + * @function decode + * @memberof proto.SSL_GeometryData + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @param {number} [length] Message length if known beforehand + * @returns {proto.SSL_GeometryData} SSL_GeometryData + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + SSL_GeometryData.decode = function decode(reader, length) { + if (!(reader instanceof $Reader)) + reader = $Reader.create(reader); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.SSL_GeometryData(); + while (reader.pos < end) { + let tag = reader.uint32(); + switch (tag >>> 3) { + case 1: { + message.field = $root.proto.SSL_GeometryFieldSize.decode(reader, reader.uint32()); + break; + } + case 2: { + if (!(message.calib && message.calib.length)) + message.calib = []; + message.calib.push($root.proto.SSL_GeometryCameraCalibration.decode(reader, reader.uint32())); + break; + } + case 3: { + message.models = $root.proto.SSL_GeometryModels.decode(reader, reader.uint32()); + break; + } + default: + reader.skipType(tag & 7); + break; + } + } + if (!message.hasOwnProperty("field")) + throw $util.ProtocolError("missing required 'field'", { instance: message }); + return message; + }; + + /** + * Decodes a SSL_GeometryData message from the specified reader or buffer, length delimited. + * @function decodeDelimited + * @memberof proto.SSL_GeometryData + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @returns {proto.SSL_GeometryData} SSL_GeometryData + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + SSL_GeometryData.decodeDelimited = function decodeDelimited(reader) { + if (!(reader instanceof $Reader)) + reader = new $Reader(reader); + return this.decode(reader, reader.uint32()); + }; + + /** + * Verifies a SSL_GeometryData message. + * @function verify + * @memberof proto.SSL_GeometryData + * @static + * @param {Object.} message Plain object to verify + * @returns {string|null} `null` if valid, otherwise the reason why it is not + */ + SSL_GeometryData.verify = function verify(message) { + if (typeof message !== "object" || message === null) + return "object expected"; + { + let error = $root.proto.SSL_GeometryFieldSize.verify(message.field); + if (error) + return "field." + error; + } + if (message.calib != null && message.hasOwnProperty("calib")) { + if (!Array.isArray(message.calib)) + return "calib: array expected"; + for (let i = 0; i < message.calib.length; ++i) { + let error = $root.proto.SSL_GeometryCameraCalibration.verify(message.calib[i]); + if (error) + return "calib." + error; + } + } + if (message.models != null && message.hasOwnProperty("models")) { + let error = $root.proto.SSL_GeometryModels.verify(message.models); + if (error) + return "models." + error; + } + return null; + }; + + /** + * Creates a SSL_GeometryData message from a plain object. Also converts values to their respective internal types. + * @function fromObject + * @memberof proto.SSL_GeometryData + * @static + * @param {Object.} object Plain object + * @returns {proto.SSL_GeometryData} SSL_GeometryData + */ + SSL_GeometryData.fromObject = function fromObject(object) { + if (object instanceof $root.proto.SSL_GeometryData) + return object; + let message = new $root.proto.SSL_GeometryData(); + if (object.field != null) { + if (typeof object.field !== "object") + throw TypeError(".proto.SSL_GeometryData.field: object expected"); + message.field = $root.proto.SSL_GeometryFieldSize.fromObject(object.field); + } + if (object.calib) { + if (!Array.isArray(object.calib)) + throw TypeError(".proto.SSL_GeometryData.calib: array expected"); + message.calib = []; + for (let i = 0; i < object.calib.length; ++i) { + if (typeof object.calib[i] !== "object") + throw TypeError(".proto.SSL_GeometryData.calib: object expected"); + message.calib[i] = $root.proto.SSL_GeometryCameraCalibration.fromObject(object.calib[i]); + } + } + if (object.models != null) { + if (typeof object.models !== "object") + throw TypeError(".proto.SSL_GeometryData.models: object expected"); + message.models = $root.proto.SSL_GeometryModels.fromObject(object.models); + } + return message; + }; + + /** + * Creates a plain object from a SSL_GeometryData message. Also converts values to other types if specified. + * @function toObject + * @memberof proto.SSL_GeometryData + * @static + * @param {proto.SSL_GeometryData} message SSL_GeometryData + * @param {$protobuf.IConversionOptions} [options] Conversion options + * @returns {Object.} Plain object + */ + SSL_GeometryData.toObject = function toObject(message, options) { + if (!options) + options = {}; + let object = {}; + if (options.arrays || options.defaults) + object.calib = []; + if (options.defaults) { + object.field = null; + object.models = null; + } + if (message.field != null && message.hasOwnProperty("field")) + object.field = $root.proto.SSL_GeometryFieldSize.toObject(message.field, options); + if (message.calib && message.calib.length) { + object.calib = []; + for (let j = 0; j < message.calib.length; ++j) + object.calib[j] = $root.proto.SSL_GeometryCameraCalibration.toObject(message.calib[j], options); + } + if (message.models != null && message.hasOwnProperty("models")) + object.models = $root.proto.SSL_GeometryModels.toObject(message.models, options); + return object; + }; + + /** + * Converts this SSL_GeometryData to JSON. + * @function toJSON + * @memberof proto.SSL_GeometryData + * @instance + * @returns {Object.} JSON object + */ + SSL_GeometryData.prototype.toJSON = function toJSON() { + return this.constructor.toObject(this, $protobuf.util.toJSONOptions); + }; + + /** + * Gets the default type url for SSL_GeometryData + * @function getTypeUrl + * @memberof proto.SSL_GeometryData + * @static + * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns {string} The default type url + */ + SSL_GeometryData.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + if (typeUrlPrefix === undefined) { + typeUrlPrefix = "type.googleapis.com"; + } + return typeUrlPrefix + "/proto.SSL_GeometryData"; + }; + + return SSL_GeometryData; + })(); + + /** + * SSL_FieldShapeType enum. + * @name proto.SSL_FieldShapeType + * @enum {number} + * @property {number} Undefined=0 Undefined value + * @property {number} CenterCircle=1 CenterCircle value + * @property {number} TopTouchLine=2 TopTouchLine value + * @property {number} BottomTouchLine=3 BottomTouchLine value + * @property {number} LeftGoalLine=4 LeftGoalLine value + * @property {number} RightGoalLine=5 RightGoalLine value + * @property {number} HalfwayLine=6 HalfwayLine value + * @property {number} CenterLine=7 CenterLine value + * @property {number} LeftPenaltyStretch=8 LeftPenaltyStretch value + * @property {number} RightPenaltyStretch=9 RightPenaltyStretch value + * @property {number} LeftFieldLeftPenaltyStretch=10 LeftFieldLeftPenaltyStretch value + * @property {number} LeftFieldRightPenaltyStretch=11 LeftFieldRightPenaltyStretch value + * @property {number} RightFieldLeftPenaltyStretch=12 RightFieldLeftPenaltyStretch value + * @property {number} RightFieldRightPenaltyStretch=13 RightFieldRightPenaltyStretch value + */ + proto.SSL_FieldShapeType = (function() { + const valuesById = {}, values = Object.create(valuesById); + values[valuesById[0] = "Undefined"] = 0; + values[valuesById[1] = "CenterCircle"] = 1; + values[valuesById[2] = "TopTouchLine"] = 2; + values[valuesById[3] = "BottomTouchLine"] = 3; + values[valuesById[4] = "LeftGoalLine"] = 4; + values[valuesById[5] = "RightGoalLine"] = 5; + values[valuesById[6] = "HalfwayLine"] = 6; + values[valuesById[7] = "CenterLine"] = 7; + values[valuesById[8] = "LeftPenaltyStretch"] = 8; + values[valuesById[9] = "RightPenaltyStretch"] = 9; + values[valuesById[10] = "LeftFieldLeftPenaltyStretch"] = 10; + values[valuesById[11] = "LeftFieldRightPenaltyStretch"] = 11; + values[valuesById[12] = "RightFieldLeftPenaltyStretch"] = 12; + values[valuesById[13] = "RightFieldRightPenaltyStretch"] = 13; + return values; + })(); + + proto.Referee = (function() { + + /** + * Properties of a Referee. + * @memberof proto + * @interface IReferee + * @property {string|null} [sourceIdentifier] Referee sourceIdentifier + * @property {proto.MatchType|null} [matchType] Referee matchType + * @property {number|Long} packetTimestamp Referee packetTimestamp + * @property {proto.Referee.Stage} stage Referee stage + * @property {number|Long|null} [stageTimeLeft] Referee stageTimeLeft + * @property {proto.Referee.Command} command Referee command + * @property {number} commandCounter Referee commandCounter + * @property {number|Long} commandTimestamp Referee commandTimestamp + * @property {proto.Referee.ITeamInfo} yellow Referee yellow + * @property {proto.Referee.ITeamInfo} blue Referee blue + * @property {proto.Referee.IPoint|null} [designatedPosition] Referee designatedPosition + * @property {boolean|null} [blueTeamOnPositiveHalf] Referee blueTeamOnPositiveHalf + * @property {proto.Referee.Command|null} [nextCommand] Referee nextCommand + * @property {Array.|null} [gameEvents] Referee gameEvents + * @property {Array.|null} [gameEventProposals] Referee gameEventProposals + * @property {number|Long|null} [currentActionTimeRemaining] Referee currentActionTimeRemaining + * @property {string|null} [statusMessage] Referee statusMessage + */ + + /** + * Constructs a new Referee. + * @memberof proto + * @classdesc Represents a Referee. + * @implements IReferee + * @constructor + * @param {proto.IReferee=} [properties] Properties to set + */ + function Referee(properties) { + this.gameEvents = []; + this.gameEventProposals = []; + if (properties) + for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) + if (properties[keys[i]] != null) + this[keys[i]] = properties[keys[i]]; + } + + /** + * Referee sourceIdentifier. + * @member {string} sourceIdentifier + * @memberof proto.Referee + * @instance + */ + Referee.prototype.sourceIdentifier = ""; + + /** + * Referee matchType. + * @member {proto.MatchType} matchType + * @memberof proto.Referee + * @instance + */ + Referee.prototype.matchType = 0; + + /** + * Referee packetTimestamp. + * @member {number|Long} packetTimestamp + * @memberof proto.Referee + * @instance + */ + Referee.prototype.packetTimestamp = $util.Long ? $util.Long.fromBits(0,0,true) : 0; + + /** + * Referee stage. + * @member {proto.Referee.Stage} stage + * @memberof proto.Referee + * @instance + */ + Referee.prototype.stage = 0; + + /** + * Referee stageTimeLeft. + * @member {number|Long} stageTimeLeft + * @memberof proto.Referee + * @instance + */ + Referee.prototype.stageTimeLeft = $util.Long ? $util.Long.fromBits(0,0,false) : 0; + + /** + * Referee command. + * @member {proto.Referee.Command} command + * @memberof proto.Referee + * @instance + */ + Referee.prototype.command = 0; + + /** + * Referee commandCounter. + * @member {number} commandCounter + * @memberof proto.Referee + * @instance + */ + Referee.prototype.commandCounter = 0; + + /** + * Referee commandTimestamp. + * @member {number|Long} commandTimestamp + * @memberof proto.Referee + * @instance + */ + Referee.prototype.commandTimestamp = $util.Long ? $util.Long.fromBits(0,0,true) : 0; + + /** + * Referee yellow. + * @member {proto.Referee.ITeamInfo} yellow + * @memberof proto.Referee + * @instance + */ + Referee.prototype.yellow = null; + + /** + * Referee blue. + * @member {proto.Referee.ITeamInfo} blue + * @memberof proto.Referee + * @instance + */ + Referee.prototype.blue = null; + + /** + * Referee designatedPosition. + * @member {proto.Referee.IPoint|null|undefined} designatedPosition + * @memberof proto.Referee + * @instance + */ + Referee.prototype.designatedPosition = null; + + /** + * Referee blueTeamOnPositiveHalf. + * @member {boolean} blueTeamOnPositiveHalf + * @memberof proto.Referee + * @instance + */ + Referee.prototype.blueTeamOnPositiveHalf = false; + + /** + * Referee nextCommand. + * @member {proto.Referee.Command} nextCommand + * @memberof proto.Referee + * @instance + */ + Referee.prototype.nextCommand = 0; + + /** + * Referee gameEvents. + * @member {Array.} gameEvents + * @memberof proto.Referee + * @instance + */ + Referee.prototype.gameEvents = $util.emptyArray; + + /** + * Referee gameEventProposals. + * @member {Array.} gameEventProposals + * @memberof proto.Referee + * @instance + */ + Referee.prototype.gameEventProposals = $util.emptyArray; + + /** + * Referee currentActionTimeRemaining. + * @member {number|Long} currentActionTimeRemaining + * @memberof proto.Referee + * @instance + */ + Referee.prototype.currentActionTimeRemaining = $util.Long ? $util.Long.fromBits(0,0,false) : 0; + + /** + * Referee statusMessage. + * @member {string} statusMessage + * @memberof proto.Referee + * @instance + */ + Referee.prototype.statusMessage = ""; + + /** + * Creates a new Referee instance using the specified properties. + * @function create + * @memberof proto.Referee + * @static + * @param {proto.IReferee=} [properties] Properties to set + * @returns {proto.Referee} Referee instance + */ + Referee.create = function create(properties) { + return new Referee(properties); + }; + + /** + * Encodes the specified Referee message. Does not implicitly {@link proto.Referee.verify|verify} messages. + * @function encode + * @memberof proto.Referee + * @static + * @param {proto.IReferee} message Referee message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + Referee.encode = function encode(message, writer) { + if (!writer) + writer = $Writer.create(); + writer.uint32(/* id 1, wireType 0 =*/8).uint64(message.packetTimestamp); + writer.uint32(/* id 2, wireType 0 =*/16).int32(message.stage); + if (message.stageTimeLeft != null && Object.hasOwnProperty.call(message, "stageTimeLeft")) + writer.uint32(/* id 3, wireType 0 =*/24).sint64(message.stageTimeLeft); + writer.uint32(/* id 4, wireType 0 =*/32).int32(message.command); + writer.uint32(/* id 5, wireType 0 =*/40).uint32(message.commandCounter); + writer.uint32(/* id 6, wireType 0 =*/48).uint64(message.commandTimestamp); + $root.proto.Referee.TeamInfo.encode(message.yellow, writer.uint32(/* id 7, wireType 2 =*/58).fork()).ldelim(); + $root.proto.Referee.TeamInfo.encode(message.blue, writer.uint32(/* id 8, wireType 2 =*/66).fork()).ldelim(); + if (message.designatedPosition != null && Object.hasOwnProperty.call(message, "designatedPosition")) + $root.proto.Referee.Point.encode(message.designatedPosition, writer.uint32(/* id 9, wireType 2 =*/74).fork()).ldelim(); + if (message.blueTeamOnPositiveHalf != null && Object.hasOwnProperty.call(message, "blueTeamOnPositiveHalf")) + writer.uint32(/* id 10, wireType 0 =*/80).bool(message.blueTeamOnPositiveHalf); + if (message.nextCommand != null && Object.hasOwnProperty.call(message, "nextCommand")) + writer.uint32(/* id 12, wireType 0 =*/96).int32(message.nextCommand); + if (message.currentActionTimeRemaining != null && Object.hasOwnProperty.call(message, "currentActionTimeRemaining")) + writer.uint32(/* id 15, wireType 0 =*/120).int64(message.currentActionTimeRemaining); + if (message.gameEvents != null && message.gameEvents.length) + for (let i = 0; i < message.gameEvents.length; ++i) + $root.proto.GameEvent.encode(message.gameEvents[i], writer.uint32(/* id 16, wireType 2 =*/130).fork()).ldelim(); + if (message.gameEventProposals != null && message.gameEventProposals.length) + for (let i = 0; i < message.gameEventProposals.length; ++i) + $root.proto.GameEventProposalGroup.encode(message.gameEventProposals[i], writer.uint32(/* id 17, wireType 2 =*/138).fork()).ldelim(); + if (message.sourceIdentifier != null && Object.hasOwnProperty.call(message, "sourceIdentifier")) + writer.uint32(/* id 18, wireType 2 =*/146).string(message.sourceIdentifier); + if (message.matchType != null && Object.hasOwnProperty.call(message, "matchType")) + writer.uint32(/* id 19, wireType 0 =*/152).int32(message.matchType); + if (message.statusMessage != null && Object.hasOwnProperty.call(message, "statusMessage")) + writer.uint32(/* id 20, wireType 2 =*/162).string(message.statusMessage); + return writer; + }; + + /** + * Encodes the specified Referee message, length delimited. Does not implicitly {@link proto.Referee.verify|verify} messages. + * @function encodeDelimited + * @memberof proto.Referee + * @static + * @param {proto.IReferee} message Referee message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + Referee.encodeDelimited = function encodeDelimited(message, writer) { + return this.encode(message, writer).ldelim(); + }; + + /** + * Decodes a Referee message from the specified reader or buffer. + * @function decode + * @memberof proto.Referee + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @param {number} [length] Message length if known beforehand + * @returns {proto.Referee} Referee + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + Referee.decode = function decode(reader, length) { + if (!(reader instanceof $Reader)) + reader = $Reader.create(reader); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.Referee(); + while (reader.pos < end) { + let tag = reader.uint32(); + switch (tag >>> 3) { + case 18: { + message.sourceIdentifier = reader.string(); + break; + } + case 19: { + message.matchType = reader.int32(); + break; + } + case 1: { + message.packetTimestamp = reader.uint64(); + break; + } + case 2: { + message.stage = reader.int32(); + break; + } + case 3: { + message.stageTimeLeft = reader.sint64(); + break; + } + case 4: { + message.command = reader.int32(); + break; + } + case 5: { + message.commandCounter = reader.uint32(); + break; + } + case 6: { + message.commandTimestamp = reader.uint64(); + break; + } + case 7: { + message.yellow = $root.proto.Referee.TeamInfo.decode(reader, reader.uint32()); + break; + } + case 8: { + message.blue = $root.proto.Referee.TeamInfo.decode(reader, reader.uint32()); + break; + } + case 9: { + message.designatedPosition = $root.proto.Referee.Point.decode(reader, reader.uint32()); + break; + } + case 10: { + message.blueTeamOnPositiveHalf = reader.bool(); + break; + } + case 12: { + message.nextCommand = reader.int32(); + break; + } + case 16: { + if (!(message.gameEvents && message.gameEvents.length)) + message.gameEvents = []; + message.gameEvents.push($root.proto.GameEvent.decode(reader, reader.uint32())); + break; + } + case 17: { + if (!(message.gameEventProposals && message.gameEventProposals.length)) + message.gameEventProposals = []; + message.gameEventProposals.push($root.proto.GameEventProposalGroup.decode(reader, reader.uint32())); + break; + } + case 15: { + message.currentActionTimeRemaining = reader.int64(); + break; + } + case 20: { + message.statusMessage = reader.string(); + break; + } + default: + reader.skipType(tag & 7); + break; + } + } + if (!message.hasOwnProperty("packetTimestamp")) + throw $util.ProtocolError("missing required 'packetTimestamp'", { instance: message }); + if (!message.hasOwnProperty("stage")) + throw $util.ProtocolError("missing required 'stage'", { instance: message }); + if (!message.hasOwnProperty("command")) + throw $util.ProtocolError("missing required 'command'", { instance: message }); + if (!message.hasOwnProperty("commandCounter")) + throw $util.ProtocolError("missing required 'commandCounter'", { instance: message }); + if (!message.hasOwnProperty("commandTimestamp")) + throw $util.ProtocolError("missing required 'commandTimestamp'", { instance: message }); + if (!message.hasOwnProperty("yellow")) + throw $util.ProtocolError("missing required 'yellow'", { instance: message }); + if (!message.hasOwnProperty("blue")) + throw $util.ProtocolError("missing required 'blue'", { instance: message }); + return message; + }; + + /** + * Decodes a Referee message from the specified reader or buffer, length delimited. + * @function decodeDelimited + * @memberof proto.Referee + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @returns {proto.Referee} Referee + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + Referee.decodeDelimited = function decodeDelimited(reader) { + if (!(reader instanceof $Reader)) + reader = new $Reader(reader); + return this.decode(reader, reader.uint32()); + }; + + /** + * Verifies a Referee message. + * @function verify + * @memberof proto.Referee + * @static + * @param {Object.} message Plain object to verify + * @returns {string|null} `null` if valid, otherwise the reason why it is not + */ + Referee.verify = function verify(message) { + if (typeof message !== "object" || message === null) + return "object expected"; + if (message.sourceIdentifier != null && message.hasOwnProperty("sourceIdentifier")) + if (!$util.isString(message.sourceIdentifier)) + return "sourceIdentifier: string expected"; + if (message.matchType != null && message.hasOwnProperty("matchType")) + switch (message.matchType) { + default: + return "matchType: enum value expected"; + case 0: + case 1: + case 2: + case 3: + break; + } + if (!$util.isInteger(message.packetTimestamp) && !(message.packetTimestamp && $util.isInteger(message.packetTimestamp.low) && $util.isInteger(message.packetTimestamp.high))) + return "packetTimestamp: integer|Long expected"; + switch (message.stage) { + default: + return "stage: enum value expected"; + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + case 6: + case 7: + case 8: + case 9: + case 10: + case 11: + case 12: + case 13: + break; + } + if (message.stageTimeLeft != null && message.hasOwnProperty("stageTimeLeft")) + if (!$util.isInteger(message.stageTimeLeft) && !(message.stageTimeLeft && $util.isInteger(message.stageTimeLeft.low) && $util.isInteger(message.stageTimeLeft.high))) + return "stageTimeLeft: integer|Long expected"; + switch (message.command) { + default: + return "command: enum value expected"; + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + case 6: + case 7: + case 8: + case 9: + case 12: + case 13: + case 16: + case 17: + break; + } + if (!$util.isInteger(message.commandCounter)) + return "commandCounter: integer expected"; + if (!$util.isInteger(message.commandTimestamp) && !(message.commandTimestamp && $util.isInteger(message.commandTimestamp.low) && $util.isInteger(message.commandTimestamp.high))) + return "commandTimestamp: integer|Long expected"; + { + let error = $root.proto.Referee.TeamInfo.verify(message.yellow); + if (error) + return "yellow." + error; + } + { + let error = $root.proto.Referee.TeamInfo.verify(message.blue); + if (error) + return "blue." + error; + } + if (message.designatedPosition != null && message.hasOwnProperty("designatedPosition")) { + let error = $root.proto.Referee.Point.verify(message.designatedPosition); + if (error) + return "designatedPosition." + error; + } + if (message.blueTeamOnPositiveHalf != null && message.hasOwnProperty("blueTeamOnPositiveHalf")) + if (typeof message.blueTeamOnPositiveHalf !== "boolean") + return "blueTeamOnPositiveHalf: boolean expected"; + if (message.nextCommand != null && message.hasOwnProperty("nextCommand")) + switch (message.nextCommand) { + default: + return "nextCommand: enum value expected"; + case 0: + case 1: + case 2: + case 3: + case 4: + case 5: + case 6: + case 7: + case 8: + case 9: + case 12: + case 13: + case 16: + case 17: + break; + } + if (message.gameEvents != null && message.hasOwnProperty("gameEvents")) { + if (!Array.isArray(message.gameEvents)) + return "gameEvents: array expected"; + for (let i = 0; i < message.gameEvents.length; ++i) { + let error = $root.proto.GameEvent.verify(message.gameEvents[i]); + if (error) + return "gameEvents." + error; + } + } + if (message.gameEventProposals != null && message.hasOwnProperty("gameEventProposals")) { + if (!Array.isArray(message.gameEventProposals)) + return "gameEventProposals: array expected"; + for (let i = 0; i < message.gameEventProposals.length; ++i) { + let error = $root.proto.GameEventProposalGroup.verify(message.gameEventProposals[i]); + if (error) + return "gameEventProposals." + error; + } + } + if (message.currentActionTimeRemaining != null && message.hasOwnProperty("currentActionTimeRemaining")) + if (!$util.isInteger(message.currentActionTimeRemaining) && !(message.currentActionTimeRemaining && $util.isInteger(message.currentActionTimeRemaining.low) && $util.isInteger(message.currentActionTimeRemaining.high))) + return "currentActionTimeRemaining: integer|Long expected"; + if (message.statusMessage != null && message.hasOwnProperty("statusMessage")) + if (!$util.isString(message.statusMessage)) + return "statusMessage: string expected"; + return null; + }; + + /** + * Creates a Referee message from a plain object. Also converts values to their respective internal types. + * @function fromObject + * @memberof proto.Referee + * @static + * @param {Object.} object Plain object + * @returns {proto.Referee} Referee + */ + Referee.fromObject = function fromObject(object) { + if (object instanceof $root.proto.Referee) + return object; + let message = new $root.proto.Referee(); + if (object.sourceIdentifier != null) + message.sourceIdentifier = String(object.sourceIdentifier); + switch (object.matchType) { + default: + if (typeof object.matchType === "number") { + message.matchType = object.matchType; + break; + } + break; + case "UNKNOWN_MATCH": + case 0: + message.matchType = 0; + break; + case "GROUP_PHASE": + case 1: + message.matchType = 1; + break; + case "ELIMINATION_PHASE": + case 2: + message.matchType = 2; + break; + case "FRIENDLY": + case 3: + message.matchType = 3; + break; + } + if (object.packetTimestamp != null) + if ($util.Long) + (message.packetTimestamp = $util.Long.fromValue(object.packetTimestamp)).unsigned = true; + else if (typeof object.packetTimestamp === "string") + message.packetTimestamp = parseInt(object.packetTimestamp, 10); + else if (typeof object.packetTimestamp === "number") + message.packetTimestamp = object.packetTimestamp; + else if (typeof object.packetTimestamp === "object") + message.packetTimestamp = new $util.LongBits(object.packetTimestamp.low >>> 0, object.packetTimestamp.high >>> 0).toNumber(true); + switch (object.stage) { + default: + if (typeof object.stage === "number") { + message.stage = object.stage; + break; + } + break; + case "NORMAL_FIRST_HALF_PRE": + case 0: + message.stage = 0; + break; + case "NORMAL_FIRST_HALF": + case 1: + message.stage = 1; + break; + case "NORMAL_HALF_TIME": + case 2: + message.stage = 2; + break; + case "NORMAL_SECOND_HALF_PRE": + case 3: + message.stage = 3; + break; + case "NORMAL_SECOND_HALF": + case 4: + message.stage = 4; + break; + case "EXTRA_TIME_BREAK": + case 5: + message.stage = 5; + break; + case "EXTRA_FIRST_HALF_PRE": + case 6: + message.stage = 6; + break; + case "EXTRA_FIRST_HALF": + case 7: + message.stage = 7; + break; + case "EXTRA_HALF_TIME": + case 8: + message.stage = 8; + break; + case "EXTRA_SECOND_HALF_PRE": + case 9: + message.stage = 9; + break; + case "EXTRA_SECOND_HALF": + case 10: + message.stage = 10; + break; + case "PENALTY_SHOOTOUT_BREAK": + case 11: + message.stage = 11; + break; + case "PENALTY_SHOOTOUT": + case 12: + message.stage = 12; + break; + case "POST_GAME": + case 13: + message.stage = 13; + break; + } + if (object.stageTimeLeft != null) + if ($util.Long) + (message.stageTimeLeft = $util.Long.fromValue(object.stageTimeLeft)).unsigned = false; + else if (typeof object.stageTimeLeft === "string") + message.stageTimeLeft = parseInt(object.stageTimeLeft, 10); + else if (typeof object.stageTimeLeft === "number") + message.stageTimeLeft = object.stageTimeLeft; + else if (typeof object.stageTimeLeft === "object") + message.stageTimeLeft = new $util.LongBits(object.stageTimeLeft.low >>> 0, object.stageTimeLeft.high >>> 0).toNumber(); + switch (object.command) { + default: + if (typeof object.command === "number") { + message.command = object.command; + break; + } + break; + case "HALT": + case 0: + message.command = 0; + break; + case "STOP": + case 1: + message.command = 1; + break; + case "NORMAL_START": + case 2: + message.command = 2; + break; + case "FORCE_START": + case 3: + message.command = 3; + break; + case "PREPARE_KICKOFF_YELLOW": + case 4: + message.command = 4; + break; + case "PREPARE_KICKOFF_BLUE": + case 5: + message.command = 5; + break; + case "PREPARE_PENALTY_YELLOW": + case 6: + message.command = 6; + break; + case "PREPARE_PENALTY_BLUE": + case 7: + message.command = 7; + break; + case "DIRECT_FREE_YELLOW": + case 8: + message.command = 8; + break; + case "DIRECT_FREE_BLUE": + case 9: + message.command = 9; + break; + case "TIMEOUT_YELLOW": + case 12: + message.command = 12; + break; + case "TIMEOUT_BLUE": + case 13: + message.command = 13; + break; + case "BALL_PLACEMENT_YELLOW": + case 16: + message.command = 16; + break; + case "BALL_PLACEMENT_BLUE": + case 17: + message.command = 17; + break; + } + if (object.commandCounter != null) + message.commandCounter = object.commandCounter >>> 0; + if (object.commandTimestamp != null) + if ($util.Long) + (message.commandTimestamp = $util.Long.fromValue(object.commandTimestamp)).unsigned = true; + else if (typeof object.commandTimestamp === "string") + message.commandTimestamp = parseInt(object.commandTimestamp, 10); + else if (typeof object.commandTimestamp === "number") + message.commandTimestamp = object.commandTimestamp; + else if (typeof object.commandTimestamp === "object") + message.commandTimestamp = new $util.LongBits(object.commandTimestamp.low >>> 0, object.commandTimestamp.high >>> 0).toNumber(true); + if (object.yellow != null) { + if (typeof object.yellow !== "object") + throw TypeError(".proto.Referee.yellow: object expected"); + message.yellow = $root.proto.Referee.TeamInfo.fromObject(object.yellow); + } + if (object.blue != null) { + if (typeof object.blue !== "object") + throw TypeError(".proto.Referee.blue: object expected"); + message.blue = $root.proto.Referee.TeamInfo.fromObject(object.blue); + } + if (object.designatedPosition != null) { + if (typeof object.designatedPosition !== "object") + throw TypeError(".proto.Referee.designatedPosition: object expected"); + message.designatedPosition = $root.proto.Referee.Point.fromObject(object.designatedPosition); + } + if (object.blueTeamOnPositiveHalf != null) + message.blueTeamOnPositiveHalf = Boolean(object.blueTeamOnPositiveHalf); + switch (object.nextCommand) { + default: + if (typeof object.nextCommand === "number") { + message.nextCommand = object.nextCommand; + break; + } + break; + case "HALT": + case 0: + message.nextCommand = 0; + break; + case "STOP": + case 1: + message.nextCommand = 1; + break; + case "NORMAL_START": + case 2: + message.nextCommand = 2; + break; + case "FORCE_START": + case 3: + message.nextCommand = 3; + break; + case "PREPARE_KICKOFF_YELLOW": + case 4: + message.nextCommand = 4; + break; + case "PREPARE_KICKOFF_BLUE": + case 5: + message.nextCommand = 5; + break; + case "PREPARE_PENALTY_YELLOW": + case 6: + message.nextCommand = 6; + break; + case "PREPARE_PENALTY_BLUE": + case 7: + message.nextCommand = 7; + break; + case "DIRECT_FREE_YELLOW": + case 8: + message.nextCommand = 8; + break; + case "DIRECT_FREE_BLUE": + case 9: + message.nextCommand = 9; + break; + case "TIMEOUT_YELLOW": + case 12: + message.nextCommand = 12; + break; + case "TIMEOUT_BLUE": + case 13: + message.nextCommand = 13; + break; + case "BALL_PLACEMENT_YELLOW": + case 16: + message.nextCommand = 16; + break; + case "BALL_PLACEMENT_BLUE": + case 17: + message.nextCommand = 17; + break; + } + if (object.gameEvents) { + if (!Array.isArray(object.gameEvents)) + throw TypeError(".proto.Referee.gameEvents: array expected"); + message.gameEvents = []; + for (let i = 0; i < object.gameEvents.length; ++i) { + if (typeof object.gameEvents[i] !== "object") + throw TypeError(".proto.Referee.gameEvents: object expected"); + message.gameEvents[i] = $root.proto.GameEvent.fromObject(object.gameEvents[i]); + } + } + if (object.gameEventProposals) { + if (!Array.isArray(object.gameEventProposals)) + throw TypeError(".proto.Referee.gameEventProposals: array expected"); + message.gameEventProposals = []; + for (let i = 0; i < object.gameEventProposals.length; ++i) { + if (typeof object.gameEventProposals[i] !== "object") + throw TypeError(".proto.Referee.gameEventProposals: object expected"); + message.gameEventProposals[i] = $root.proto.GameEventProposalGroup.fromObject(object.gameEventProposals[i]); + } + } + if (object.currentActionTimeRemaining != null) + if ($util.Long) + (message.currentActionTimeRemaining = $util.Long.fromValue(object.currentActionTimeRemaining)).unsigned = false; + else if (typeof object.currentActionTimeRemaining === "string") + message.currentActionTimeRemaining = parseInt(object.currentActionTimeRemaining, 10); + else if (typeof object.currentActionTimeRemaining === "number") + message.currentActionTimeRemaining = object.currentActionTimeRemaining; + else if (typeof object.currentActionTimeRemaining === "object") + message.currentActionTimeRemaining = new $util.LongBits(object.currentActionTimeRemaining.low >>> 0, object.currentActionTimeRemaining.high >>> 0).toNumber(); + if (object.statusMessage != null) + message.statusMessage = String(object.statusMessage); + return message; + }; + + /** + * Creates a plain object from a Referee message. Also converts values to other types if specified. + * @function toObject + * @memberof proto.Referee + * @static + * @param {proto.Referee} message Referee + * @param {$protobuf.IConversionOptions} [options] Conversion options + * @returns {Object.} Plain object + */ + Referee.toObject = function toObject(message, options) { + if (!options) + options = {}; + let object = {}; + if (options.arrays || options.defaults) { + object.gameEvents = []; + object.gameEventProposals = []; + } + if (options.defaults) { + if ($util.Long) { + let long = new $util.Long(0, 0, true); + object.packetTimestamp = options.longs === String ? long.toString() : options.longs === Number ? long.toNumber() : long; + } else + object.packetTimestamp = options.longs === String ? "0" : 0; + object.stage = options.enums === String ? "NORMAL_FIRST_HALF_PRE" : 0; + if ($util.Long) { + let long = new $util.Long(0, 0, false); + object.stageTimeLeft = options.longs === String ? long.toString() : options.longs === Number ? long.toNumber() : long; + } else + object.stageTimeLeft = options.longs === String ? "0" : 0; + object.command = options.enums === String ? "HALT" : 0; + object.commandCounter = 0; + if ($util.Long) { + let long = new $util.Long(0, 0, true); + object.commandTimestamp = options.longs === String ? long.toString() : options.longs === Number ? long.toNumber() : long; + } else + object.commandTimestamp = options.longs === String ? "0" : 0; + object.yellow = null; + object.blue = null; + object.designatedPosition = null; + object.blueTeamOnPositiveHalf = false; + object.nextCommand = options.enums === String ? "HALT" : 0; + if ($util.Long) { + let long = new $util.Long(0, 0, false); + object.currentActionTimeRemaining = options.longs === String ? long.toString() : options.longs === Number ? long.toNumber() : long; + } else + object.currentActionTimeRemaining = options.longs === String ? "0" : 0; + object.sourceIdentifier = ""; + object.matchType = options.enums === String ? "UNKNOWN_MATCH" : 0; + object.statusMessage = ""; + } + if (message.packetTimestamp != null && message.hasOwnProperty("packetTimestamp")) + if (typeof message.packetTimestamp === "number") + object.packetTimestamp = options.longs === String ? String(message.packetTimestamp) : message.packetTimestamp; + else + object.packetTimestamp = options.longs === String ? $util.Long.prototype.toString.call(message.packetTimestamp) : options.longs === Number ? new $util.LongBits(message.packetTimestamp.low >>> 0, message.packetTimestamp.high >>> 0).toNumber(true) : message.packetTimestamp; + if (message.stage != null && message.hasOwnProperty("stage")) + object.stage = options.enums === String ? $root.proto.Referee.Stage[message.stage] === undefined ? message.stage : $root.proto.Referee.Stage[message.stage] : message.stage; + if (message.stageTimeLeft != null && message.hasOwnProperty("stageTimeLeft")) + if (typeof message.stageTimeLeft === "number") + object.stageTimeLeft = options.longs === String ? String(message.stageTimeLeft) : message.stageTimeLeft; + else + object.stageTimeLeft = options.longs === String ? $util.Long.prototype.toString.call(message.stageTimeLeft) : options.longs === Number ? new $util.LongBits(message.stageTimeLeft.low >>> 0, message.stageTimeLeft.high >>> 0).toNumber() : message.stageTimeLeft; + if (message.command != null && message.hasOwnProperty("command")) + object.command = options.enums === String ? $root.proto.Referee.Command[message.command] === undefined ? message.command : $root.proto.Referee.Command[message.command] : message.command; + if (message.commandCounter != null && message.hasOwnProperty("commandCounter")) + object.commandCounter = message.commandCounter; + if (message.commandTimestamp != null && message.hasOwnProperty("commandTimestamp")) + if (typeof message.commandTimestamp === "number") + object.commandTimestamp = options.longs === String ? String(message.commandTimestamp) : message.commandTimestamp; + else + object.commandTimestamp = options.longs === String ? $util.Long.prototype.toString.call(message.commandTimestamp) : options.longs === Number ? new $util.LongBits(message.commandTimestamp.low >>> 0, message.commandTimestamp.high >>> 0).toNumber(true) : message.commandTimestamp; + if (message.yellow != null && message.hasOwnProperty("yellow")) + object.yellow = $root.proto.Referee.TeamInfo.toObject(message.yellow, options); + if (message.blue != null && message.hasOwnProperty("blue")) + object.blue = $root.proto.Referee.TeamInfo.toObject(message.blue, options); + if (message.designatedPosition != null && message.hasOwnProperty("designatedPosition")) + object.designatedPosition = $root.proto.Referee.Point.toObject(message.designatedPosition, options); + if (message.blueTeamOnPositiveHalf != null && message.hasOwnProperty("blueTeamOnPositiveHalf")) + object.blueTeamOnPositiveHalf = message.blueTeamOnPositiveHalf; + if (message.nextCommand != null && message.hasOwnProperty("nextCommand")) + object.nextCommand = options.enums === String ? $root.proto.Referee.Command[message.nextCommand] === undefined ? message.nextCommand : $root.proto.Referee.Command[message.nextCommand] : message.nextCommand; + if (message.currentActionTimeRemaining != null && message.hasOwnProperty("currentActionTimeRemaining")) + if (typeof message.currentActionTimeRemaining === "number") + object.currentActionTimeRemaining = options.longs === String ? String(message.currentActionTimeRemaining) : message.currentActionTimeRemaining; + else + object.currentActionTimeRemaining = options.longs === String ? $util.Long.prototype.toString.call(message.currentActionTimeRemaining) : options.longs === Number ? new $util.LongBits(message.currentActionTimeRemaining.low >>> 0, message.currentActionTimeRemaining.high >>> 0).toNumber() : message.currentActionTimeRemaining; + if (message.gameEvents && message.gameEvents.length) { + object.gameEvents = []; + for (let j = 0; j < message.gameEvents.length; ++j) + object.gameEvents[j] = $root.proto.GameEvent.toObject(message.gameEvents[j], options); + } + if (message.gameEventProposals && message.gameEventProposals.length) { + object.gameEventProposals = []; + for (let j = 0; j < message.gameEventProposals.length; ++j) + object.gameEventProposals[j] = $root.proto.GameEventProposalGroup.toObject(message.gameEventProposals[j], options); + } + if (message.sourceIdentifier != null && message.hasOwnProperty("sourceIdentifier")) + object.sourceIdentifier = message.sourceIdentifier; + if (message.matchType != null && message.hasOwnProperty("matchType")) + object.matchType = options.enums === String ? $root.proto.MatchType[message.matchType] === undefined ? message.matchType : $root.proto.MatchType[message.matchType] : message.matchType; + if (message.statusMessage != null && message.hasOwnProperty("statusMessage")) + object.statusMessage = message.statusMessage; + return object; + }; + + /** + * Converts this Referee to JSON. + * @function toJSON + * @memberof proto.Referee + * @instance + * @returns {Object.} JSON object + */ + Referee.prototype.toJSON = function toJSON() { + return this.constructor.toObject(this, $protobuf.util.toJSONOptions); + }; + + /** + * Gets the default type url for Referee + * @function getTypeUrl + * @memberof proto.Referee + * @static + * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns {string} The default type url + */ + Referee.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + if (typeUrlPrefix === undefined) { + typeUrlPrefix = "type.googleapis.com"; + } + return typeUrlPrefix + "/proto.Referee"; + }; + + /** + * Stage enum. + * @name proto.Referee.Stage + * @enum {number} + * @property {number} NORMAL_FIRST_HALF_PRE=0 NORMAL_FIRST_HALF_PRE value + * @property {number} NORMAL_FIRST_HALF=1 NORMAL_FIRST_HALF value + * @property {number} NORMAL_HALF_TIME=2 NORMAL_HALF_TIME value + * @property {number} NORMAL_SECOND_HALF_PRE=3 NORMAL_SECOND_HALF_PRE value + * @property {number} NORMAL_SECOND_HALF=4 NORMAL_SECOND_HALF value + * @property {number} EXTRA_TIME_BREAK=5 EXTRA_TIME_BREAK value + * @property {number} EXTRA_FIRST_HALF_PRE=6 EXTRA_FIRST_HALF_PRE value + * @property {number} EXTRA_FIRST_HALF=7 EXTRA_FIRST_HALF value + * @property {number} EXTRA_HALF_TIME=8 EXTRA_HALF_TIME value + * @property {number} EXTRA_SECOND_HALF_PRE=9 EXTRA_SECOND_HALF_PRE value + * @property {number} EXTRA_SECOND_HALF=10 EXTRA_SECOND_HALF value + * @property {number} PENALTY_SHOOTOUT_BREAK=11 PENALTY_SHOOTOUT_BREAK value + * @property {number} PENALTY_SHOOTOUT=12 PENALTY_SHOOTOUT value + * @property {number} POST_GAME=13 POST_GAME value + */ + Referee.Stage = (function() { + const valuesById = {}, values = Object.create(valuesById); + values[valuesById[0] = "NORMAL_FIRST_HALF_PRE"] = 0; + values[valuesById[1] = "NORMAL_FIRST_HALF"] = 1; + values[valuesById[2] = "NORMAL_HALF_TIME"] = 2; + values[valuesById[3] = "NORMAL_SECOND_HALF_PRE"] = 3; + values[valuesById[4] = "NORMAL_SECOND_HALF"] = 4; + values[valuesById[5] = "EXTRA_TIME_BREAK"] = 5; + values[valuesById[6] = "EXTRA_FIRST_HALF_PRE"] = 6; + values[valuesById[7] = "EXTRA_FIRST_HALF"] = 7; + values[valuesById[8] = "EXTRA_HALF_TIME"] = 8; + values[valuesById[9] = "EXTRA_SECOND_HALF_PRE"] = 9; + values[valuesById[10] = "EXTRA_SECOND_HALF"] = 10; + values[valuesById[11] = "PENALTY_SHOOTOUT_BREAK"] = 11; + values[valuesById[12] = "PENALTY_SHOOTOUT"] = 12; + values[valuesById[13] = "POST_GAME"] = 13; + return values; + })(); + + /** + * Command enum. + * @name proto.Referee.Command + * @enum {number} + * @property {number} HALT=0 HALT value + * @property {number} STOP=1 STOP value + * @property {number} NORMAL_START=2 NORMAL_START value + * @property {number} FORCE_START=3 FORCE_START value + * @property {number} PREPARE_KICKOFF_YELLOW=4 PREPARE_KICKOFF_YELLOW value + * @property {number} PREPARE_KICKOFF_BLUE=5 PREPARE_KICKOFF_BLUE value * @property {number} PREPARE_PENALTY_YELLOW=6 PREPARE_PENALTY_YELLOW value * @property {number} PREPARE_PENALTY_BLUE=7 PREPARE_PENALTY_BLUE value * @property {number} DIRECT_FREE_YELLOW=8 DIRECT_FREE_YELLOW value * @property {number} DIRECT_FREE_BLUE=9 DIRECT_FREE_BLUE value - * @property {number} INDIRECT_FREE_YELLOW=10 INDIRECT_FREE_YELLOW value - * @property {number} INDIRECT_FREE_BLUE=11 INDIRECT_FREE_BLUE value * @property {number} TIMEOUT_YELLOW=12 TIMEOUT_YELLOW value * @property {number} TIMEOUT_BLUE=13 TIMEOUT_BLUE value * @property {number} BALL_PLACEMENT_YELLOW=16 BALL_PLACEMENT_YELLOW value * @property {number} BALL_PLACEMENT_BLUE=17 BALL_PLACEMENT_BLUE value */ - SSL_Referee.Command = (function() { + Referee.Command = (function() { const valuesById = {}, values = Object.create(valuesById); values[valuesById[0] = "HALT"] = 0; values[valuesById[1] = "STOP"] = 1; @@ -13187,8 +13660,6 @@ export const proto = $root.proto = (() => { values[valuesById[7] = "PREPARE_PENALTY_BLUE"] = 7; values[valuesById[8] = "DIRECT_FREE_YELLOW"] = 8; values[valuesById[9] = "DIRECT_FREE_BLUE"] = 9; - values[valuesById[10] = "INDIRECT_FREE_YELLOW"] = 10; - values[valuesById[11] = "INDIRECT_FREE_BLUE"] = 11; values[valuesById[12] = "TIMEOUT_YELLOW"] = 12; values[valuesById[13] = "TIMEOUT_BLUE"] = 13; values[valuesById[16] = "BALL_PLACEMENT_YELLOW"] = 16; @@ -13196,11 +13667,11 @@ export const proto = $root.proto = (() => { return values; })(); - SSL_Referee.TeamInfo = (function() { + Referee.TeamInfo = (function() { /** * Properties of a TeamInfo. - * @memberof proto.SSL_Referee + * @memberof proto.Referee * @interface ITeamInfo * @property {string} name TeamInfo name * @property {number} score TeamInfo score @@ -13216,15 +13687,16 @@ export const proto = $root.proto = (() => { * @property {number|null} [maxAllowedBots] TeamInfo maxAllowedBots * @property {boolean|null} [botSubstitutionIntent] TeamInfo botSubstitutionIntent * @property {boolean|null} [ballPlacementFailuresReached] TeamInfo ballPlacementFailuresReached + * @property {boolean|null} [botSubstitutionAllowed] TeamInfo botSubstitutionAllowed */ /** * Constructs a new TeamInfo. - * @memberof proto.SSL_Referee + * @memberof proto.Referee * @classdesc Represents a TeamInfo. * @implements ITeamInfo * @constructor - * @param {proto.SSL_Referee.ITeamInfo=} [properties] Properties to set + * @param {proto.Referee.ITeamInfo=} [properties] Properties to set */ function TeamInfo(properties) { this.yellowCardTimes = []; @@ -13237,7 +13709,7 @@ export const proto = $root.proto = (() => { /** * TeamInfo name. * @member {string} name - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @instance */ TeamInfo.prototype.name = ""; @@ -13245,7 +13717,7 @@ export const proto = $root.proto = (() => { /** * TeamInfo score. * @member {number} score - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @instance */ TeamInfo.prototype.score = 0; @@ -13253,7 +13725,7 @@ export const proto = $root.proto = (() => { /** * TeamInfo redCards. * @member {number} redCards - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @instance */ TeamInfo.prototype.redCards = 0; @@ -13261,7 +13733,7 @@ export const proto = $root.proto = (() => { /** * TeamInfo yellowCardTimes. * @member {Array.} yellowCardTimes - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @instance */ TeamInfo.prototype.yellowCardTimes = $util.emptyArray; @@ -13269,7 +13741,7 @@ export const proto = $root.proto = (() => { /** * TeamInfo yellowCards. * @member {number} yellowCards - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @instance */ TeamInfo.prototype.yellowCards = 0; @@ -13277,7 +13749,7 @@ export const proto = $root.proto = (() => { /** * TeamInfo timeouts. * @member {number} timeouts - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @instance */ TeamInfo.prototype.timeouts = 0; @@ -13285,7 +13757,7 @@ export const proto = $root.proto = (() => { /** * TeamInfo timeoutTime. * @member {number} timeoutTime - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @instance */ TeamInfo.prototype.timeoutTime = 0; @@ -13293,7 +13765,7 @@ export const proto = $root.proto = (() => { /** * TeamInfo goalkeeper. * @member {number} goalkeeper - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @instance */ TeamInfo.prototype.goalkeeper = 0; @@ -13301,7 +13773,7 @@ export const proto = $root.proto = (() => { /** * TeamInfo foulCounter. * @member {number} foulCounter - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @instance */ TeamInfo.prototype.foulCounter = 0; @@ -13309,7 +13781,7 @@ export const proto = $root.proto = (() => { /** * TeamInfo ballPlacementFailures. * @member {number} ballPlacementFailures - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @instance */ TeamInfo.prototype.ballPlacementFailures = 0; @@ -13317,7 +13789,7 @@ export const proto = $root.proto = (() => { /** * TeamInfo canPlaceBall. * @member {boolean} canPlaceBall - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @instance */ TeamInfo.prototype.canPlaceBall = false; @@ -13325,7 +13797,7 @@ export const proto = $root.proto = (() => { /** * TeamInfo maxAllowedBots. * @member {number} maxAllowedBots - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @instance */ TeamInfo.prototype.maxAllowedBots = 0; @@ -13333,7 +13805,7 @@ export const proto = $root.proto = (() => { /** * TeamInfo botSubstitutionIntent. * @member {boolean} botSubstitutionIntent - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @instance */ TeamInfo.prototype.botSubstitutionIntent = false; @@ -13341,29 +13813,37 @@ export const proto = $root.proto = (() => { /** * TeamInfo ballPlacementFailuresReached. * @member {boolean} ballPlacementFailuresReached - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @instance */ TeamInfo.prototype.ballPlacementFailuresReached = false; + /** + * TeamInfo botSubstitutionAllowed. + * @member {boolean} botSubstitutionAllowed + * @memberof proto.Referee.TeamInfo + * @instance + */ + TeamInfo.prototype.botSubstitutionAllowed = false; + /** * Creates a new TeamInfo instance using the specified properties. * @function create - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @static - * @param {proto.SSL_Referee.ITeamInfo=} [properties] Properties to set - * @returns {proto.SSL_Referee.TeamInfo} TeamInfo instance + * @param {proto.Referee.ITeamInfo=} [properties] Properties to set + * @returns {proto.Referee.TeamInfo} TeamInfo instance */ TeamInfo.create = function create(properties) { return new TeamInfo(properties); }; /** - * Encodes the specified TeamInfo message. Does not implicitly {@link proto.SSL_Referee.TeamInfo.verify|verify} messages. + * Encodes the specified TeamInfo message. Does not implicitly {@link proto.Referee.TeamInfo.verify|verify} messages. * @function encode - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @static - * @param {proto.SSL_Referee.ITeamInfo} message TeamInfo message or plain object to encode + * @param {proto.Referee.ITeamInfo} message TeamInfo message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ @@ -13395,15 +13875,17 @@ export const proto = $root.proto = (() => { writer.uint32(/* id 14, wireType 0 =*/112).bool(message.botSubstitutionIntent); if (message.ballPlacementFailuresReached != null && Object.hasOwnProperty.call(message, "ballPlacementFailuresReached")) writer.uint32(/* id 15, wireType 0 =*/120).bool(message.ballPlacementFailuresReached); + if (message.botSubstitutionAllowed != null && Object.hasOwnProperty.call(message, "botSubstitutionAllowed")) + writer.uint32(/* id 16, wireType 0 =*/128).bool(message.botSubstitutionAllowed); return writer; }; /** - * Encodes the specified TeamInfo message, length delimited. Does not implicitly {@link proto.SSL_Referee.TeamInfo.verify|verify} messages. + * Encodes the specified TeamInfo message, length delimited. Does not implicitly {@link proto.Referee.TeamInfo.verify|verify} messages. * @function encodeDelimited - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @static - * @param {proto.SSL_Referee.ITeamInfo} message TeamInfo message or plain object to encode + * @param {proto.Referee.ITeamInfo} message TeamInfo message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ @@ -13414,18 +13896,18 @@ export const proto = $root.proto = (() => { /** * Decodes a TeamInfo message from the specified reader or buffer. * @function decode - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from * @param {number} [length] Message length if known beforehand - * @returns {proto.SSL_Referee.TeamInfo} TeamInfo + * @returns {proto.Referee.TeamInfo} TeamInfo * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ TeamInfo.decode = function decode(reader, length) { if (!(reader instanceof $Reader)) reader = $Reader.create(reader); - let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.SSL_Referee.TeamInfo(); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.Referee.TeamInfo(); while (reader.pos < end) { let tag = reader.uint32(); switch (tag >>> 3) { @@ -13492,6 +13974,10 @@ export const proto = $root.proto = (() => { message.ballPlacementFailuresReached = reader.bool(); break; } + case 16: { + message.botSubstitutionAllowed = reader.bool(); + break; + } default: reader.skipType(tag & 7); break; @@ -13517,10 +14003,10 @@ export const proto = $root.proto = (() => { /** * Decodes a TeamInfo message from the specified reader or buffer, length delimited. * @function decodeDelimited - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @returns {proto.SSL_Referee.TeamInfo} TeamInfo + * @returns {proto.Referee.TeamInfo} TeamInfo * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ @@ -13533,7 +14019,7 @@ export const proto = $root.proto = (() => { /** * Verifies a TeamInfo message. * @function verify - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @static * @param {Object.} message Plain object to verify * @returns {string|null} `null` if valid, otherwise the reason why it is not @@ -13580,21 +14066,24 @@ export const proto = $root.proto = (() => { if (message.ballPlacementFailuresReached != null && message.hasOwnProperty("ballPlacementFailuresReached")) if (typeof message.ballPlacementFailuresReached !== "boolean") return "ballPlacementFailuresReached: boolean expected"; + if (message.botSubstitutionAllowed != null && message.hasOwnProperty("botSubstitutionAllowed")) + if (typeof message.botSubstitutionAllowed !== "boolean") + return "botSubstitutionAllowed: boolean expected"; return null; }; /** * Creates a TeamInfo message from a plain object. Also converts values to their respective internal types. * @function fromObject - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @static * @param {Object.} object Plain object - * @returns {proto.SSL_Referee.TeamInfo} TeamInfo + * @returns {proto.Referee.TeamInfo} TeamInfo */ TeamInfo.fromObject = function fromObject(object) { - if (object instanceof $root.proto.SSL_Referee.TeamInfo) + if (object instanceof $root.proto.Referee.TeamInfo) return object; - let message = new $root.proto.SSL_Referee.TeamInfo(); + let message = new $root.proto.Referee.TeamInfo(); if (object.name != null) message.name = String(object.name); if (object.score != null) @@ -13603,7 +14092,7 @@ export const proto = $root.proto = (() => { message.redCards = object.redCards >>> 0; if (object.yellowCardTimes) { if (!Array.isArray(object.yellowCardTimes)) - throw TypeError(".proto.SSL_Referee.TeamInfo.yellowCardTimes: array expected"); + throw TypeError(".proto.Referee.TeamInfo.yellowCardTimes: array expected"); message.yellowCardTimes = []; for (let i = 0; i < object.yellowCardTimes.length; ++i) message.yellowCardTimes[i] = object.yellowCardTimes[i] >>> 0; @@ -13628,15 +14117,17 @@ export const proto = $root.proto = (() => { message.botSubstitutionIntent = Boolean(object.botSubstitutionIntent); if (object.ballPlacementFailuresReached != null) message.ballPlacementFailuresReached = Boolean(object.ballPlacementFailuresReached); + if (object.botSubstitutionAllowed != null) + message.botSubstitutionAllowed = Boolean(object.botSubstitutionAllowed); return message; }; /** * Creates a plain object from a TeamInfo message. Also converts values to other types if specified. * @function toObject - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @static - * @param {proto.SSL_Referee.TeamInfo} message TeamInfo + * @param {proto.Referee.TeamInfo} message TeamInfo * @param {$protobuf.IConversionOptions} [options] Conversion options * @returns {Object.} Plain object */ @@ -13660,6 +14151,7 @@ export const proto = $root.proto = (() => { object.maxAllowedBots = 0; object.botSubstitutionIntent = false; object.ballPlacementFailuresReached = false; + object.botSubstitutionAllowed = false; } if (message.name != null && message.hasOwnProperty("name")) object.name = message.name; @@ -13692,13 +14184,15 @@ export const proto = $root.proto = (() => { object.botSubstitutionIntent = message.botSubstitutionIntent; if (message.ballPlacementFailuresReached != null && message.hasOwnProperty("ballPlacementFailuresReached")) object.ballPlacementFailuresReached = message.ballPlacementFailuresReached; + if (message.botSubstitutionAllowed != null && message.hasOwnProperty("botSubstitutionAllowed")) + object.botSubstitutionAllowed = message.botSubstitutionAllowed; return object; }; /** * Converts this TeamInfo to JSON. * @function toJSON - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @instance * @returns {Object.} JSON object */ @@ -13709,7 +14203,7 @@ export const proto = $root.proto = (() => { /** * Gets the default type url for TeamInfo * @function getTypeUrl - * @memberof proto.SSL_Referee.TeamInfo + * @memberof proto.Referee.TeamInfo * @static * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns {string} The default type url @@ -13718,17 +14212,17 @@ export const proto = $root.proto = (() => { if (typeUrlPrefix === undefined) { typeUrlPrefix = "type.googleapis.com"; } - return typeUrlPrefix + "/proto.SSL_Referee.TeamInfo"; + return typeUrlPrefix + "/proto.Referee.TeamInfo"; }; return TeamInfo; })(); - SSL_Referee.Point = (function() { + Referee.Point = (function() { /** * Properties of a Point. - * @memberof proto.SSL_Referee + * @memberof proto.Referee * @interface IPoint * @property {number} x Point x * @property {number} y Point y @@ -13736,11 +14230,11 @@ export const proto = $root.proto = (() => { /** * Constructs a new Point. - * @memberof proto.SSL_Referee + * @memberof proto.Referee * @classdesc Represents a Point. * @implements IPoint * @constructor - * @param {proto.SSL_Referee.IPoint=} [properties] Properties to set + * @param {proto.Referee.IPoint=} [properties] Properties to set */ function Point(properties) { if (properties) @@ -13752,7 +14246,7 @@ export const proto = $root.proto = (() => { /** * Point x. * @member {number} x - * @memberof proto.SSL_Referee.Point + * @memberof proto.Referee.Point * @instance */ Point.prototype.x = 0; @@ -13760,7 +14254,7 @@ export const proto = $root.proto = (() => { /** * Point y. * @member {number} y - * @memberof proto.SSL_Referee.Point + * @memberof proto.Referee.Point * @instance */ Point.prototype.y = 0; @@ -13768,21 +14262,21 @@ export const proto = $root.proto = (() => { /** * Creates a new Point instance using the specified properties. * @function create - * @memberof proto.SSL_Referee.Point + * @memberof proto.Referee.Point * @static - * @param {proto.SSL_Referee.IPoint=} [properties] Properties to set - * @returns {proto.SSL_Referee.Point} Point instance + * @param {proto.Referee.IPoint=} [properties] Properties to set + * @returns {proto.Referee.Point} Point instance */ Point.create = function create(properties) { return new Point(properties); }; /** - * Encodes the specified Point message. Does not implicitly {@link proto.SSL_Referee.Point.verify|verify} messages. + * Encodes the specified Point message. Does not implicitly {@link proto.Referee.Point.verify|verify} messages. * @function encode - * @memberof proto.SSL_Referee.Point + * @memberof proto.Referee.Point * @static - * @param {proto.SSL_Referee.IPoint} message Point message or plain object to encode + * @param {proto.Referee.IPoint} message Point message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ @@ -13795,11 +14289,11 @@ export const proto = $root.proto = (() => { }; /** - * Encodes the specified Point message, length delimited. Does not implicitly {@link proto.SSL_Referee.Point.verify|verify} messages. + * Encodes the specified Point message, length delimited. Does not implicitly {@link proto.Referee.Point.verify|verify} messages. * @function encodeDelimited - * @memberof proto.SSL_Referee.Point + * @memberof proto.Referee.Point * @static - * @param {proto.SSL_Referee.IPoint} message Point message or plain object to encode + * @param {proto.Referee.IPoint} message Point message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ @@ -13810,18 +14304,18 @@ export const proto = $root.proto = (() => { /** * Decodes a Point message from the specified reader or buffer. * @function decode - * @memberof proto.SSL_Referee.Point + * @memberof proto.Referee.Point * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from * @param {number} [length] Message length if known beforehand - * @returns {proto.SSL_Referee.Point} Point + * @returns {proto.Referee.Point} Point * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ Point.decode = function decode(reader, length) { if (!(reader instanceof $Reader)) reader = $Reader.create(reader); - let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.SSL_Referee.Point(); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.Referee.Point(); while (reader.pos < end) { let tag = reader.uint32(); switch (tag >>> 3) { @@ -13848,10 +14342,10 @@ export const proto = $root.proto = (() => { /** * Decodes a Point message from the specified reader or buffer, length delimited. * @function decodeDelimited - * @memberof proto.SSL_Referee.Point + * @memberof proto.Referee.Point * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @returns {proto.SSL_Referee.Point} Point + * @returns {proto.Referee.Point} Point * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ @@ -13864,7 +14358,7 @@ export const proto = $root.proto = (() => { /** * Verifies a Point message. * @function verify - * @memberof proto.SSL_Referee.Point + * @memberof proto.Referee.Point * @static * @param {Object.} message Plain object to verify * @returns {string|null} `null` if valid, otherwise the reason why it is not @@ -13882,15 +14376,15 @@ export const proto = $root.proto = (() => { /** * Creates a Point message from a plain object. Also converts values to their respective internal types. * @function fromObject - * @memberof proto.SSL_Referee.Point + * @memberof proto.Referee.Point * @static * @param {Object.} object Plain object - * @returns {proto.SSL_Referee.Point} Point + * @returns {proto.Referee.Point} Point */ Point.fromObject = function fromObject(object) { - if (object instanceof $root.proto.SSL_Referee.Point) + if (object instanceof $root.proto.Referee.Point) return object; - let message = new $root.proto.SSL_Referee.Point(); + let message = new $root.proto.Referee.Point(); if (object.x != null) message.x = Number(object.x); if (object.y != null) @@ -13901,9 +14395,9 @@ export const proto = $root.proto = (() => { /** * Creates a plain object from a Point message. Also converts values to other types if specified. * @function toObject - * @memberof proto.SSL_Referee.Point + * @memberof proto.Referee.Point * @static - * @param {proto.SSL_Referee.Point} message Point + * @param {proto.Referee.Point} message Point * @param {$protobuf.IConversionOptions} [options] Conversion options * @returns {Object.} Plain object */ @@ -13925,7 +14419,7 @@ export const proto = $root.proto = (() => { /** * Converts this Point to JSON. * @function toJSON - * @memberof proto.SSL_Referee.Point + * @memberof proto.Referee.Point * @instance * @returns {Object.} JSON object */ @@ -13936,7 +14430,7 @@ export const proto = $root.proto = (() => { /** * Gets the default type url for Point * @function getTypeUrl - * @memberof proto.SSL_Referee.Point + * @memberof proto.Referee.Point * @static * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns {string} The default type url @@ -13945,13 +14439,13 @@ export const proto = $root.proto = (() => { if (typeUrlPrefix === undefined) { typeUrlPrefix = "type.googleapis.com"; } - return typeUrlPrefix + "/proto.SSL_Referee.Point"; + return typeUrlPrefix + "/proto.Referee.Point"; }; return Point; })(); - return SSL_Referee; + return Referee; })(); proto.GameEventProposalGroup = (function() { @@ -13960,7 +14454,8 @@ export const proto = $root.proto = (() => { * Properties of a GameEventProposalGroup. * @memberof proto * @interface IGameEventProposalGroup - * @property {Array.|null} [gameEvent] GameEventProposalGroup gameEvent + * @property {string|null} [id] GameEventProposalGroup id + * @property {Array.|null} [gameEvents] GameEventProposalGroup gameEvents * @property {boolean|null} [accepted] GameEventProposalGroup accepted */ @@ -13973,7 +14468,7 @@ export const proto = $root.proto = (() => { * @param {proto.IGameEventProposalGroup=} [properties] Properties to set */ function GameEventProposalGroup(properties) { - this.gameEvent = []; + this.gameEvents = []; if (properties) for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) if (properties[keys[i]] != null) @@ -13981,12 +14476,20 @@ export const proto = $root.proto = (() => { } /** - * GameEventProposalGroup gameEvent. - * @member {Array.} gameEvent + * GameEventProposalGroup id. + * @member {string} id + * @memberof proto.GameEventProposalGroup + * @instance + */ + GameEventProposalGroup.prototype.id = ""; + + /** + * GameEventProposalGroup gameEvents. + * @member {Array.} gameEvents * @memberof proto.GameEventProposalGroup * @instance */ - GameEventProposalGroup.prototype.gameEvent = $util.emptyArray; + GameEventProposalGroup.prototype.gameEvents = $util.emptyArray; /** * GameEventProposalGroup accepted. @@ -14020,11 +14523,13 @@ export const proto = $root.proto = (() => { GameEventProposalGroup.encode = function encode(message, writer) { if (!writer) writer = $Writer.create(); - if (message.gameEvent != null && message.gameEvent.length) - for (let i = 0; i < message.gameEvent.length; ++i) - $root.proto.GameEvent.encode(message.gameEvent[i], writer.uint32(/* id 1, wireType 2 =*/10).fork()).ldelim(); + if (message.gameEvents != null && message.gameEvents.length) + for (let i = 0; i < message.gameEvents.length; ++i) + $root.proto.GameEvent.encode(message.gameEvents[i], writer.uint32(/* id 1, wireType 2 =*/10).fork()).ldelim(); if (message.accepted != null && Object.hasOwnProperty.call(message, "accepted")) writer.uint32(/* id 2, wireType 0 =*/16).bool(message.accepted); + if (message.id != null && Object.hasOwnProperty.call(message, "id")) + writer.uint32(/* id 3, wireType 2 =*/26).string(message.id); return writer; }; @@ -14059,10 +14564,14 @@ export const proto = $root.proto = (() => { while (reader.pos < end) { let tag = reader.uint32(); switch (tag >>> 3) { + case 3: { + message.id = reader.string(); + break; + } case 1: { - if (!(message.gameEvent && message.gameEvent.length)) - message.gameEvent = []; - message.gameEvent.push($root.proto.GameEvent.decode(reader, reader.uint32())); + if (!(message.gameEvents && message.gameEvents.length)) + message.gameEvents = []; + message.gameEvents.push($root.proto.GameEvent.decode(reader, reader.uint32())); break; } case 2: { @@ -14104,13 +14613,16 @@ export const proto = $root.proto = (() => { GameEventProposalGroup.verify = function verify(message) { if (typeof message !== "object" || message === null) return "object expected"; - if (message.gameEvent != null && message.hasOwnProperty("gameEvent")) { - if (!Array.isArray(message.gameEvent)) - return "gameEvent: array expected"; - for (let i = 0; i < message.gameEvent.length; ++i) { - let error = $root.proto.GameEvent.verify(message.gameEvent[i]); + if (message.id != null && message.hasOwnProperty("id")) + if (!$util.isString(message.id)) + return "id: string expected"; + if (message.gameEvents != null && message.hasOwnProperty("gameEvents")) { + if (!Array.isArray(message.gameEvents)) + return "gameEvents: array expected"; + for (let i = 0; i < message.gameEvents.length; ++i) { + let error = $root.proto.GameEvent.verify(message.gameEvents[i]); if (error) - return "gameEvent." + error; + return "gameEvents." + error; } } if (message.accepted != null && message.hasOwnProperty("accepted")) @@ -14131,14 +14643,16 @@ export const proto = $root.proto = (() => { if (object instanceof $root.proto.GameEventProposalGroup) return object; let message = new $root.proto.GameEventProposalGroup(); - if (object.gameEvent) { - if (!Array.isArray(object.gameEvent)) - throw TypeError(".proto.GameEventProposalGroup.gameEvent: array expected"); - message.gameEvent = []; - for (let i = 0; i < object.gameEvent.length; ++i) { - if (typeof object.gameEvent[i] !== "object") - throw TypeError(".proto.GameEventProposalGroup.gameEvent: object expected"); - message.gameEvent[i] = $root.proto.GameEvent.fromObject(object.gameEvent[i]); + if (object.id != null) + message.id = String(object.id); + if (object.gameEvents) { + if (!Array.isArray(object.gameEvents)) + throw TypeError(".proto.GameEventProposalGroup.gameEvents: array expected"); + message.gameEvents = []; + for (let i = 0; i < object.gameEvents.length; ++i) { + if (typeof object.gameEvents[i] !== "object") + throw TypeError(".proto.GameEventProposalGroup.gameEvents: object expected"); + message.gameEvents[i] = $root.proto.GameEvent.fromObject(object.gameEvents[i]); } } if (object.accepted != null) @@ -14160,16 +14674,20 @@ export const proto = $root.proto = (() => { options = {}; let object = {}; if (options.arrays || options.defaults) - object.gameEvent = []; - if (options.defaults) + object.gameEvents = []; + if (options.defaults) { object.accepted = false; - if (message.gameEvent && message.gameEvent.length) { - object.gameEvent = []; - for (let j = 0; j < message.gameEvent.length; ++j) - object.gameEvent[j] = $root.proto.GameEvent.toObject(message.gameEvent[j], options); + object.id = ""; + } + if (message.gameEvents && message.gameEvents.length) { + object.gameEvents = []; + for (let j = 0; j < message.gameEvents.length; ++j) + object.gameEvents[j] = $root.proto.GameEvent.toObject(message.gameEvents[j], options); } if (message.accepted != null && message.hasOwnProperty("accepted")) object.accepted = message.accepted; + if (message.id != null && message.hasOwnProperty("id")) + object.id = message.id; return object; }; @@ -14202,14 +14720,34 @@ export const proto = $root.proto = (() => { return GameEventProposalGroup; })(); + /** + * MatchType enum. + * @name proto.MatchType + * @enum {number} + * @property {number} UNKNOWN_MATCH=0 UNKNOWN_MATCH value + * @property {number} GROUP_PHASE=1 GROUP_PHASE value + * @property {number} ELIMINATION_PHASE=2 ELIMINATION_PHASE value + * @property {number} FRIENDLY=3 FRIENDLY value + */ + proto.MatchType = (function() { + const valuesById = {}, values = Object.create(valuesById); + values[valuesById[0] = "UNKNOWN_MATCH"] = 0; + values[valuesById[1] = "GROUP_PHASE"] = 1; + values[valuesById[2] = "ELIMINATION_PHASE"] = 2; + values[valuesById[3] = "FRIENDLY"] = 3; + return values; + })(); + proto.GameEvent = (function() { /** * Properties of a GameEvent. * @memberof proto * @interface IGameEvent + * @property {string|null} [id] GameEvent id * @property {proto.GameEvent.Type|null} [type] GameEvent type * @property {Array.|null} [origin] GameEvent origin + * @property {number|Long|null} [createdTimestamp] GameEvent createdTimestamp * @property {proto.GameEvent.IBallLeftField|null} [ballLeftFieldTouchLine] GameEvent ballLeftFieldTouchLine * @property {proto.GameEvent.IBallLeftField|null} [ballLeftFieldGoalLine] GameEvent ballLeftFieldGoalLine * @property {proto.GameEvent.IAimlessKick|null} [aimlessKick] GameEvent aimlessKick @@ -14221,6 +14759,7 @@ export const proto = $root.proto = (() => { * @property {proto.GameEvent.IBotPushedBot|null} [botPushedBot] GameEvent botPushedBot * @property {proto.GameEvent.IBotHeldBallDeliberately|null} [botHeldBallDeliberately] GameEvent botHeldBallDeliberately * @property {proto.GameEvent.IBotTippedOver|null} [botTippedOver] GameEvent botTippedOver + * @property {proto.GameEvent.IBotDroppedParts|null} [botDroppedParts] GameEvent botDroppedParts * @property {proto.GameEvent.IAttackerTouchedBallInDefenseArea|null} [attackerTouchedBallInDefenseArea] GameEvent attackerTouchedBallInDefenseArea * @property {proto.GameEvent.IBotKickedBallTooFast|null} [botKickedBallTooFast] GameEvent botKickedBallTooFast * @property {proto.GameEvent.IBotCrashUnique|null} [botCrashUnique] GameEvent botCrashUnique @@ -14241,6 +14780,7 @@ export const proto = $root.proto = (() => { * @property {proto.GameEvent.IBotSubstitution|null} [botSubstitution] GameEvent botSubstitution * @property {proto.GameEvent.ITooManyRobots|null} [tooManyRobots] GameEvent tooManyRobots * @property {proto.GameEvent.IChallengeFlag|null} [challengeFlag] GameEvent challengeFlag + * @property {proto.GameEvent.IChallengeFlagHandled|null} [challengeFlagHandled] GameEvent challengeFlagHandled * @property {proto.GameEvent.IEmergencyStop|null} [emergencyStop] GameEvent emergencyStop * @property {proto.GameEvent.IUnsportingBehaviorMinor|null} [unsportingBehaviorMinor] GameEvent unsportingBehaviorMinor * @property {proto.GameEvent.IUnsportingBehaviorMajor|null} [unsportingBehaviorMajor] GameEvent unsportingBehaviorMajor @@ -14262,6 +14802,14 @@ export const proto = $root.proto = (() => { this[keys[i]] = properties[keys[i]]; } + /** + * GameEvent id. + * @member {string} id + * @memberof proto.GameEvent + * @instance + */ + GameEvent.prototype.id = ""; + /** * GameEvent type. * @member {proto.GameEvent.Type} type @@ -14278,6 +14826,14 @@ export const proto = $root.proto = (() => { */ GameEvent.prototype.origin = $util.emptyArray; + /** + * GameEvent createdTimestamp. + * @member {number|Long} createdTimestamp + * @memberof proto.GameEvent + * @instance + */ + GameEvent.prototype.createdTimestamp = $util.Long ? $util.Long.fromBits(0,0,true) : 0; + /** * GameEvent ballLeftFieldTouchLine. * @member {proto.GameEvent.IBallLeftField|null|undefined} ballLeftFieldTouchLine @@ -14366,6 +14922,14 @@ export const proto = $root.proto = (() => { */ GameEvent.prototype.botTippedOver = null; + /** + * GameEvent botDroppedParts. + * @member {proto.GameEvent.IBotDroppedParts|null|undefined} botDroppedParts + * @memberof proto.GameEvent + * @instance + */ + GameEvent.prototype.botDroppedParts = null; + /** * GameEvent attackerTouchedBallInDefenseArea. * @member {proto.GameEvent.IAttackerTouchedBallInDefenseArea|null|undefined} attackerTouchedBallInDefenseArea @@ -14526,6 +15090,14 @@ export const proto = $root.proto = (() => { */ GameEvent.prototype.challengeFlag = null; + /** + * GameEvent challengeFlagHandled. + * @member {proto.GameEvent.IChallengeFlagHandled|null|undefined} challengeFlagHandled + * @memberof proto.GameEvent + * @instance + */ + GameEvent.prototype.challengeFlagHandled = null; + /** * GameEvent emergencyStop. * @member {proto.GameEvent.IEmergencyStop|null|undefined} emergencyStop @@ -14555,12 +15127,12 @@ export const proto = $root.proto = (() => { /** * GameEvent event. - * @member {"ballLeftFieldTouchLine"|"ballLeftFieldGoalLine"|"aimlessKick"|"attackerTooCloseToDefenseArea"|"defenderInDefenseArea"|"boundaryCrossing"|"keeperHeldBall"|"botDribbledBallTooFar"|"botPushedBot"|"botHeldBallDeliberately"|"botTippedOver"|"attackerTouchedBallInDefenseArea"|"botKickedBallTooFast"|"botCrashUnique"|"botCrashDrawn"|"defenderTooCloseToKickPoint"|"botTooFastInStop"|"botInterferedPlacement"|"possibleGoal"|"goal"|"invalidGoal"|"attackerDoubleTouchedBall"|"placementSucceeded"|"penaltyKickFailed"|"noProgressInGame"|"placementFailed"|"multipleCards"|"multipleFouls"|"botSubstitution"|"tooManyRobots"|"challengeFlag"|"emergencyStop"|"unsportingBehaviorMinor"|"unsportingBehaviorMajor"|undefined} event + * @member {"ballLeftFieldTouchLine"|"ballLeftFieldGoalLine"|"aimlessKick"|"attackerTooCloseToDefenseArea"|"defenderInDefenseArea"|"boundaryCrossing"|"keeperHeldBall"|"botDribbledBallTooFar"|"botPushedBot"|"botHeldBallDeliberately"|"botTippedOver"|"botDroppedParts"|"attackerTouchedBallInDefenseArea"|"botKickedBallTooFast"|"botCrashUnique"|"botCrashDrawn"|"defenderTooCloseToKickPoint"|"botTooFastInStop"|"botInterferedPlacement"|"possibleGoal"|"goal"|"invalidGoal"|"attackerDoubleTouchedBall"|"placementSucceeded"|"penaltyKickFailed"|"noProgressInGame"|"placementFailed"|"multipleCards"|"multipleFouls"|"botSubstitution"|"tooManyRobots"|"challengeFlag"|"challengeFlagHandled"|"emergencyStop"|"unsportingBehaviorMinor"|"unsportingBehaviorMajor"|undefined} event * @memberof proto.GameEvent * @instance */ Object.defineProperty(GameEvent.prototype, "event", { - get: $util.oneOfGetter($oneOfFields = ["ballLeftFieldTouchLine", "ballLeftFieldGoalLine", "aimlessKick", "attackerTooCloseToDefenseArea", "defenderInDefenseArea", "boundaryCrossing", "keeperHeldBall", "botDribbledBallTooFar", "botPushedBot", "botHeldBallDeliberately", "botTippedOver", "attackerTouchedBallInDefenseArea", "botKickedBallTooFast", "botCrashUnique", "botCrashDrawn", "defenderTooCloseToKickPoint", "botTooFastInStop", "botInterferedPlacement", "possibleGoal", "goal", "invalidGoal", "attackerDoubleTouchedBall", "placementSucceeded", "penaltyKickFailed", "noProgressInGame", "placementFailed", "multipleCards", "multipleFouls", "botSubstitution", "tooManyRobots", "challengeFlag", "emergencyStop", "unsportingBehaviorMinor", "unsportingBehaviorMajor"]), + get: $util.oneOfGetter($oneOfFields = ["ballLeftFieldTouchLine", "ballLeftFieldGoalLine", "aimlessKick", "attackerTooCloseToDefenseArea", "defenderInDefenseArea", "boundaryCrossing", "keeperHeldBall", "botDribbledBallTooFar", "botPushedBot", "botHeldBallDeliberately", "botTippedOver", "botDroppedParts", "attackerTouchedBallInDefenseArea", "botKickedBallTooFast", "botCrashUnique", "botCrashDrawn", "defenderTooCloseToKickPoint", "botTooFastInStop", "botInterferedPlacement", "possibleGoal", "goal", "invalidGoal", "attackerDoubleTouchedBall", "placementSucceeded", "penaltyKickFailed", "noProgressInGame", "placementFailed", "multipleCards", "multipleFouls", "botSubstitution", "tooManyRobots", "challengeFlag", "challengeFlagHandled", "emergencyStop", "unsportingBehaviorMinor", "unsportingBehaviorMajor"]), set: $util.oneOfSetter($oneOfFields) }); @@ -14661,6 +15233,14 @@ export const proto = $root.proto = (() => { $root.proto.GameEvent.ChallengeFlag.encode(message.challengeFlag, writer.uint32(/* id 46, wireType 2 =*/370).fork()).ldelim(); if (message.emergencyStop != null && Object.hasOwnProperty.call(message, "emergencyStop")) $root.proto.GameEvent.EmergencyStop.encode(message.emergencyStop, writer.uint32(/* id 47, wireType 2 =*/378).fork()).ldelim(); + if (message.challengeFlagHandled != null && Object.hasOwnProperty.call(message, "challengeFlagHandled")) + $root.proto.GameEvent.ChallengeFlagHandled.encode(message.challengeFlagHandled, writer.uint32(/* id 48, wireType 2 =*/386).fork()).ldelim(); + if (message.createdTimestamp != null && Object.hasOwnProperty.call(message, "createdTimestamp")) + writer.uint32(/* id 49, wireType 0 =*/392).uint64(message.createdTimestamp); + if (message.id != null && Object.hasOwnProperty.call(message, "id")) + writer.uint32(/* id 50, wireType 2 =*/402).string(message.id); + if (message.botDroppedParts != null && Object.hasOwnProperty.call(message, "botDroppedParts")) + $root.proto.GameEvent.BotDroppedParts.encode(message.botDroppedParts, writer.uint32(/* id 51, wireType 2 =*/410).fork()).ldelim(); return writer; }; @@ -14695,6 +15275,10 @@ export const proto = $root.proto = (() => { while (reader.pos < end) { let tag = reader.uint32(); switch (tag >>> 3) { + case 50: { + message.id = reader.string(); + break; + } case 40: { message.type = reader.int32(); break; @@ -14705,6 +15289,10 @@ export const proto = $root.proto = (() => { message.origin.push(reader.string()); break; } + case 49: { + message.createdTimestamp = reader.uint64(); + break; + } case 6: { message.ballLeftFieldTouchLine = $root.proto.GameEvent.BallLeftField.decode(reader, reader.uint32()); break; @@ -14749,6 +15337,10 @@ export const proto = $root.proto = (() => { message.botTippedOver = $root.proto.GameEvent.BotTippedOver.decode(reader, reader.uint32()); break; } + case 51: { + message.botDroppedParts = $root.proto.GameEvent.BotDroppedParts.decode(reader, reader.uint32()); + break; + } case 15: { message.attackerTouchedBallInDefenseArea = $root.proto.GameEvent.AttackerTouchedBallInDefenseArea.decode(reader, reader.uint32()); break; @@ -14829,6 +15421,10 @@ export const proto = $root.proto = (() => { message.challengeFlag = $root.proto.GameEvent.ChallengeFlag.decode(reader, reader.uint32()); break; } + case 48: { + message.challengeFlagHandled = $root.proto.GameEvent.ChallengeFlagHandled.decode(reader, reader.uint32()); + break; + } case 47: { message.emergencyStop = $root.proto.GameEvent.EmergencyStop.decode(reader, reader.uint32()); break; @@ -14877,6 +15473,9 @@ export const proto = $root.proto = (() => { if (typeof message !== "object" || message === null) return "object expected"; let properties = {}; + if (message.id != null && message.hasOwnProperty("id")) + if (!$util.isString(message.id)) + return "id: string expected"; if (message.type != null && message.hasOwnProperty("type")) switch (message.type) { default: @@ -14893,6 +15492,7 @@ export const proto = $root.proto = (() => { case 24: case 26: case 27: + case 47: case 15: case 18: case 22: @@ -14913,6 +15513,7 @@ export const proto = $root.proto = (() => { case 37: case 38: case 44: + case 46: case 45: case 35: case 36: @@ -14925,6 +15526,9 @@ export const proto = $root.proto = (() => { if (!$util.isString(message.origin[i])) return "origin: string[] expected"; } + if (message.createdTimestamp != null && message.hasOwnProperty("createdTimestamp")) + if (!$util.isInteger(message.createdTimestamp) && !(message.createdTimestamp && $util.isInteger(message.createdTimestamp.low) && $util.isInteger(message.createdTimestamp.high))) + return "createdTimestamp: integer|Long expected"; if (message.ballLeftFieldTouchLine != null && message.hasOwnProperty("ballLeftFieldTouchLine")) { properties.event = 1; { @@ -15033,6 +15637,16 @@ export const proto = $root.proto = (() => { return "botTippedOver." + error; } } + if (message.botDroppedParts != null && message.hasOwnProperty("botDroppedParts")) { + if (properties.event === 1) + return "event: multiple values"; + properties.event = 1; + { + let error = $root.proto.GameEvent.BotDroppedParts.verify(message.botDroppedParts); + if (error) + return "botDroppedParts." + error; + } + } if (message.attackerTouchedBallInDefenseArea != null && message.hasOwnProperty("attackerTouchedBallInDefenseArea")) { if (properties.event === 1) return "event: multiple values"; @@ -15233,6 +15847,16 @@ export const proto = $root.proto = (() => { return "challengeFlag." + error; } } + if (message.challengeFlagHandled != null && message.hasOwnProperty("challengeFlagHandled")) { + if (properties.event === 1) + return "event: multiple values"; + properties.event = 1; + { + let error = $root.proto.GameEvent.ChallengeFlagHandled.verify(message.challengeFlagHandled); + if (error) + return "challengeFlagHandled." + error; + } + } if (message.emergencyStop != null && message.hasOwnProperty("emergencyStop")) { if (properties.event === 1) return "event: multiple values"; @@ -15278,6 +15902,8 @@ export const proto = $root.proto = (() => { if (object instanceof $root.proto.GameEvent) return object; let message = new $root.proto.GameEvent(); + if (object.id != null) + message.id = String(object.id); switch (object.type) { default: if (typeof object.type === "number") { @@ -15333,6 +15959,10 @@ export const proto = $root.proto = (() => { case 27: message.type = 27; break; + case "BOT_DROPPED_PARTS": + case 47: + message.type = 47; + break; case "ATTACKER_TOUCHED_BALL_IN_DEFENSE_AREA": case 15: message.type = 15; @@ -15413,6 +16043,10 @@ export const proto = $root.proto = (() => { case 44: message.type = 44; break; + case "CHALLENGE_FLAG_HANDLED": + case 46: + message.type = 46; + break; case "EMERGENCY_STOP": case 45: message.type = 45; @@ -15433,6 +16067,15 @@ export const proto = $root.proto = (() => { for (let i = 0; i < object.origin.length; ++i) message.origin[i] = String(object.origin[i]); } + if (object.createdTimestamp != null) + if ($util.Long) + (message.createdTimestamp = $util.Long.fromValue(object.createdTimestamp)).unsigned = true; + else if (typeof object.createdTimestamp === "string") + message.createdTimestamp = parseInt(object.createdTimestamp, 10); + else if (typeof object.createdTimestamp === "number") + message.createdTimestamp = object.createdTimestamp; + else if (typeof object.createdTimestamp === "object") + message.createdTimestamp = new $util.LongBits(object.createdTimestamp.low >>> 0, object.createdTimestamp.high >>> 0).toNumber(true); if (object.ballLeftFieldTouchLine != null) { if (typeof object.ballLeftFieldTouchLine !== "object") throw TypeError(".proto.GameEvent.ballLeftFieldTouchLine: object expected"); @@ -15488,6 +16131,11 @@ export const proto = $root.proto = (() => { throw TypeError(".proto.GameEvent.botTippedOver: object expected"); message.botTippedOver = $root.proto.GameEvent.BotTippedOver.fromObject(object.botTippedOver); } + if (object.botDroppedParts != null) { + if (typeof object.botDroppedParts !== "object") + throw TypeError(".proto.GameEvent.botDroppedParts: object expected"); + message.botDroppedParts = $root.proto.GameEvent.BotDroppedParts.fromObject(object.botDroppedParts); + } if (object.attackerTouchedBallInDefenseArea != null) { if (typeof object.attackerTouchedBallInDefenseArea !== "object") throw TypeError(".proto.GameEvent.attackerTouchedBallInDefenseArea: object expected"); @@ -15588,6 +16236,11 @@ export const proto = $root.proto = (() => { throw TypeError(".proto.GameEvent.challengeFlag: object expected"); message.challengeFlag = $root.proto.GameEvent.ChallengeFlag.fromObject(object.challengeFlag); } + if (object.challengeFlagHandled != null) { + if (typeof object.challengeFlagHandled !== "object") + throw TypeError(".proto.GameEvent.challengeFlagHandled: object expected"); + message.challengeFlagHandled = $root.proto.GameEvent.ChallengeFlagHandled.fromObject(object.challengeFlagHandled); + } if (object.emergencyStop != null) { if (typeof object.emergencyStop !== "object") throw TypeError(".proto.GameEvent.emergencyStop: object expected"); @@ -15621,8 +16274,15 @@ export const proto = $root.proto = (() => { let object = {}; if (options.arrays || options.defaults) object.origin = []; - if (options.defaults) + if (options.defaults) { object.type = options.enums === String ? "UNKNOWN_GAME_EVENT_TYPE" : 0; + if ($util.Long) { + let long = new $util.Long(0, 0, true); + object.createdTimestamp = options.longs === String ? long.toString() : options.longs === Number ? long.toNumber() : long; + } else + object.createdTimestamp = options.longs === String ? "0" : 0; + object.id = ""; + } if (message.noProgressInGame != null && message.hasOwnProperty("noProgressInGame")) { object.noProgressInGame = $root.proto.GameEvent.NoProgressInGame.toObject(message.noProgressInGame, options); if (options.oneofs) @@ -15800,6 +16460,23 @@ export const proto = $root.proto = (() => { if (options.oneofs) object.event = "emergencyStop"; } + if (message.challengeFlagHandled != null && message.hasOwnProperty("challengeFlagHandled")) { + object.challengeFlagHandled = $root.proto.GameEvent.ChallengeFlagHandled.toObject(message.challengeFlagHandled, options); + if (options.oneofs) + object.event = "challengeFlagHandled"; + } + if (message.createdTimestamp != null && message.hasOwnProperty("createdTimestamp")) + if (typeof message.createdTimestamp === "number") + object.createdTimestamp = options.longs === String ? String(message.createdTimestamp) : message.createdTimestamp; + else + object.createdTimestamp = options.longs === String ? $util.Long.prototype.toString.call(message.createdTimestamp) : options.longs === Number ? new $util.LongBits(message.createdTimestamp.low >>> 0, message.createdTimestamp.high >>> 0).toNumber(true) : message.createdTimestamp; + if (message.id != null && message.hasOwnProperty("id")) + object.id = message.id; + if (message.botDroppedParts != null && message.hasOwnProperty("botDroppedParts")) { + object.botDroppedParts = $root.proto.GameEvent.BotDroppedParts.toObject(message.botDroppedParts, options); + if (options.oneofs) + object.event = "botDroppedParts"; + } return object; }; @@ -19443,6 +20120,313 @@ export const proto = $root.proto = (() => { return BotTippedOver; })(); + GameEvent.BotDroppedParts = (function() { + + /** + * Properties of a BotDroppedParts. + * @memberof proto.GameEvent + * @interface IBotDroppedParts + * @property {proto.Team} byTeam BotDroppedParts byTeam + * @property {number|null} [byBot] BotDroppedParts byBot + * @property {proto.IVector2|null} [location] BotDroppedParts location + * @property {proto.IVector2|null} [ballLocation] BotDroppedParts ballLocation + */ + + /** + * Constructs a new BotDroppedParts. + * @memberof proto.GameEvent + * @classdesc Represents a BotDroppedParts. + * @implements IBotDroppedParts + * @constructor + * @param {proto.GameEvent.IBotDroppedParts=} [properties] Properties to set + */ + function BotDroppedParts(properties) { + if (properties) + for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) + if (properties[keys[i]] != null) + this[keys[i]] = properties[keys[i]]; + } + + /** + * BotDroppedParts byTeam. + * @member {proto.Team} byTeam + * @memberof proto.GameEvent.BotDroppedParts + * @instance + */ + BotDroppedParts.prototype.byTeam = 0; + + /** + * BotDroppedParts byBot. + * @member {number} byBot + * @memberof proto.GameEvent.BotDroppedParts + * @instance + */ + BotDroppedParts.prototype.byBot = 0; + + /** + * BotDroppedParts location. + * @member {proto.IVector2|null|undefined} location + * @memberof proto.GameEvent.BotDroppedParts + * @instance + */ + BotDroppedParts.prototype.location = null; + + /** + * BotDroppedParts ballLocation. + * @member {proto.IVector2|null|undefined} ballLocation + * @memberof proto.GameEvent.BotDroppedParts + * @instance + */ + BotDroppedParts.prototype.ballLocation = null; + + /** + * Creates a new BotDroppedParts instance using the specified properties. + * @function create + * @memberof proto.GameEvent.BotDroppedParts + * @static + * @param {proto.GameEvent.IBotDroppedParts=} [properties] Properties to set + * @returns {proto.GameEvent.BotDroppedParts} BotDroppedParts instance + */ + BotDroppedParts.create = function create(properties) { + return new BotDroppedParts(properties); + }; + + /** + * Encodes the specified BotDroppedParts message. Does not implicitly {@link proto.GameEvent.BotDroppedParts.verify|verify} messages. + * @function encode + * @memberof proto.GameEvent.BotDroppedParts + * @static + * @param {proto.GameEvent.IBotDroppedParts} message BotDroppedParts message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + BotDroppedParts.encode = function encode(message, writer) { + if (!writer) + writer = $Writer.create(); + writer.uint32(/* id 1, wireType 0 =*/8).int32(message.byTeam); + if (message.byBot != null && Object.hasOwnProperty.call(message, "byBot")) + writer.uint32(/* id 2, wireType 0 =*/16).uint32(message.byBot); + if (message.location != null && Object.hasOwnProperty.call(message, "location")) + $root.proto.Vector2.encode(message.location, writer.uint32(/* id 3, wireType 2 =*/26).fork()).ldelim(); + if (message.ballLocation != null && Object.hasOwnProperty.call(message, "ballLocation")) + $root.proto.Vector2.encode(message.ballLocation, writer.uint32(/* id 4, wireType 2 =*/34).fork()).ldelim(); + return writer; + }; + + /** + * Encodes the specified BotDroppedParts message, length delimited. Does not implicitly {@link proto.GameEvent.BotDroppedParts.verify|verify} messages. + * @function encodeDelimited + * @memberof proto.GameEvent.BotDroppedParts + * @static + * @param {proto.GameEvent.IBotDroppedParts} message BotDroppedParts message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + BotDroppedParts.encodeDelimited = function encodeDelimited(message, writer) { + return this.encode(message, writer).ldelim(); + }; + + /** + * Decodes a BotDroppedParts message from the specified reader or buffer. + * @function decode + * @memberof proto.GameEvent.BotDroppedParts + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @param {number} [length] Message length if known beforehand + * @returns {proto.GameEvent.BotDroppedParts} BotDroppedParts + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + BotDroppedParts.decode = function decode(reader, length) { + if (!(reader instanceof $Reader)) + reader = $Reader.create(reader); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.GameEvent.BotDroppedParts(); + while (reader.pos < end) { + let tag = reader.uint32(); + switch (tag >>> 3) { + case 1: { + message.byTeam = reader.int32(); + break; + } + case 2: { + message.byBot = reader.uint32(); + break; + } + case 3: { + message.location = $root.proto.Vector2.decode(reader, reader.uint32()); + break; + } + case 4: { + message.ballLocation = $root.proto.Vector2.decode(reader, reader.uint32()); + break; + } + default: + reader.skipType(tag & 7); + break; + } + } + if (!message.hasOwnProperty("byTeam")) + throw $util.ProtocolError("missing required 'byTeam'", { instance: message }); + return message; + }; + + /** + * Decodes a BotDroppedParts message from the specified reader or buffer, length delimited. + * @function decodeDelimited + * @memberof proto.GameEvent.BotDroppedParts + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @returns {proto.GameEvent.BotDroppedParts} BotDroppedParts + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + BotDroppedParts.decodeDelimited = function decodeDelimited(reader) { + if (!(reader instanceof $Reader)) + reader = new $Reader(reader); + return this.decode(reader, reader.uint32()); + }; + + /** + * Verifies a BotDroppedParts message. + * @function verify + * @memberof proto.GameEvent.BotDroppedParts + * @static + * @param {Object.} message Plain object to verify + * @returns {string|null} `null` if valid, otherwise the reason why it is not + */ + BotDroppedParts.verify = function verify(message) { + if (typeof message !== "object" || message === null) + return "object expected"; + switch (message.byTeam) { + default: + return "byTeam: enum value expected"; + case 0: + case 1: + case 2: + break; + } + if (message.byBot != null && message.hasOwnProperty("byBot")) + if (!$util.isInteger(message.byBot)) + return "byBot: integer expected"; + if (message.location != null && message.hasOwnProperty("location")) { + let error = $root.proto.Vector2.verify(message.location); + if (error) + return "location." + error; + } + if (message.ballLocation != null && message.hasOwnProperty("ballLocation")) { + let error = $root.proto.Vector2.verify(message.ballLocation); + if (error) + return "ballLocation." + error; + } + return null; + }; + + /** + * Creates a BotDroppedParts message from a plain object. Also converts values to their respective internal types. + * @function fromObject + * @memberof proto.GameEvent.BotDroppedParts + * @static + * @param {Object.} object Plain object + * @returns {proto.GameEvent.BotDroppedParts} BotDroppedParts + */ + BotDroppedParts.fromObject = function fromObject(object) { + if (object instanceof $root.proto.GameEvent.BotDroppedParts) + return object; + let message = new $root.proto.GameEvent.BotDroppedParts(); + switch (object.byTeam) { + default: + if (typeof object.byTeam === "number") { + message.byTeam = object.byTeam; + break; + } + break; + case "UNKNOWN": + case 0: + message.byTeam = 0; + break; + case "YELLOW": + case 1: + message.byTeam = 1; + break; + case "BLUE": + case 2: + message.byTeam = 2; + break; + } + if (object.byBot != null) + message.byBot = object.byBot >>> 0; + if (object.location != null) { + if (typeof object.location !== "object") + throw TypeError(".proto.GameEvent.BotDroppedParts.location: object expected"); + message.location = $root.proto.Vector2.fromObject(object.location); + } + if (object.ballLocation != null) { + if (typeof object.ballLocation !== "object") + throw TypeError(".proto.GameEvent.BotDroppedParts.ballLocation: object expected"); + message.ballLocation = $root.proto.Vector2.fromObject(object.ballLocation); + } + return message; + }; + + /** + * Creates a plain object from a BotDroppedParts message. Also converts values to other types if specified. + * @function toObject + * @memberof proto.GameEvent.BotDroppedParts + * @static + * @param {proto.GameEvent.BotDroppedParts} message BotDroppedParts + * @param {$protobuf.IConversionOptions} [options] Conversion options + * @returns {Object.} Plain object + */ + BotDroppedParts.toObject = function toObject(message, options) { + if (!options) + options = {}; + let object = {}; + if (options.defaults) { + object.byTeam = options.enums === String ? "UNKNOWN" : 0; + object.byBot = 0; + object.location = null; + object.ballLocation = null; + } + if (message.byTeam != null && message.hasOwnProperty("byTeam")) + object.byTeam = options.enums === String ? $root.proto.Team[message.byTeam] === undefined ? message.byTeam : $root.proto.Team[message.byTeam] : message.byTeam; + if (message.byBot != null && message.hasOwnProperty("byBot")) + object.byBot = message.byBot; + if (message.location != null && message.hasOwnProperty("location")) + object.location = $root.proto.Vector2.toObject(message.location, options); + if (message.ballLocation != null && message.hasOwnProperty("ballLocation")) + object.ballLocation = $root.proto.Vector2.toObject(message.ballLocation, options); + return object; + }; + + /** + * Converts this BotDroppedParts to JSON. + * @function toJSON + * @memberof proto.GameEvent.BotDroppedParts + * @instance + * @returns {Object.} JSON object + */ + BotDroppedParts.prototype.toJSON = function toJSON() { + return this.constructor.toObject(this, $protobuf.util.toJSONOptions); + }; + + /** + * Gets the default type url for BotDroppedParts + * @function getTypeUrl + * @memberof proto.GameEvent.BotDroppedParts + * @static + * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns {string} The default type url + */ + BotDroppedParts.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + if (typeUrlPrefix === undefined) { + typeUrlPrefix = "type.googleapis.com"; + } + return typeUrlPrefix + "/proto.GameEvent.BotDroppedParts"; + }; + + return BotDroppedParts; + })(); + GameEvent.DefenderInDefenseArea = (function() { /** @@ -22735,6 +23719,7 @@ export const proto = $root.proto = (() => { * @memberof proto.GameEvent * @interface IMultipleFouls * @property {proto.Team} byTeam MultipleFouls byTeam + * @property {Array.|null} [causedGameEvents] MultipleFouls causedGameEvents */ /** @@ -22746,6 +23731,7 @@ export const proto = $root.proto = (() => { * @param {proto.GameEvent.IMultipleFouls=} [properties] Properties to set */ function MultipleFouls(properties) { + this.causedGameEvents = []; if (properties) for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) if (properties[keys[i]] != null) @@ -22760,6 +23746,14 @@ export const proto = $root.proto = (() => { */ MultipleFouls.prototype.byTeam = 0; + /** + * MultipleFouls causedGameEvents. + * @member {Array.} causedGameEvents + * @memberof proto.GameEvent.MultipleFouls + * @instance + */ + MultipleFouls.prototype.causedGameEvents = $util.emptyArray; + /** * Creates a new MultipleFouls instance using the specified properties. * @function create @@ -22785,6 +23779,9 @@ export const proto = $root.proto = (() => { if (!writer) writer = $Writer.create(); writer.uint32(/* id 1, wireType 0 =*/8).int32(message.byTeam); + if (message.causedGameEvents != null && message.causedGameEvents.length) + for (let i = 0; i < message.causedGameEvents.length; ++i) + $root.proto.GameEvent.encode(message.causedGameEvents[i], writer.uint32(/* id 2, wireType 2 =*/18).fork()).ldelim(); return writer; }; @@ -22823,6 +23820,12 @@ export const proto = $root.proto = (() => { message.byTeam = reader.int32(); break; } + case 2: { + if (!(message.causedGameEvents && message.causedGameEvents.length)) + message.causedGameEvents = []; + message.causedGameEvents.push($root.proto.GameEvent.decode(reader, reader.uint32())); + break; + } default: reader.skipType(tag & 7); break; @@ -22868,6 +23871,15 @@ export const proto = $root.proto = (() => { case 2: break; } + if (message.causedGameEvents != null && message.hasOwnProperty("causedGameEvents")) { + if (!Array.isArray(message.causedGameEvents)) + return "causedGameEvents: array expected"; + for (let i = 0; i < message.causedGameEvents.length; ++i) { + let error = $root.proto.GameEvent.verify(message.causedGameEvents[i]); + if (error) + return "causedGameEvents." + error; + } + } return null; }; @@ -22903,6 +23915,16 @@ export const proto = $root.proto = (() => { message.byTeam = 2; break; } + if (object.causedGameEvents) { + if (!Array.isArray(object.causedGameEvents)) + throw TypeError(".proto.GameEvent.MultipleFouls.causedGameEvents: array expected"); + message.causedGameEvents = []; + for (let i = 0; i < object.causedGameEvents.length; ++i) { + if (typeof object.causedGameEvents[i] !== "object") + throw TypeError(".proto.GameEvent.MultipleFouls.causedGameEvents: object expected"); + message.causedGameEvents[i] = $root.proto.GameEvent.fromObject(object.causedGameEvents[i]); + } + } return message; }; @@ -22919,10 +23941,17 @@ export const proto = $root.proto = (() => { if (!options) options = {}; let object = {}; + if (options.arrays || options.defaults) + object.causedGameEvents = []; if (options.defaults) object.byTeam = options.enums === String ? "UNKNOWN" : 0; if (message.byTeam != null && message.hasOwnProperty("byTeam")) object.byTeam = options.enums === String ? $root.proto.Team[message.byTeam] === undefined ? message.byTeam : $root.proto.Team[message.byTeam] : message.byTeam; + if (message.causedGameEvents && message.causedGameEvents.length) { + object.causedGameEvents = []; + for (let j = 0; j < message.causedGameEvents.length; ++j) + object.causedGameEvents[j] = $root.proto.GameEvent.toObject(message.causedGameEvents[j], options); + } return object; }; @@ -25679,6 +26708,257 @@ export const proto = $root.proto = (() => { return ChallengeFlag; })(); + GameEvent.ChallengeFlagHandled = (function() { + + /** + * Properties of a ChallengeFlagHandled. + * @memberof proto.GameEvent + * @interface IChallengeFlagHandled + * @property {proto.Team} byTeam ChallengeFlagHandled byTeam + * @property {boolean} accepted ChallengeFlagHandled accepted + */ + + /** + * Constructs a new ChallengeFlagHandled. + * @memberof proto.GameEvent + * @classdesc Represents a ChallengeFlagHandled. + * @implements IChallengeFlagHandled + * @constructor + * @param {proto.GameEvent.IChallengeFlagHandled=} [properties] Properties to set + */ + function ChallengeFlagHandled(properties) { + if (properties) + for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) + if (properties[keys[i]] != null) + this[keys[i]] = properties[keys[i]]; + } + + /** + * ChallengeFlagHandled byTeam. + * @member {proto.Team} byTeam + * @memberof proto.GameEvent.ChallengeFlagHandled + * @instance + */ + ChallengeFlagHandled.prototype.byTeam = 0; + + /** + * ChallengeFlagHandled accepted. + * @member {boolean} accepted + * @memberof proto.GameEvent.ChallengeFlagHandled + * @instance + */ + ChallengeFlagHandled.prototype.accepted = false; + + /** + * Creates a new ChallengeFlagHandled instance using the specified properties. + * @function create + * @memberof proto.GameEvent.ChallengeFlagHandled + * @static + * @param {proto.GameEvent.IChallengeFlagHandled=} [properties] Properties to set + * @returns {proto.GameEvent.ChallengeFlagHandled} ChallengeFlagHandled instance + */ + ChallengeFlagHandled.create = function create(properties) { + return new ChallengeFlagHandled(properties); + }; + + /** + * Encodes the specified ChallengeFlagHandled message. Does not implicitly {@link proto.GameEvent.ChallengeFlagHandled.verify|verify} messages. + * @function encode + * @memberof proto.GameEvent.ChallengeFlagHandled + * @static + * @param {proto.GameEvent.IChallengeFlagHandled} message ChallengeFlagHandled message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + ChallengeFlagHandled.encode = function encode(message, writer) { + if (!writer) + writer = $Writer.create(); + writer.uint32(/* id 1, wireType 0 =*/8).int32(message.byTeam); + writer.uint32(/* id 2, wireType 0 =*/16).bool(message.accepted); + return writer; + }; + + /** + * Encodes the specified ChallengeFlagHandled message, length delimited. Does not implicitly {@link proto.GameEvent.ChallengeFlagHandled.verify|verify} messages. + * @function encodeDelimited + * @memberof proto.GameEvent.ChallengeFlagHandled + * @static + * @param {proto.GameEvent.IChallengeFlagHandled} message ChallengeFlagHandled message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + ChallengeFlagHandled.encodeDelimited = function encodeDelimited(message, writer) { + return this.encode(message, writer).ldelim(); + }; + + /** + * Decodes a ChallengeFlagHandled message from the specified reader or buffer. + * @function decode + * @memberof proto.GameEvent.ChallengeFlagHandled + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @param {number} [length] Message length if known beforehand + * @returns {proto.GameEvent.ChallengeFlagHandled} ChallengeFlagHandled + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + ChallengeFlagHandled.decode = function decode(reader, length) { + if (!(reader instanceof $Reader)) + reader = $Reader.create(reader); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.GameEvent.ChallengeFlagHandled(); + while (reader.pos < end) { + let tag = reader.uint32(); + switch (tag >>> 3) { + case 1: { + message.byTeam = reader.int32(); + break; + } + case 2: { + message.accepted = reader.bool(); + break; + } + default: + reader.skipType(tag & 7); + break; + } + } + if (!message.hasOwnProperty("byTeam")) + throw $util.ProtocolError("missing required 'byTeam'", { instance: message }); + if (!message.hasOwnProperty("accepted")) + throw $util.ProtocolError("missing required 'accepted'", { instance: message }); + return message; + }; + + /** + * Decodes a ChallengeFlagHandled message from the specified reader or buffer, length delimited. + * @function decodeDelimited + * @memberof proto.GameEvent.ChallengeFlagHandled + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @returns {proto.GameEvent.ChallengeFlagHandled} ChallengeFlagHandled + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + ChallengeFlagHandled.decodeDelimited = function decodeDelimited(reader) { + if (!(reader instanceof $Reader)) + reader = new $Reader(reader); + return this.decode(reader, reader.uint32()); + }; + + /** + * Verifies a ChallengeFlagHandled message. + * @function verify + * @memberof proto.GameEvent.ChallengeFlagHandled + * @static + * @param {Object.} message Plain object to verify + * @returns {string|null} `null` if valid, otherwise the reason why it is not + */ + ChallengeFlagHandled.verify = function verify(message) { + if (typeof message !== "object" || message === null) + return "object expected"; + switch (message.byTeam) { + default: + return "byTeam: enum value expected"; + case 0: + case 1: + case 2: + break; + } + if (typeof message.accepted !== "boolean") + return "accepted: boolean expected"; + return null; + }; + + /** + * Creates a ChallengeFlagHandled message from a plain object. Also converts values to their respective internal types. + * @function fromObject + * @memberof proto.GameEvent.ChallengeFlagHandled + * @static + * @param {Object.} object Plain object + * @returns {proto.GameEvent.ChallengeFlagHandled} ChallengeFlagHandled + */ + ChallengeFlagHandled.fromObject = function fromObject(object) { + if (object instanceof $root.proto.GameEvent.ChallengeFlagHandled) + return object; + let message = new $root.proto.GameEvent.ChallengeFlagHandled(); + switch (object.byTeam) { + default: + if (typeof object.byTeam === "number") { + message.byTeam = object.byTeam; + break; + } + break; + case "UNKNOWN": + case 0: + message.byTeam = 0; + break; + case "YELLOW": + case 1: + message.byTeam = 1; + break; + case "BLUE": + case 2: + message.byTeam = 2; + break; + } + if (object.accepted != null) + message.accepted = Boolean(object.accepted); + return message; + }; + + /** + * Creates a plain object from a ChallengeFlagHandled message. Also converts values to other types if specified. + * @function toObject + * @memberof proto.GameEvent.ChallengeFlagHandled + * @static + * @param {proto.GameEvent.ChallengeFlagHandled} message ChallengeFlagHandled + * @param {$protobuf.IConversionOptions} [options] Conversion options + * @returns {Object.} Plain object + */ + ChallengeFlagHandled.toObject = function toObject(message, options) { + if (!options) + options = {}; + let object = {}; + if (options.defaults) { + object.byTeam = options.enums === String ? "UNKNOWN" : 0; + object.accepted = false; + } + if (message.byTeam != null && message.hasOwnProperty("byTeam")) + object.byTeam = options.enums === String ? $root.proto.Team[message.byTeam] === undefined ? message.byTeam : $root.proto.Team[message.byTeam] : message.byTeam; + if (message.accepted != null && message.hasOwnProperty("accepted")) + object.accepted = message.accepted; + return object; + }; + + /** + * Converts this ChallengeFlagHandled to JSON. + * @function toJSON + * @memberof proto.GameEvent.ChallengeFlagHandled + * @instance + * @returns {Object.} JSON object + */ + ChallengeFlagHandled.prototype.toJSON = function toJSON() { + return this.constructor.toObject(this, $protobuf.util.toJSONOptions); + }; + + /** + * Gets the default type url for ChallengeFlagHandled + * @function getTypeUrl + * @memberof proto.GameEvent.ChallengeFlagHandled + * @static + * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns {string} The default type url + */ + ChallengeFlagHandled.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + if (typeUrlPrefix === undefined) { + typeUrlPrefix = "type.googleapis.com"; + } + return typeUrlPrefix + "/proto.GameEvent.ChallengeFlagHandled"; + }; + + return ChallengeFlagHandled; + })(); + GameEvent.EmergencyStop = (function() { /** @@ -26472,6 +27752,7 @@ export const proto = $root.proto = (() => { * @interface IPenaltyKickFailed * @property {proto.Team} byTeam PenaltyKickFailed byTeam * @property {proto.IVector2|null} [location] PenaltyKickFailed location + * @property {string|null} [reason] PenaltyKickFailed reason */ /** @@ -26505,6 +27786,14 @@ export const proto = $root.proto = (() => { */ PenaltyKickFailed.prototype.location = null; + /** + * PenaltyKickFailed reason. + * @member {string} reason + * @memberof proto.GameEvent.PenaltyKickFailed + * @instance + */ + PenaltyKickFailed.prototype.reason = ""; + /** * Creates a new PenaltyKickFailed instance using the specified properties. * @function create @@ -26532,6 +27821,8 @@ export const proto = $root.proto = (() => { writer.uint32(/* id 1, wireType 0 =*/8).int32(message.byTeam); if (message.location != null && Object.hasOwnProperty.call(message, "location")) $root.proto.Vector2.encode(message.location, writer.uint32(/* id 2, wireType 2 =*/18).fork()).ldelim(); + if (message.reason != null && Object.hasOwnProperty.call(message, "reason")) + writer.uint32(/* id 3, wireType 2 =*/26).string(message.reason); return writer; }; @@ -26574,6 +27865,10 @@ export const proto = $root.proto = (() => { message.location = $root.proto.Vector2.decode(reader, reader.uint32()); break; } + case 3: { + message.reason = reader.string(); + break; + } default: reader.skipType(tag & 7); break; @@ -26624,6 +27919,9 @@ export const proto = $root.proto = (() => { if (error) return "location." + error; } + if (message.reason != null && message.hasOwnProperty("reason")) + if (!$util.isString(message.reason)) + return "reason: string expected"; return null; }; @@ -26664,6 +27962,8 @@ export const proto = $root.proto = (() => { throw TypeError(".proto.GameEvent.PenaltyKickFailed.location: object expected"); message.location = $root.proto.Vector2.fromObject(object.location); } + if (object.reason != null) + message.reason = String(object.reason); return message; }; @@ -26683,11 +27983,14 @@ export const proto = $root.proto = (() => { if (options.defaults) { object.byTeam = options.enums === String ? "UNKNOWN" : 0; object.location = null; + object.reason = ""; } if (message.byTeam != null && message.hasOwnProperty("byTeam")) object.byTeam = options.enums === String ? $root.proto.Team[message.byTeam] === undefined ? message.byTeam : $root.proto.Team[message.byTeam] : message.byTeam; if (message.location != null && message.hasOwnProperty("location")) object.location = $root.proto.Vector2.toObject(message.location, options); + if (message.reason != null && message.hasOwnProperty("reason")) + object.reason = message.reason; return object; }; @@ -26736,6 +28039,7 @@ export const proto = $root.proto = (() => { * @property {number} BOT_PUSHED_BOT=24 BOT_PUSHED_BOT value * @property {number} BOT_HELD_BALL_DELIBERATELY=26 BOT_HELD_BALL_DELIBERATELY value * @property {number} BOT_TIPPED_OVER=27 BOT_TIPPED_OVER value + * @property {number} BOT_DROPPED_PARTS=47 BOT_DROPPED_PARTS value * @property {number} ATTACKER_TOUCHED_BALL_IN_DEFENSE_AREA=15 ATTACKER_TOUCHED_BALL_IN_DEFENSE_AREA value * @property {number} BOT_KICKED_BALL_TOO_FAST=18 BOT_KICKED_BALL_TOO_FAST value * @property {number} BOT_CRASH_UNIQUE=22 BOT_CRASH_UNIQUE value @@ -26756,6 +28060,7 @@ export const proto = $root.proto = (() => { * @property {number} BOT_SUBSTITUTION=37 BOT_SUBSTITUTION value * @property {number} TOO_MANY_ROBOTS=38 TOO_MANY_ROBOTS value * @property {number} CHALLENGE_FLAG=44 CHALLENGE_FLAG value + * @property {number} CHALLENGE_FLAG_HANDLED=46 CHALLENGE_FLAG_HANDLED value * @property {number} EMERGENCY_STOP=45 EMERGENCY_STOP value * @property {number} UNSPORTING_BEHAVIOR_MINOR=35 UNSPORTING_BEHAVIOR_MINOR value * @property {number} UNSPORTING_BEHAVIOR_MAJOR=36 UNSPORTING_BEHAVIOR_MAJOR value @@ -26774,6 +28079,7 @@ export const proto = $root.proto = (() => { values[valuesById[24] = "BOT_PUSHED_BOT"] = 24; values[valuesById[26] = "BOT_HELD_BALL_DELIBERATELY"] = 26; values[valuesById[27] = "BOT_TIPPED_OVER"] = 27; + values[valuesById[47] = "BOT_DROPPED_PARTS"] = 47; values[valuesById[15] = "ATTACKER_TOUCHED_BALL_IN_DEFENSE_AREA"] = 15; values[valuesById[18] = "BOT_KICKED_BALL_TOO_FAST"] = 18; values[valuesById[22] = "BOT_CRASH_UNIQUE"] = 22; @@ -26794,6 +28100,7 @@ export const proto = $root.proto = (() => { values[valuesById[37] = "BOT_SUBSTITUTION"] = 37; values[valuesById[38] = "TOO_MANY_ROBOTS"] = 38; values[valuesById[44] = "CHALLENGE_FLAG"] = 44; + values[valuesById[46] = "CHALLENGE_FLAG_HANDLED"] = 46; values[valuesById[45] = "EMERGENCY_STOP"] = 45; values[valuesById[35] = "UNSPORTING_BEHAVIOR_MINOR"] = 35; values[valuesById[36] = "UNSPORTING_BEHAVIOR_MAJOR"] = 36; @@ -26861,579 +28168,73 @@ export const proto = $root.proto = (() => { RobotId.prototype.team = 0; /** - * Creates a new RobotId instance using the specified properties. - * @function create - * @memberof proto.RobotId - * @static - * @param {proto.IRobotId=} [properties] Properties to set - * @returns {proto.RobotId} RobotId instance - */ - RobotId.create = function create(properties) { - return new RobotId(properties); - }; - - /** - * Encodes the specified RobotId message. Does not implicitly {@link proto.RobotId.verify|verify} messages. - * @function encode - * @memberof proto.RobotId - * @static - * @param {proto.IRobotId} message RobotId message or plain object to encode - * @param {$protobuf.Writer} [writer] Writer to encode to - * @returns {$protobuf.Writer} Writer - */ - RobotId.encode = function encode(message, writer) { - if (!writer) - writer = $Writer.create(); - if (message.id != null && Object.hasOwnProperty.call(message, "id")) - writer.uint32(/* id 1, wireType 0 =*/8).uint32(message.id); - if (message.team != null && Object.hasOwnProperty.call(message, "team")) - writer.uint32(/* id 2, wireType 0 =*/16).int32(message.team); - return writer; - }; - - /** - * Encodes the specified RobotId message, length delimited. Does not implicitly {@link proto.RobotId.verify|verify} messages. - * @function encodeDelimited - * @memberof proto.RobotId - * @static - * @param {proto.IRobotId} message RobotId message or plain object to encode - * @param {$protobuf.Writer} [writer] Writer to encode to - * @returns {$protobuf.Writer} Writer - */ - RobotId.encodeDelimited = function encodeDelimited(message, writer) { - return this.encode(message, writer).ldelim(); - }; - - /** - * Decodes a RobotId message from the specified reader or buffer. - * @function decode - * @memberof proto.RobotId - * @static - * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @param {number} [length] Message length if known beforehand - * @returns {proto.RobotId} RobotId - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - RobotId.decode = function decode(reader, length) { - if (!(reader instanceof $Reader)) - reader = $Reader.create(reader); - let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.RobotId(); - while (reader.pos < end) { - let tag = reader.uint32(); - switch (tag >>> 3) { - case 1: { - message.id = reader.uint32(); - break; - } - case 2: { - message.team = reader.int32(); - break; - } - default: - reader.skipType(tag & 7); - break; - } - } - return message; - }; - - /** - * Decodes a RobotId message from the specified reader or buffer, length delimited. - * @function decodeDelimited - * @memberof proto.RobotId - * @static - * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @returns {proto.RobotId} RobotId - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - RobotId.decodeDelimited = function decodeDelimited(reader) { - if (!(reader instanceof $Reader)) - reader = new $Reader(reader); - return this.decode(reader, reader.uint32()); - }; - - /** - * Verifies a RobotId message. - * @function verify - * @memberof proto.RobotId - * @static - * @param {Object.} message Plain object to verify - * @returns {string|null} `null` if valid, otherwise the reason why it is not - */ - RobotId.verify = function verify(message) { - if (typeof message !== "object" || message === null) - return "object expected"; - if (message.id != null && message.hasOwnProperty("id")) - if (!$util.isInteger(message.id)) - return "id: integer expected"; - if (message.team != null && message.hasOwnProperty("team")) - switch (message.team) { - default: - return "team: enum value expected"; - case 0: - case 1: - case 2: - break; - } - return null; - }; - - /** - * Creates a RobotId message from a plain object. Also converts values to their respective internal types. - * @function fromObject - * @memberof proto.RobotId - * @static - * @param {Object.} object Plain object - * @returns {proto.RobotId} RobotId - */ - RobotId.fromObject = function fromObject(object) { - if (object instanceof $root.proto.RobotId) - return object; - let message = new $root.proto.RobotId(); - if (object.id != null) - message.id = object.id >>> 0; - switch (object.team) { - default: - if (typeof object.team === "number") { - message.team = object.team; - break; - } - break; - case "UNKNOWN": - case 0: - message.team = 0; - break; - case "YELLOW": - case 1: - message.team = 1; - break; - case "BLUE": - case 2: - message.team = 2; - break; - } - return message; - }; - - /** - * Creates a plain object from a RobotId message. Also converts values to other types if specified. - * @function toObject - * @memberof proto.RobotId - * @static - * @param {proto.RobotId} message RobotId - * @param {$protobuf.IConversionOptions} [options] Conversion options - * @returns {Object.} Plain object - */ - RobotId.toObject = function toObject(message, options) { - if (!options) - options = {}; - let object = {}; - if (options.defaults) { - object.id = 0; - object.team = options.enums === String ? "UNKNOWN" : 0; - } - if (message.id != null && message.hasOwnProperty("id")) - object.id = message.id; - if (message.team != null && message.hasOwnProperty("team")) - object.team = options.enums === String ? $root.proto.Team[message.team] === undefined ? message.team : $root.proto.Team[message.team] : message.team; - return object; - }; - - /** - * Converts this RobotId to JSON. - * @function toJSON - * @memberof proto.RobotId - * @instance - * @returns {Object.} JSON object - */ - RobotId.prototype.toJSON = function toJSON() { - return this.constructor.toObject(this, $protobuf.util.toJSONOptions); - }; - - /** - * Gets the default type url for RobotId - * @function getTypeUrl - * @memberof proto.RobotId - * @static - * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") - * @returns {string} The default type url - */ - RobotId.getTypeUrl = function getTypeUrl(typeUrlPrefix) { - if (typeUrlPrefix === undefined) { - typeUrlPrefix = "type.googleapis.com"; - } - return typeUrlPrefix + "/proto.RobotId"; - }; - - return RobotId; - })(); - - /** - * Division enum. - * @name proto.Division - * @enum {number} - * @property {number} DIV_UNKNOWN=0 DIV_UNKNOWN value - * @property {number} DIV_A=1 DIV_A value - * @property {number} DIV_B=2 DIV_B value - */ - proto.Division = (function() { - const valuesById = {}, values = Object.create(valuesById); - values[valuesById[0] = "DIV_UNKNOWN"] = 0; - values[valuesById[1] = "DIV_A"] = 1; - values[valuesById[2] = "DIV_B"] = 2; - return values; - })(); - - proto.Vector2 = (function() { - - /** - * Properties of a Vector2. - * @memberof proto - * @interface IVector2 - * @property {number} x Vector2 x - * @property {number} y Vector2 y - */ - - /** - * Constructs a new Vector2. - * @memberof proto - * @classdesc Represents a Vector2. - * @implements IVector2 - * @constructor - * @param {proto.IVector2=} [properties] Properties to set - */ - function Vector2(properties) { - if (properties) - for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) - if (properties[keys[i]] != null) - this[keys[i]] = properties[keys[i]]; - } - - /** - * Vector2 x. - * @member {number} x - * @memberof proto.Vector2 - * @instance - */ - Vector2.prototype.x = 0; - - /** - * Vector2 y. - * @member {number} y - * @memberof proto.Vector2 - * @instance - */ - Vector2.prototype.y = 0; - - /** - * Creates a new Vector2 instance using the specified properties. - * @function create - * @memberof proto.Vector2 - * @static - * @param {proto.IVector2=} [properties] Properties to set - * @returns {proto.Vector2} Vector2 instance - */ - Vector2.create = function create(properties) { - return new Vector2(properties); - }; - - /** - * Encodes the specified Vector2 message. Does not implicitly {@link proto.Vector2.verify|verify} messages. - * @function encode - * @memberof proto.Vector2 - * @static - * @param {proto.IVector2} message Vector2 message or plain object to encode - * @param {$protobuf.Writer} [writer] Writer to encode to - * @returns {$protobuf.Writer} Writer - */ - Vector2.encode = function encode(message, writer) { - if (!writer) - writer = $Writer.create(); - writer.uint32(/* id 1, wireType 5 =*/13).float(message.x); - writer.uint32(/* id 2, wireType 5 =*/21).float(message.y); - return writer; - }; - - /** - * Encodes the specified Vector2 message, length delimited. Does not implicitly {@link proto.Vector2.verify|verify} messages. - * @function encodeDelimited - * @memberof proto.Vector2 - * @static - * @param {proto.IVector2} message Vector2 message or plain object to encode - * @param {$protobuf.Writer} [writer] Writer to encode to - * @returns {$protobuf.Writer} Writer - */ - Vector2.encodeDelimited = function encodeDelimited(message, writer) { - return this.encode(message, writer).ldelim(); - }; - - /** - * Decodes a Vector2 message from the specified reader or buffer. - * @function decode - * @memberof proto.Vector2 - * @static - * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @param {number} [length] Message length if known beforehand - * @returns {proto.Vector2} Vector2 - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - Vector2.decode = function decode(reader, length) { - if (!(reader instanceof $Reader)) - reader = $Reader.create(reader); - let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.Vector2(); - while (reader.pos < end) { - let tag = reader.uint32(); - switch (tag >>> 3) { - case 1: { - message.x = reader.float(); - break; - } - case 2: { - message.y = reader.float(); - break; - } - default: - reader.skipType(tag & 7); - break; - } - } - if (!message.hasOwnProperty("x")) - throw $util.ProtocolError("missing required 'x'", { instance: message }); - if (!message.hasOwnProperty("y")) - throw $util.ProtocolError("missing required 'y'", { instance: message }); - return message; - }; - - /** - * Decodes a Vector2 message from the specified reader or buffer, length delimited. - * @function decodeDelimited - * @memberof proto.Vector2 - * @static - * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @returns {proto.Vector2} Vector2 - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - Vector2.decodeDelimited = function decodeDelimited(reader) { - if (!(reader instanceof $Reader)) - reader = new $Reader(reader); - return this.decode(reader, reader.uint32()); - }; - - /** - * Verifies a Vector2 message. - * @function verify - * @memberof proto.Vector2 - * @static - * @param {Object.} message Plain object to verify - * @returns {string|null} `null` if valid, otherwise the reason why it is not - */ - Vector2.verify = function verify(message) { - if (typeof message !== "object" || message === null) - return "object expected"; - if (typeof message.x !== "number") - return "x: number expected"; - if (typeof message.y !== "number") - return "y: number expected"; - return null; - }; - - /** - * Creates a Vector2 message from a plain object. Also converts values to their respective internal types. - * @function fromObject - * @memberof proto.Vector2 - * @static - * @param {Object.} object Plain object - * @returns {proto.Vector2} Vector2 - */ - Vector2.fromObject = function fromObject(object) { - if (object instanceof $root.proto.Vector2) - return object; - let message = new $root.proto.Vector2(); - if (object.x != null) - message.x = Number(object.x); - if (object.y != null) - message.y = Number(object.y); - return message; - }; - - /** - * Creates a plain object from a Vector2 message. Also converts values to other types if specified. - * @function toObject - * @memberof proto.Vector2 - * @static - * @param {proto.Vector2} message Vector2 - * @param {$protobuf.IConversionOptions} [options] Conversion options - * @returns {Object.} Plain object - */ - Vector2.toObject = function toObject(message, options) { - if (!options) - options = {}; - let object = {}; - if (options.defaults) { - object.x = 0; - object.y = 0; - } - if (message.x != null && message.hasOwnProperty("x")) - object.x = options.json && !isFinite(message.x) ? String(message.x) : message.x; - if (message.y != null && message.hasOwnProperty("y")) - object.y = options.json && !isFinite(message.y) ? String(message.y) : message.y; - return object; - }; - - /** - * Converts this Vector2 to JSON. - * @function toJSON - * @memberof proto.Vector2 - * @instance - * @returns {Object.} JSON object - */ - Vector2.prototype.toJSON = function toJSON() { - return this.constructor.toObject(this, $protobuf.util.toJSONOptions); - }; - - /** - * Gets the default type url for Vector2 - * @function getTypeUrl - * @memberof proto.Vector2 - * @static - * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") - * @returns {string} The default type url - */ - Vector2.getTypeUrl = function getTypeUrl(typeUrlPrefix) { - if (typeUrlPrefix === undefined) { - typeUrlPrefix = "type.googleapis.com"; - } - return typeUrlPrefix + "/proto.Vector2"; - }; - - return Vector2; - })(); - - proto.Vector3 = (function() { - - /** - * Properties of a Vector3. - * @memberof proto - * @interface IVector3 - * @property {number} x Vector3 x - * @property {number} y Vector3 y - * @property {number} z Vector3 z - */ - - /** - * Constructs a new Vector3. - * @memberof proto - * @classdesc Represents a Vector3. - * @implements IVector3 - * @constructor - * @param {proto.IVector3=} [properties] Properties to set - */ - function Vector3(properties) { - if (properties) - for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) - if (properties[keys[i]] != null) - this[keys[i]] = properties[keys[i]]; - } - - /** - * Vector3 x. - * @member {number} x - * @memberof proto.Vector3 - * @instance - */ - Vector3.prototype.x = 0; - - /** - * Vector3 y. - * @member {number} y - * @memberof proto.Vector3 - * @instance - */ - Vector3.prototype.y = 0; - - /** - * Vector3 z. - * @member {number} z - * @memberof proto.Vector3 - * @instance - */ - Vector3.prototype.z = 0; - - /** - * Creates a new Vector3 instance using the specified properties. + * Creates a new RobotId instance using the specified properties. * @function create - * @memberof proto.Vector3 + * @memberof proto.RobotId * @static - * @param {proto.IVector3=} [properties] Properties to set - * @returns {proto.Vector3} Vector3 instance + * @param {proto.IRobotId=} [properties] Properties to set + * @returns {proto.RobotId} RobotId instance */ - Vector3.create = function create(properties) { - return new Vector3(properties); + RobotId.create = function create(properties) { + return new RobotId(properties); }; /** - * Encodes the specified Vector3 message. Does not implicitly {@link proto.Vector3.verify|verify} messages. + * Encodes the specified RobotId message. Does not implicitly {@link proto.RobotId.verify|verify} messages. * @function encode - * @memberof proto.Vector3 + * @memberof proto.RobotId * @static - * @param {proto.IVector3} message Vector3 message or plain object to encode + * @param {proto.IRobotId} message RobotId message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ - Vector3.encode = function encode(message, writer) { + RobotId.encode = function encode(message, writer) { if (!writer) writer = $Writer.create(); - writer.uint32(/* id 1, wireType 5 =*/13).float(message.x); - writer.uint32(/* id 2, wireType 5 =*/21).float(message.y); - writer.uint32(/* id 3, wireType 5 =*/29).float(message.z); + if (message.id != null && Object.hasOwnProperty.call(message, "id")) + writer.uint32(/* id 1, wireType 0 =*/8).uint32(message.id); + if (message.team != null && Object.hasOwnProperty.call(message, "team")) + writer.uint32(/* id 2, wireType 0 =*/16).int32(message.team); return writer; }; /** - * Encodes the specified Vector3 message, length delimited. Does not implicitly {@link proto.Vector3.verify|verify} messages. + * Encodes the specified RobotId message, length delimited. Does not implicitly {@link proto.RobotId.verify|verify} messages. * @function encodeDelimited - * @memberof proto.Vector3 + * @memberof proto.RobotId * @static - * @param {proto.IVector3} message Vector3 message or plain object to encode + * @param {proto.IRobotId} message RobotId message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ - Vector3.encodeDelimited = function encodeDelimited(message, writer) { + RobotId.encodeDelimited = function encodeDelimited(message, writer) { return this.encode(message, writer).ldelim(); }; /** - * Decodes a Vector3 message from the specified reader or buffer. + * Decodes a RobotId message from the specified reader or buffer. * @function decode - * @memberof proto.Vector3 + * @memberof proto.RobotId * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from * @param {number} [length] Message length if known beforehand - * @returns {proto.Vector3} Vector3 + * @returns {proto.RobotId} RobotId * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - Vector3.decode = function decode(reader, length) { + RobotId.decode = function decode(reader, length) { if (!(reader instanceof $Reader)) reader = $Reader.create(reader); - let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.Vector3(); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.RobotId(); while (reader.pos < end) { let tag = reader.uint32(); switch (tag >>> 3) { case 1: { - message.x = reader.float(); + message.id = reader.uint32(); break; } case 2: { - message.y = reader.float(); - break; - } - case 3: { - message.z = reader.float(); + message.team = reader.int32(); break; } default: @@ -27441,187 +28242,176 @@ export const proto = $root.proto = (() => { break; } } - if (!message.hasOwnProperty("x")) - throw $util.ProtocolError("missing required 'x'", { instance: message }); - if (!message.hasOwnProperty("y")) - throw $util.ProtocolError("missing required 'y'", { instance: message }); - if (!message.hasOwnProperty("z")) - throw $util.ProtocolError("missing required 'z'", { instance: message }); return message; }; /** - * Decodes a Vector3 message from the specified reader or buffer, length delimited. + * Decodes a RobotId message from the specified reader or buffer, length delimited. * @function decodeDelimited - * @memberof proto.Vector3 + * @memberof proto.RobotId * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @returns {proto.Vector3} Vector3 + * @returns {proto.RobotId} RobotId * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - Vector3.decodeDelimited = function decodeDelimited(reader) { + RobotId.decodeDelimited = function decodeDelimited(reader) { if (!(reader instanceof $Reader)) reader = new $Reader(reader); return this.decode(reader, reader.uint32()); }; /** - * Verifies a Vector3 message. + * Verifies a RobotId message. * @function verify - * @memberof proto.Vector3 + * @memberof proto.RobotId * @static * @param {Object.} message Plain object to verify * @returns {string|null} `null` if valid, otherwise the reason why it is not */ - Vector3.verify = function verify(message) { + RobotId.verify = function verify(message) { if (typeof message !== "object" || message === null) return "object expected"; - if (typeof message.x !== "number") - return "x: number expected"; - if (typeof message.y !== "number") - return "y: number expected"; - if (typeof message.z !== "number") - return "z: number expected"; + if (message.id != null && message.hasOwnProperty("id")) + if (!$util.isInteger(message.id)) + return "id: integer expected"; + if (message.team != null && message.hasOwnProperty("team")) + switch (message.team) { + default: + return "team: enum value expected"; + case 0: + case 1: + case 2: + break; + } return null; }; /** - * Creates a Vector3 message from a plain object. Also converts values to their respective internal types. + * Creates a RobotId message from a plain object. Also converts values to their respective internal types. * @function fromObject - * @memberof proto.Vector3 + * @memberof proto.RobotId * @static * @param {Object.} object Plain object - * @returns {proto.Vector3} Vector3 + * @returns {proto.RobotId} RobotId */ - Vector3.fromObject = function fromObject(object) { - if (object instanceof $root.proto.Vector3) + RobotId.fromObject = function fromObject(object) { + if (object instanceof $root.proto.RobotId) return object; - let message = new $root.proto.Vector3(); - if (object.x != null) - message.x = Number(object.x); - if (object.y != null) - message.y = Number(object.y); - if (object.z != null) - message.z = Number(object.z); + let message = new $root.proto.RobotId(); + if (object.id != null) + message.id = object.id >>> 0; + switch (object.team) { + default: + if (typeof object.team === "number") { + message.team = object.team; + break; + } + break; + case "UNKNOWN": + case 0: + message.team = 0; + break; + case "YELLOW": + case 1: + message.team = 1; + break; + case "BLUE": + case 2: + message.team = 2; + break; + } return message; }; /** - * Creates a plain object from a Vector3 message. Also converts values to other types if specified. + * Creates a plain object from a RobotId message. Also converts values to other types if specified. * @function toObject - * @memberof proto.Vector3 + * @memberof proto.RobotId * @static - * @param {proto.Vector3} message Vector3 + * @param {proto.RobotId} message RobotId * @param {$protobuf.IConversionOptions} [options] Conversion options * @returns {Object.} Plain object */ - Vector3.toObject = function toObject(message, options) { + RobotId.toObject = function toObject(message, options) { if (!options) options = {}; let object = {}; if (options.defaults) { - object.x = 0; - object.y = 0; - object.z = 0; + object.id = 0; + object.team = options.enums === String ? "UNKNOWN" : 0; } - if (message.x != null && message.hasOwnProperty("x")) - object.x = options.json && !isFinite(message.x) ? String(message.x) : message.x; - if (message.y != null && message.hasOwnProperty("y")) - object.y = options.json && !isFinite(message.y) ? String(message.y) : message.y; - if (message.z != null && message.hasOwnProperty("z")) - object.z = options.json && !isFinite(message.z) ? String(message.z) : message.z; + if (message.id != null && message.hasOwnProperty("id")) + object.id = message.id; + if (message.team != null && message.hasOwnProperty("team")) + object.team = options.enums === String ? $root.proto.Team[message.team] === undefined ? message.team : $root.proto.Team[message.team] : message.team; return object; }; /** - * Converts this Vector3 to JSON. + * Converts this RobotId to JSON. * @function toJSON - * @memberof proto.Vector3 + * @memberof proto.RobotId * @instance * @returns {Object.} JSON object */ - Vector3.prototype.toJSON = function toJSON() { + RobotId.prototype.toJSON = function toJSON() { return this.constructor.toObject(this, $protobuf.util.toJSONOptions); }; /** - * Gets the default type url for Vector3 + * Gets the default type url for RobotId * @function getTypeUrl - * @memberof proto.Vector3 + * @memberof proto.RobotId * @static * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns {string} The default type url */ - Vector3.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + RobotId.getTypeUrl = function getTypeUrl(typeUrlPrefix) { if (typeUrlPrefix === undefined) { typeUrlPrefix = "type.googleapis.com"; } - return typeUrlPrefix + "/proto.Vector3"; + return typeUrlPrefix + "/proto.RobotId"; }; - return Vector3; - })(); - - /** - * RobotTeam enum. - * @name proto.RobotTeam - * @enum {number} - * @property {number} YELLOW_TEAM=0 YELLOW_TEAM value - * @property {number} BLUE_TEAM=1 BLUE_TEAM value - */ - proto.RobotTeam = (function() { - const valuesById = {}, values = Object.create(valuesById); - values[valuesById[0] = "YELLOW_TEAM"] = 0; - values[valuesById[1] = "BLUE_TEAM"] = 1; - return values; + return RobotId; })(); /** - * RobotFeedbackSource enum. - * @name proto.RobotFeedbackSource + * Division enum. + * @name proto.Division * @enum {number} - * @property {number} SIMULATOR=0 SIMULATOR value - * @property {number} BASESTATION=1 BASESTATION value + * @property {number} DIV_UNKNOWN=0 DIV_UNKNOWN value + * @property {number} DIV_A=1 DIV_A value + * @property {number} DIV_B=2 DIV_B value */ - proto.RobotFeedbackSource = (function() { + proto.Division = (function() { const valuesById = {}, values = Object.create(valuesById); - values[valuesById[0] = "SIMULATOR"] = 0; - values[valuesById[1] = "BASESTATION"] = 1; + values[valuesById[0] = "DIV_UNKNOWN"] = 0; + values[valuesById[1] = "DIV_A"] = 1; + values[valuesById[2] = "DIV_B"] = 2; return values; })(); - proto.RobotFeedback = (function() { + proto.Vector2 = (function() { /** - * Properties of a RobotFeedback. + * Properties of a Vector2. * @memberof proto - * @interface IRobotFeedback - * @property {number|null} [id] RobotFeedback id - * @property {boolean|null} [ballSensorSeesBall] RobotFeedback ballSensorSeesBall - * @property {number|null} [ballPosition] RobotFeedback ballPosition - * @property {boolean|null} [ballSensorIsWorking] RobotFeedback ballSensorIsWorking - * @property {boolean|null} [dribblerSeesBall] RobotFeedback dribblerSeesBall - * @property {number|null} [estimatedVelocityX] RobotFeedback estimatedVelocityX - * @property {number|null} [estimatedVelocityY] RobotFeedback estimatedVelocityY - * @property {number|null} [estimatedAngle] RobotFeedback estimatedAngle - * @property {boolean|null} [xsensIsCalibrated] RobotFeedback xsensIsCalibrated - * @property {boolean|null} [capacitorIsCharged] RobotFeedback capacitorIsCharged - * @property {number|null} [wheelsLocked] RobotFeedback wheelsLocked - * @property {number|null} [wheelsBraking] RobotFeedback wheelsBraking - * @property {number|null} [batteryLevel] RobotFeedback batteryLevel - * @property {number|null} [signalStrength] RobotFeedback signalStrength + * @interface IVector2 + * @property {number} x Vector2 x + * @property {number} y Vector2 y */ /** - * Constructs a new RobotFeedback. + * Constructs a new Vector2. * @memberof proto - * @classdesc Represents a RobotFeedback. - * @implements IRobotFeedback + * @classdesc Represents a Vector2. + * @implements IVector2 * @constructor - * @param {proto.IRobotFeedback=} [properties] Properties to set + * @param {proto.IVector2=} [properties] Properties to set */ - function RobotFeedback(properties) { + function Vector2(properties) { if (properties) for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) if (properties[keys[i]] != null) @@ -27629,257 +28419,87 @@ export const proto = $root.proto = (() => { } /** - * RobotFeedback id. - * @member {number} id - * @memberof proto.RobotFeedback - * @instance - */ - RobotFeedback.prototype.id = 0; - - /** - * RobotFeedback ballSensorSeesBall. - * @member {boolean} ballSensorSeesBall - * @memberof proto.RobotFeedback - * @instance - */ - RobotFeedback.prototype.ballSensorSeesBall = false; - - /** - * RobotFeedback ballPosition. - * @member {number} ballPosition - * @memberof proto.RobotFeedback - * @instance - */ - RobotFeedback.prototype.ballPosition = 0; - - /** - * RobotFeedback ballSensorIsWorking. - * @member {boolean} ballSensorIsWorking - * @memberof proto.RobotFeedback - * @instance - */ - RobotFeedback.prototype.ballSensorIsWorking = false; - - /** - * RobotFeedback dribblerSeesBall. - * @member {boolean} dribblerSeesBall - * @memberof proto.RobotFeedback - * @instance - */ - RobotFeedback.prototype.dribblerSeesBall = false; - - /** - * RobotFeedback estimatedVelocityX. - * @member {number} estimatedVelocityX - * @memberof proto.RobotFeedback - * @instance - */ - RobotFeedback.prototype.estimatedVelocityX = 0; - - /** - * RobotFeedback estimatedVelocityY. - * @member {number} estimatedVelocityY - * @memberof proto.RobotFeedback - * @instance - */ - RobotFeedback.prototype.estimatedVelocityY = 0; - - /** - * RobotFeedback estimatedAngle. - * @member {number} estimatedAngle - * @memberof proto.RobotFeedback - * @instance - */ - RobotFeedback.prototype.estimatedAngle = 0; - - /** - * RobotFeedback xsensIsCalibrated. - * @member {boolean} xsensIsCalibrated - * @memberof proto.RobotFeedback - * @instance - */ - RobotFeedback.prototype.xsensIsCalibrated = false; - - /** - * RobotFeedback capacitorIsCharged. - * @member {boolean} capacitorIsCharged - * @memberof proto.RobotFeedback - * @instance - */ - RobotFeedback.prototype.capacitorIsCharged = false; - - /** - * RobotFeedback wheelsLocked. - * @member {number} wheelsLocked - * @memberof proto.RobotFeedback - * @instance - */ - RobotFeedback.prototype.wheelsLocked = 0; - - /** - * RobotFeedback wheelsBraking. - * @member {number} wheelsBraking - * @memberof proto.RobotFeedback - * @instance - */ - RobotFeedback.prototype.wheelsBraking = 0; - - /** - * RobotFeedback batteryLevel. - * @member {number} batteryLevel - * @memberof proto.RobotFeedback + * Vector2 x. + * @member {number} x + * @memberof proto.Vector2 * @instance */ - RobotFeedback.prototype.batteryLevel = 0; + Vector2.prototype.x = 0; /** - * RobotFeedback signalStrength. - * @member {number} signalStrength - * @memberof proto.RobotFeedback + * Vector2 y. + * @member {number} y + * @memberof proto.Vector2 * @instance */ - RobotFeedback.prototype.signalStrength = 0; + Vector2.prototype.y = 0; /** - * Creates a new RobotFeedback instance using the specified properties. + * Creates a new Vector2 instance using the specified properties. * @function create - * @memberof proto.RobotFeedback + * @memberof proto.Vector2 * @static - * @param {proto.IRobotFeedback=} [properties] Properties to set - * @returns {proto.RobotFeedback} RobotFeedback instance + * @param {proto.IVector2=} [properties] Properties to set + * @returns {proto.Vector2} Vector2 instance */ - RobotFeedback.create = function create(properties) { - return new RobotFeedback(properties); + Vector2.create = function create(properties) { + return new Vector2(properties); }; /** - * Encodes the specified RobotFeedback message. Does not implicitly {@link proto.RobotFeedback.verify|verify} messages. + * Encodes the specified Vector2 message. Does not implicitly {@link proto.Vector2.verify|verify} messages. * @function encode - * @memberof proto.RobotFeedback + * @memberof proto.Vector2 * @static - * @param {proto.IRobotFeedback} message RobotFeedback message or plain object to encode + * @param {proto.IVector2} message Vector2 message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ - RobotFeedback.encode = function encode(message, writer) { + Vector2.encode = function encode(message, writer) { if (!writer) writer = $Writer.create(); - if (message.id != null && Object.hasOwnProperty.call(message, "id")) - writer.uint32(/* id 1, wireType 0 =*/8).int32(message.id); - if (message.ballSensorSeesBall != null && Object.hasOwnProperty.call(message, "ballSensorSeesBall")) - writer.uint32(/* id 2, wireType 0 =*/16).bool(message.ballSensorSeesBall); - if (message.ballPosition != null && Object.hasOwnProperty.call(message, "ballPosition")) - writer.uint32(/* id 3, wireType 5 =*/29).float(message.ballPosition); - if (message.ballSensorIsWorking != null && Object.hasOwnProperty.call(message, "ballSensorIsWorking")) - writer.uint32(/* id 4, wireType 0 =*/32).bool(message.ballSensorIsWorking); - if (message.dribblerSeesBall != null && Object.hasOwnProperty.call(message, "dribblerSeesBall")) - writer.uint32(/* id 5, wireType 0 =*/40).bool(message.dribblerSeesBall); - if (message.estimatedVelocityX != null && Object.hasOwnProperty.call(message, "estimatedVelocityX")) - writer.uint32(/* id 6, wireType 1 =*/49).double(message.estimatedVelocityX); - if (message.estimatedVelocityY != null && Object.hasOwnProperty.call(message, "estimatedVelocityY")) - writer.uint32(/* id 7, wireType 1 =*/57).double(message.estimatedVelocityY); - if (message.estimatedAngle != null && Object.hasOwnProperty.call(message, "estimatedAngle")) - writer.uint32(/* id 8, wireType 1 =*/65).double(message.estimatedAngle); - if (message.xsensIsCalibrated != null && Object.hasOwnProperty.call(message, "xsensIsCalibrated")) - writer.uint32(/* id 9, wireType 0 =*/72).bool(message.xsensIsCalibrated); - if (message.capacitorIsCharged != null && Object.hasOwnProperty.call(message, "capacitorIsCharged")) - writer.uint32(/* id 10, wireType 0 =*/80).bool(message.capacitorIsCharged); - if (message.wheelsLocked != null && Object.hasOwnProperty.call(message, "wheelsLocked")) - writer.uint32(/* id 11, wireType 0 =*/88).int32(message.wheelsLocked); - if (message.wheelsBraking != null && Object.hasOwnProperty.call(message, "wheelsBraking")) - writer.uint32(/* id 12, wireType 0 =*/96).int32(message.wheelsBraking); - if (message.batteryLevel != null && Object.hasOwnProperty.call(message, "batteryLevel")) - writer.uint32(/* id 13, wireType 5 =*/109).float(message.batteryLevel); - if (message.signalStrength != null && Object.hasOwnProperty.call(message, "signalStrength")) - writer.uint32(/* id 14, wireType 0 =*/112).int32(message.signalStrength); + writer.uint32(/* id 1, wireType 5 =*/13).float(message.x); + writer.uint32(/* id 2, wireType 5 =*/21).float(message.y); return writer; }; /** - * Encodes the specified RobotFeedback message, length delimited. Does not implicitly {@link proto.RobotFeedback.verify|verify} messages. + * Encodes the specified Vector2 message, length delimited. Does not implicitly {@link proto.Vector2.verify|verify} messages. * @function encodeDelimited - * @memberof proto.RobotFeedback + * @memberof proto.Vector2 * @static - * @param {proto.IRobotFeedback} message RobotFeedback message or plain object to encode + * @param {proto.IVector2} message Vector2 message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ - RobotFeedback.encodeDelimited = function encodeDelimited(message, writer) { + Vector2.encodeDelimited = function encodeDelimited(message, writer) { return this.encode(message, writer).ldelim(); }; /** - * Decodes a RobotFeedback message from the specified reader or buffer. + * Decodes a Vector2 message from the specified reader or buffer. * @function decode - * @memberof proto.RobotFeedback + * @memberof proto.Vector2 * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from * @param {number} [length] Message length if known beforehand - * @returns {proto.RobotFeedback} RobotFeedback + * @returns {proto.Vector2} Vector2 * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - RobotFeedback.decode = function decode(reader, length) { + Vector2.decode = function decode(reader, length) { if (!(reader instanceof $Reader)) reader = $Reader.create(reader); - let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.RobotFeedback(); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.Vector2(); while (reader.pos < end) { let tag = reader.uint32(); switch (tag >>> 3) { case 1: { - message.id = reader.int32(); + message.x = reader.float(); break; } case 2: { - message.ballSensorSeesBall = reader.bool(); - break; - } - case 3: { - message.ballPosition = reader.float(); - break; - } - case 4: { - message.ballSensorIsWorking = reader.bool(); - break; - } - case 5: { - message.dribblerSeesBall = reader.bool(); - break; - } - case 6: { - message.estimatedVelocityX = reader.double(); - break; - } - case 7: { - message.estimatedVelocityY = reader.double(); - break; - } - case 8: { - message.estimatedAngle = reader.double(); - break; - } - case 9: { - message.xsensIsCalibrated = reader.bool(); - break; - } - case 10: { - message.capacitorIsCharged = reader.bool(); - break; - } - case 11: { - message.wheelsLocked = reader.int32(); - break; - } - case 12: { - message.wheelsBraking = reader.int32(); - break; - } - case 13: { - message.batteryLevel = reader.float(); - break; - } - case 14: { - message.signalStrength = reader.int32(); + message.y = reader.float(); break; } default: @@ -27887,234 +28507,139 @@ export const proto = $root.proto = (() => { break; } } + if (!message.hasOwnProperty("x")) + throw $util.ProtocolError("missing required 'x'", { instance: message }); + if (!message.hasOwnProperty("y")) + throw $util.ProtocolError("missing required 'y'", { instance: message }); return message; }; /** - * Decodes a RobotFeedback message from the specified reader or buffer, length delimited. + * Decodes a Vector2 message from the specified reader or buffer, length delimited. * @function decodeDelimited - * @memberof proto.RobotFeedback + * @memberof proto.Vector2 * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @returns {proto.RobotFeedback} RobotFeedback + * @returns {proto.Vector2} Vector2 * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - RobotFeedback.decodeDelimited = function decodeDelimited(reader) { + Vector2.decodeDelimited = function decodeDelimited(reader) { if (!(reader instanceof $Reader)) reader = new $Reader(reader); return this.decode(reader, reader.uint32()); }; /** - * Verifies a RobotFeedback message. + * Verifies a Vector2 message. * @function verify - * @memberof proto.RobotFeedback + * @memberof proto.Vector2 * @static * @param {Object.} message Plain object to verify * @returns {string|null} `null` if valid, otherwise the reason why it is not */ - RobotFeedback.verify = function verify(message) { + Vector2.verify = function verify(message) { if (typeof message !== "object" || message === null) return "object expected"; - if (message.id != null && message.hasOwnProperty("id")) - if (!$util.isInteger(message.id)) - return "id: integer expected"; - if (message.ballSensorSeesBall != null && message.hasOwnProperty("ballSensorSeesBall")) - if (typeof message.ballSensorSeesBall !== "boolean") - return "ballSensorSeesBall: boolean expected"; - if (message.ballPosition != null && message.hasOwnProperty("ballPosition")) - if (typeof message.ballPosition !== "number") - return "ballPosition: number expected"; - if (message.ballSensorIsWorking != null && message.hasOwnProperty("ballSensorIsWorking")) - if (typeof message.ballSensorIsWorking !== "boolean") - return "ballSensorIsWorking: boolean expected"; - if (message.dribblerSeesBall != null && message.hasOwnProperty("dribblerSeesBall")) - if (typeof message.dribblerSeesBall !== "boolean") - return "dribblerSeesBall: boolean expected"; - if (message.estimatedVelocityX != null && message.hasOwnProperty("estimatedVelocityX")) - if (typeof message.estimatedVelocityX !== "number") - return "estimatedVelocityX: number expected"; - if (message.estimatedVelocityY != null && message.hasOwnProperty("estimatedVelocityY")) - if (typeof message.estimatedVelocityY !== "number") - return "estimatedVelocityY: number expected"; - if (message.estimatedAngle != null && message.hasOwnProperty("estimatedAngle")) - if (typeof message.estimatedAngle !== "number") - return "estimatedAngle: number expected"; - if (message.xsensIsCalibrated != null && message.hasOwnProperty("xsensIsCalibrated")) - if (typeof message.xsensIsCalibrated !== "boolean") - return "xsensIsCalibrated: boolean expected"; - if (message.capacitorIsCharged != null && message.hasOwnProperty("capacitorIsCharged")) - if (typeof message.capacitorIsCharged !== "boolean") - return "capacitorIsCharged: boolean expected"; - if (message.wheelsLocked != null && message.hasOwnProperty("wheelsLocked")) - if (!$util.isInteger(message.wheelsLocked)) - return "wheelsLocked: integer expected"; - if (message.wheelsBraking != null && message.hasOwnProperty("wheelsBraking")) - if (!$util.isInteger(message.wheelsBraking)) - return "wheelsBraking: integer expected"; - if (message.batteryLevel != null && message.hasOwnProperty("batteryLevel")) - if (typeof message.batteryLevel !== "number") - return "batteryLevel: number expected"; - if (message.signalStrength != null && message.hasOwnProperty("signalStrength")) - if (!$util.isInteger(message.signalStrength)) - return "signalStrength: integer expected"; + if (typeof message.x !== "number") + return "x: number expected"; + if (typeof message.y !== "number") + return "y: number expected"; return null; }; /** - * Creates a RobotFeedback message from a plain object. Also converts values to their respective internal types. + * Creates a Vector2 message from a plain object. Also converts values to their respective internal types. * @function fromObject - * @memberof proto.RobotFeedback + * @memberof proto.Vector2 * @static * @param {Object.} object Plain object - * @returns {proto.RobotFeedback} RobotFeedback + * @returns {proto.Vector2} Vector2 */ - RobotFeedback.fromObject = function fromObject(object) { - if (object instanceof $root.proto.RobotFeedback) + Vector2.fromObject = function fromObject(object) { + if (object instanceof $root.proto.Vector2) return object; - let message = new $root.proto.RobotFeedback(); - if (object.id != null) - message.id = object.id | 0; - if (object.ballSensorSeesBall != null) - message.ballSensorSeesBall = Boolean(object.ballSensorSeesBall); - if (object.ballPosition != null) - message.ballPosition = Number(object.ballPosition); - if (object.ballSensorIsWorking != null) - message.ballSensorIsWorking = Boolean(object.ballSensorIsWorking); - if (object.dribblerSeesBall != null) - message.dribblerSeesBall = Boolean(object.dribblerSeesBall); - if (object.estimatedVelocityX != null) - message.estimatedVelocityX = Number(object.estimatedVelocityX); - if (object.estimatedVelocityY != null) - message.estimatedVelocityY = Number(object.estimatedVelocityY); - if (object.estimatedAngle != null) - message.estimatedAngle = Number(object.estimatedAngle); - if (object.xsensIsCalibrated != null) - message.xsensIsCalibrated = Boolean(object.xsensIsCalibrated); - if (object.capacitorIsCharged != null) - message.capacitorIsCharged = Boolean(object.capacitorIsCharged); - if (object.wheelsLocked != null) - message.wheelsLocked = object.wheelsLocked | 0; - if (object.wheelsBraking != null) - message.wheelsBraking = object.wheelsBraking | 0; - if (object.batteryLevel != null) - message.batteryLevel = Number(object.batteryLevel); - if (object.signalStrength != null) - message.signalStrength = object.signalStrength | 0; + let message = new $root.proto.Vector2(); + if (object.x != null) + message.x = Number(object.x); + if (object.y != null) + message.y = Number(object.y); return message; }; /** - * Creates a plain object from a RobotFeedback message. Also converts values to other types if specified. + * Creates a plain object from a Vector2 message. Also converts values to other types if specified. * @function toObject - * @memberof proto.RobotFeedback + * @memberof proto.Vector2 * @static - * @param {proto.RobotFeedback} message RobotFeedback + * @param {proto.Vector2} message Vector2 * @param {$protobuf.IConversionOptions} [options] Conversion options * @returns {Object.} Plain object */ - RobotFeedback.toObject = function toObject(message, options) { + Vector2.toObject = function toObject(message, options) { if (!options) options = {}; let object = {}; if (options.defaults) { - object.id = 0; - object.ballSensorSeesBall = false; - object.ballPosition = 0; - object.ballSensorIsWorking = false; - object.dribblerSeesBall = false; - object.estimatedVelocityX = 0; - object.estimatedVelocityY = 0; - object.estimatedAngle = 0; - object.xsensIsCalibrated = false; - object.capacitorIsCharged = false; - object.wheelsLocked = 0; - object.wheelsBraking = 0; - object.batteryLevel = 0; - object.signalStrength = 0; + object.x = 0; + object.y = 0; } - if (message.id != null && message.hasOwnProperty("id")) - object.id = message.id; - if (message.ballSensorSeesBall != null && message.hasOwnProperty("ballSensorSeesBall")) - object.ballSensorSeesBall = message.ballSensorSeesBall; - if (message.ballPosition != null && message.hasOwnProperty("ballPosition")) - object.ballPosition = options.json && !isFinite(message.ballPosition) ? String(message.ballPosition) : message.ballPosition; - if (message.ballSensorIsWorking != null && message.hasOwnProperty("ballSensorIsWorking")) - object.ballSensorIsWorking = message.ballSensorIsWorking; - if (message.dribblerSeesBall != null && message.hasOwnProperty("dribblerSeesBall")) - object.dribblerSeesBall = message.dribblerSeesBall; - if (message.estimatedVelocityX != null && message.hasOwnProperty("estimatedVelocityX")) - object.estimatedVelocityX = options.json && !isFinite(message.estimatedVelocityX) ? String(message.estimatedVelocityX) : message.estimatedVelocityX; - if (message.estimatedVelocityY != null && message.hasOwnProperty("estimatedVelocityY")) - object.estimatedVelocityY = options.json && !isFinite(message.estimatedVelocityY) ? String(message.estimatedVelocityY) : message.estimatedVelocityY; - if (message.estimatedAngle != null && message.hasOwnProperty("estimatedAngle")) - object.estimatedAngle = options.json && !isFinite(message.estimatedAngle) ? String(message.estimatedAngle) : message.estimatedAngle; - if (message.xsensIsCalibrated != null && message.hasOwnProperty("xsensIsCalibrated")) - object.xsensIsCalibrated = message.xsensIsCalibrated; - if (message.capacitorIsCharged != null && message.hasOwnProperty("capacitorIsCharged")) - object.capacitorIsCharged = message.capacitorIsCharged; - if (message.wheelsLocked != null && message.hasOwnProperty("wheelsLocked")) - object.wheelsLocked = message.wheelsLocked; - if (message.wheelsBraking != null && message.hasOwnProperty("wheelsBraking")) - object.wheelsBraking = message.wheelsBraking; - if (message.batteryLevel != null && message.hasOwnProperty("batteryLevel")) - object.batteryLevel = options.json && !isFinite(message.batteryLevel) ? String(message.batteryLevel) : message.batteryLevel; - if (message.signalStrength != null && message.hasOwnProperty("signalStrength")) - object.signalStrength = message.signalStrength; + if (message.x != null && message.hasOwnProperty("x")) + object.x = options.json && !isFinite(message.x) ? String(message.x) : message.x; + if (message.y != null && message.hasOwnProperty("y")) + object.y = options.json && !isFinite(message.y) ? String(message.y) : message.y; return object; }; /** - * Converts this RobotFeedback to JSON. + * Converts this Vector2 to JSON. * @function toJSON - * @memberof proto.RobotFeedback + * @memberof proto.Vector2 * @instance * @returns {Object.} JSON object */ - RobotFeedback.prototype.toJSON = function toJSON() { + Vector2.prototype.toJSON = function toJSON() { return this.constructor.toObject(this, $protobuf.util.toJSONOptions); }; /** - * Gets the default type url for RobotFeedback + * Gets the default type url for Vector2 * @function getTypeUrl - * @memberof proto.RobotFeedback + * @memberof proto.Vector2 * @static * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns {string} The default type url */ - RobotFeedback.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + Vector2.getTypeUrl = function getTypeUrl(typeUrlPrefix) { if (typeUrlPrefix === undefined) { typeUrlPrefix = "type.googleapis.com"; } - return typeUrlPrefix + "/proto.RobotFeedback"; + return typeUrlPrefix + "/proto.Vector2"; }; - return RobotFeedback; + return Vector2; })(); - proto.RobotsFeedback = (function() { + proto.Vector3 = (function() { /** - * Properties of a RobotsFeedback. + * Properties of a Vector3. * @memberof proto - * @interface IRobotsFeedback - * @property {proto.RobotTeam|null} [team] RobotsFeedback team - * @property {proto.RobotFeedbackSource|null} [source] RobotsFeedback source - * @property {Array.|null} [robotsFeedback] RobotsFeedback robotsFeedback + * @interface IVector3 + * @property {number} x Vector3 x + * @property {number} y Vector3 y + * @property {number} z Vector3 z */ /** - * Constructs a new RobotsFeedback. + * Constructs a new Vector3. * @memberof proto - * @classdesc Represents a RobotsFeedback. - * @implements IRobotsFeedback + * @classdesc Represents a Vector3. + * @implements IVector3 * @constructor - * @param {proto.IRobotsFeedback=} [properties] Properties to set + * @param {proto.IVector3=} [properties] Properties to set */ - function RobotsFeedback(properties) { - this.robotsFeedback = []; + function Vector3(properties) { if (properties) for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) if (properties[keys[i]] != null) @@ -28122,106 +28647,100 @@ export const proto = $root.proto = (() => { } /** - * RobotsFeedback team. - * @member {proto.RobotTeam} team - * @memberof proto.RobotsFeedback + * Vector3 x. + * @member {number} x + * @memberof proto.Vector3 * @instance */ - RobotsFeedback.prototype.team = 0; + Vector3.prototype.x = 0; /** - * RobotsFeedback source. - * @member {proto.RobotFeedbackSource} source - * @memberof proto.RobotsFeedback + * Vector3 y. + * @member {number} y + * @memberof proto.Vector3 * @instance */ - RobotsFeedback.prototype.source = 0; + Vector3.prototype.y = 0; /** - * RobotsFeedback robotsFeedback. - * @member {Array.} robotsFeedback - * @memberof proto.RobotsFeedback + * Vector3 z. + * @member {number} z + * @memberof proto.Vector3 * @instance */ - RobotsFeedback.prototype.robotsFeedback = $util.emptyArray; + Vector3.prototype.z = 0; /** - * Creates a new RobotsFeedback instance using the specified properties. + * Creates a new Vector3 instance using the specified properties. * @function create - * @memberof proto.RobotsFeedback + * @memberof proto.Vector3 * @static - * @param {proto.IRobotsFeedback=} [properties] Properties to set - * @returns {proto.RobotsFeedback} RobotsFeedback instance + * @param {proto.IVector3=} [properties] Properties to set + * @returns {proto.Vector3} Vector3 instance */ - RobotsFeedback.create = function create(properties) { - return new RobotsFeedback(properties); + Vector3.create = function create(properties) { + return new Vector3(properties); }; /** - * Encodes the specified RobotsFeedback message. Does not implicitly {@link proto.RobotsFeedback.verify|verify} messages. + * Encodes the specified Vector3 message. Does not implicitly {@link proto.Vector3.verify|verify} messages. * @function encode - * @memberof proto.RobotsFeedback + * @memberof proto.Vector3 * @static - * @param {proto.IRobotsFeedback} message RobotsFeedback message or plain object to encode + * @param {proto.IVector3} message Vector3 message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ - RobotsFeedback.encode = function encode(message, writer) { + Vector3.encode = function encode(message, writer) { if (!writer) writer = $Writer.create(); - if (message.team != null && Object.hasOwnProperty.call(message, "team")) - writer.uint32(/* id 1, wireType 0 =*/8).int32(message.team); - if (message.source != null && Object.hasOwnProperty.call(message, "source")) - writer.uint32(/* id 2, wireType 0 =*/16).int32(message.source); - if (message.robotsFeedback != null && message.robotsFeedback.length) - for (let i = 0; i < message.robotsFeedback.length; ++i) - $root.proto.RobotFeedback.encode(message.robotsFeedback[i], writer.uint32(/* id 3, wireType 2 =*/26).fork()).ldelim(); + writer.uint32(/* id 1, wireType 5 =*/13).float(message.x); + writer.uint32(/* id 2, wireType 5 =*/21).float(message.y); + writer.uint32(/* id 3, wireType 5 =*/29).float(message.z); return writer; }; /** - * Encodes the specified RobotsFeedback message, length delimited. Does not implicitly {@link proto.RobotsFeedback.verify|verify} messages. + * Encodes the specified Vector3 message, length delimited. Does not implicitly {@link proto.Vector3.verify|verify} messages. * @function encodeDelimited - * @memberof proto.RobotsFeedback + * @memberof proto.Vector3 * @static - * @param {proto.IRobotsFeedback} message RobotsFeedback message or plain object to encode + * @param {proto.IVector3} message Vector3 message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ - RobotsFeedback.encodeDelimited = function encodeDelimited(message, writer) { + Vector3.encodeDelimited = function encodeDelimited(message, writer) { return this.encode(message, writer).ldelim(); }; /** - * Decodes a RobotsFeedback message from the specified reader or buffer. + * Decodes a Vector3 message from the specified reader or buffer. * @function decode - * @memberof proto.RobotsFeedback + * @memberof proto.Vector3 * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from * @param {number} [length] Message length if known beforehand - * @returns {proto.RobotsFeedback} RobotsFeedback + * @returns {proto.Vector3} Vector3 * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - RobotsFeedback.decode = function decode(reader, length) { + Vector3.decode = function decode(reader, length) { if (!(reader instanceof $Reader)) reader = $Reader.create(reader); - let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.RobotsFeedback(); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.Vector3(); while (reader.pos < end) { let tag = reader.uint32(); switch (tag >>> 3) { case 1: { - message.team = reader.int32(); + message.x = reader.float(); break; } case 2: { - message.source = reader.int32(); + message.y = reader.float(); break; } case 3: { - if (!(message.robotsFeedback && message.robotsFeedback.length)) - message.robotsFeedback = []; - message.robotsFeedback.push($root.proto.RobotFeedback.decode(reader, reader.uint32())); + message.z = reader.float(); break; } default: @@ -28229,212 +28748,183 @@ export const proto = $root.proto = (() => { break; } } + if (!message.hasOwnProperty("x")) + throw $util.ProtocolError("missing required 'x'", { instance: message }); + if (!message.hasOwnProperty("y")) + throw $util.ProtocolError("missing required 'y'", { instance: message }); + if (!message.hasOwnProperty("z")) + throw $util.ProtocolError("missing required 'z'", { instance: message }); return message; }; /** - * Decodes a RobotsFeedback message from the specified reader or buffer, length delimited. + * Decodes a Vector3 message from the specified reader or buffer, length delimited. * @function decodeDelimited - * @memberof proto.RobotsFeedback + * @memberof proto.Vector3 * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @returns {proto.RobotsFeedback} RobotsFeedback + * @returns {proto.Vector3} Vector3 * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - RobotsFeedback.decodeDelimited = function decodeDelimited(reader) { + Vector3.decodeDelimited = function decodeDelimited(reader) { if (!(reader instanceof $Reader)) reader = new $Reader(reader); return this.decode(reader, reader.uint32()); }; /** - * Verifies a RobotsFeedback message. + * Verifies a Vector3 message. * @function verify - * @memberof proto.RobotsFeedback + * @memberof proto.Vector3 * @static * @param {Object.} message Plain object to verify * @returns {string|null} `null` if valid, otherwise the reason why it is not */ - RobotsFeedback.verify = function verify(message) { + Vector3.verify = function verify(message) { if (typeof message !== "object" || message === null) return "object expected"; - if (message.team != null && message.hasOwnProperty("team")) - switch (message.team) { - default: - return "team: enum value expected"; - case 0: - case 1: - break; - } - if (message.source != null && message.hasOwnProperty("source")) - switch (message.source) { - default: - return "source: enum value expected"; - case 0: - case 1: - break; - } - if (message.robotsFeedback != null && message.hasOwnProperty("robotsFeedback")) { - if (!Array.isArray(message.robotsFeedback)) - return "robotsFeedback: array expected"; - for (let i = 0; i < message.robotsFeedback.length; ++i) { - let error = $root.proto.RobotFeedback.verify(message.robotsFeedback[i]); - if (error) - return "robotsFeedback." + error; - } - } + if (typeof message.x !== "number") + return "x: number expected"; + if (typeof message.y !== "number") + return "y: number expected"; + if (typeof message.z !== "number") + return "z: number expected"; return null; }; /** - * Creates a RobotsFeedback message from a plain object. Also converts values to their respective internal types. + * Creates a Vector3 message from a plain object. Also converts values to their respective internal types. * @function fromObject - * @memberof proto.RobotsFeedback + * @memberof proto.Vector3 * @static * @param {Object.} object Plain object - * @returns {proto.RobotsFeedback} RobotsFeedback + * @returns {proto.Vector3} Vector3 */ - RobotsFeedback.fromObject = function fromObject(object) { - if (object instanceof $root.proto.RobotsFeedback) + Vector3.fromObject = function fromObject(object) { + if (object instanceof $root.proto.Vector3) return object; - let message = new $root.proto.RobotsFeedback(); - switch (object.team) { - default: - if (typeof object.team === "number") { - message.team = object.team; - break; - } - break; - case "YELLOW_TEAM": - case 0: - message.team = 0; - break; - case "BLUE_TEAM": - case 1: - message.team = 1; - break; - } - switch (object.source) { - default: - if (typeof object.source === "number") { - message.source = object.source; - break; - } - break; - case "SIMULATOR": - case 0: - message.source = 0; - break; - case "BASESTATION": - case 1: - message.source = 1; - break; - } - if (object.robotsFeedback) { - if (!Array.isArray(object.robotsFeedback)) - throw TypeError(".proto.RobotsFeedback.robotsFeedback: array expected"); - message.robotsFeedback = []; - for (let i = 0; i < object.robotsFeedback.length; ++i) { - if (typeof object.robotsFeedback[i] !== "object") - throw TypeError(".proto.RobotsFeedback.robotsFeedback: object expected"); - message.robotsFeedback[i] = $root.proto.RobotFeedback.fromObject(object.robotsFeedback[i]); - } - } + let message = new $root.proto.Vector3(); + if (object.x != null) + message.x = Number(object.x); + if (object.y != null) + message.y = Number(object.y); + if (object.z != null) + message.z = Number(object.z); return message; }; /** - * Creates a plain object from a RobotsFeedback message. Also converts values to other types if specified. + * Creates a plain object from a Vector3 message. Also converts values to other types if specified. * @function toObject - * @memberof proto.RobotsFeedback + * @memberof proto.Vector3 * @static - * @param {proto.RobotsFeedback} message RobotsFeedback + * @param {proto.Vector3} message Vector3 * @param {$protobuf.IConversionOptions} [options] Conversion options * @returns {Object.} Plain object */ - RobotsFeedback.toObject = function toObject(message, options) { + Vector3.toObject = function toObject(message, options) { if (!options) options = {}; let object = {}; - if (options.arrays || options.defaults) - object.robotsFeedback = []; if (options.defaults) { - object.team = options.enums === String ? "YELLOW_TEAM" : 0; - object.source = options.enums === String ? "SIMULATOR" : 0; - } - if (message.team != null && message.hasOwnProperty("team")) - object.team = options.enums === String ? $root.proto.RobotTeam[message.team] === undefined ? message.team : $root.proto.RobotTeam[message.team] : message.team; - if (message.source != null && message.hasOwnProperty("source")) - object.source = options.enums === String ? $root.proto.RobotFeedbackSource[message.source] === undefined ? message.source : $root.proto.RobotFeedbackSource[message.source] : message.source; - if (message.robotsFeedback && message.robotsFeedback.length) { - object.robotsFeedback = []; - for (let j = 0; j < message.robotsFeedback.length; ++j) - object.robotsFeedback[j] = $root.proto.RobotFeedback.toObject(message.robotsFeedback[j], options); + object.x = 0; + object.y = 0; + object.z = 0; } + if (message.x != null && message.hasOwnProperty("x")) + object.x = options.json && !isFinite(message.x) ? String(message.x) : message.x; + if (message.y != null && message.hasOwnProperty("y")) + object.y = options.json && !isFinite(message.y) ? String(message.y) : message.y; + if (message.z != null && message.hasOwnProperty("z")) + object.z = options.json && !isFinite(message.z) ? String(message.z) : message.z; return object; }; /** - * Converts this RobotsFeedback to JSON. + * Converts this Vector3 to JSON. * @function toJSON - * @memberof proto.RobotsFeedback + * @memberof proto.Vector3 * @instance * @returns {Object.} JSON object */ - RobotsFeedback.prototype.toJSON = function toJSON() { + Vector3.prototype.toJSON = function toJSON() { return this.constructor.toObject(this, $protobuf.util.toJSONOptions); }; /** - * Gets the default type url for RobotsFeedback + * Gets the default type url for Vector3 * @function getTypeUrl - * @memberof proto.RobotsFeedback + * @memberof proto.Vector3 * @static * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns {string} The default type url */ - RobotsFeedback.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + Vector3.getTypeUrl = function getTypeUrl(typeUrlPrefix) { if (typeUrlPrefix === undefined) { typeUrlPrefix = "type.googleapis.com"; } - return typeUrlPrefix + "/proto.RobotsFeedback"; + return typeUrlPrefix + "/proto.Vector3"; }; - return RobotsFeedback; + return Vector3; })(); - proto.RobotCommand = (function() { + /** + * RobotTeam enum. + * @name proto.RobotTeam + * @enum {number} + * @property {number} YELLOW_TEAM=0 YELLOW_TEAM value + * @property {number} BLUE_TEAM=1 BLUE_TEAM value + */ + proto.RobotTeam = (function() { + const valuesById = {}, values = Object.create(valuesById); + values[valuesById[0] = "YELLOW_TEAM"] = 0; + values[valuesById[1] = "BLUE_TEAM"] = 1; + return values; + })(); + + /** + * RobotFeedbackSource enum. + * @name proto.RobotFeedbackSource + * @enum {number} + * @property {number} SIMULATOR=0 SIMULATOR value + * @property {number} BASESTATION=1 BASESTATION value + */ + proto.RobotFeedbackSource = (function() { + const valuesById = {}, values = Object.create(valuesById); + values[valuesById[0] = "SIMULATOR"] = 0; + values[valuesById[1] = "BASESTATION"] = 1; + return values; + })(); + + proto.RobotFeedback = (function() { /** - * Properties of a RobotCommand. + * Properties of a RobotFeedback. * @memberof proto - * @interface IRobotCommand - * @property {number|null} [id] RobotCommand id - * @property {number|null} [velocityX] RobotCommand velocityX - * @property {number|null} [velocityY] RobotCommand velocityY - * @property {number|null} [angle] RobotCommand angle - * @property {number|null} [angularVelocity] RobotCommand angularVelocity - * @property {boolean|null} [useAngularVelocity] RobotCommand useAngularVelocity - * @property {number|null} [cameraAngleOfRobot] RobotCommand cameraAngleOfRobot - * @property {boolean|null} [cameraAngleOfRobotIsSet] RobotCommand cameraAngleOfRobotIsSet - * @property {number|null} [kickSpeed] RobotCommand kickSpeed - * @property {boolean|null} [waitForBall] RobotCommand waitForBall - * @property {boolean|null} [kickAtAngle] RobotCommand kickAtAngle - * @property {proto.RobotCommand.KickType|null} [kickType] RobotCommand kickType - * @property {number|null} [dribblerSpeed] RobotCommand dribblerSpeed - * @property {boolean|null} [ignorePacket] RobotCommand ignorePacket + * @interface IRobotFeedback + * @property {number|null} [id] RobotFeedback id + * @property {boolean|null} [ballSensorSeesBall] RobotFeedback ballSensorSeesBall + * @property {boolean|null} [ballSensorIsWorking] RobotFeedback ballSensorIsWorking + * @property {boolean|null} [dribblerSeesBall] RobotFeedback dribblerSeesBall + * @property {number|null} [estimatedVelocityX] RobotFeedback estimatedVelocityX + * @property {number|null} [estimatedVelocityY] RobotFeedback estimatedVelocityY + * @property {number|null} [estimatedYaw] RobotFeedback estimatedYaw + * @property {boolean|null} [xsensIsCalibrated] RobotFeedback xsensIsCalibrated + * @property {boolean|null} [capacitorIsCharged] RobotFeedback capacitorIsCharged + * @property {number|null} [batteryLevel] RobotFeedback batteryLevel */ /** - * Constructs a new RobotCommand. + * Constructs a new RobotFeedback. * @memberof proto - * @classdesc Represents a RobotCommand. - * @implements IRobotCommand + * @classdesc Represents a RobotFeedback. + * @implements IRobotFeedback * @constructor - * @param {proto.IRobotCommand=} [properties] Properties to set + * @param {proto.IRobotFeedback=} [properties] Properties to set */ - function RobotCommand(properties) { + function RobotFeedback(properties) { if (properties) for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) if (properties[keys[i]] != null) @@ -28442,200 +28932,160 @@ export const proto = $root.proto = (() => { } /** - * RobotCommand id. + * RobotFeedback id. * @member {number} id - * @memberof proto.RobotCommand - * @instance - */ - RobotCommand.prototype.id = 0; - - /** - * RobotCommand velocityX. - * @member {number} velocityX - * @memberof proto.RobotCommand - * @instance - */ - RobotCommand.prototype.velocityX = 0; - - /** - * RobotCommand velocityY. - * @member {number} velocityY - * @memberof proto.RobotCommand - * @instance - */ - RobotCommand.prototype.velocityY = 0; - - /** - * RobotCommand angle. - * @member {number} angle - * @memberof proto.RobotCommand - * @instance - */ - RobotCommand.prototype.angle = 0; - - /** - * RobotCommand angularVelocity. - * @member {number} angularVelocity - * @memberof proto.RobotCommand + * @memberof proto.RobotFeedback * @instance */ - RobotCommand.prototype.angularVelocity = 0; + RobotFeedback.prototype.id = 0; /** - * RobotCommand useAngularVelocity. - * @member {boolean} useAngularVelocity - * @memberof proto.RobotCommand + * RobotFeedback ballSensorSeesBall. + * @member {boolean} ballSensorSeesBall + * @memberof proto.RobotFeedback * @instance */ - RobotCommand.prototype.useAngularVelocity = false; + RobotFeedback.prototype.ballSensorSeesBall = false; /** - * RobotCommand cameraAngleOfRobot. - * @member {number} cameraAngleOfRobot - * @memberof proto.RobotCommand + * RobotFeedback ballSensorIsWorking. + * @member {boolean} ballSensorIsWorking + * @memberof proto.RobotFeedback * @instance */ - RobotCommand.prototype.cameraAngleOfRobot = 0; + RobotFeedback.prototype.ballSensorIsWorking = false; /** - * RobotCommand cameraAngleOfRobotIsSet. - * @member {boolean} cameraAngleOfRobotIsSet - * @memberof proto.RobotCommand + * RobotFeedback dribblerSeesBall. + * @member {boolean} dribblerSeesBall + * @memberof proto.RobotFeedback * @instance */ - RobotCommand.prototype.cameraAngleOfRobotIsSet = false; + RobotFeedback.prototype.dribblerSeesBall = false; /** - * RobotCommand kickSpeed. - * @member {number} kickSpeed - * @memberof proto.RobotCommand + * RobotFeedback estimatedVelocityX. + * @member {number} estimatedVelocityX + * @memberof proto.RobotFeedback * @instance */ - RobotCommand.prototype.kickSpeed = 0; + RobotFeedback.prototype.estimatedVelocityX = 0; /** - * RobotCommand waitForBall. - * @member {boolean} waitForBall - * @memberof proto.RobotCommand + * RobotFeedback estimatedVelocityY. + * @member {number} estimatedVelocityY + * @memberof proto.RobotFeedback * @instance */ - RobotCommand.prototype.waitForBall = false; + RobotFeedback.prototype.estimatedVelocityY = 0; /** - * RobotCommand kickAtAngle. - * @member {boolean} kickAtAngle - * @memberof proto.RobotCommand + * RobotFeedback estimatedYaw. + * @member {number} estimatedYaw + * @memberof proto.RobotFeedback * @instance */ - RobotCommand.prototype.kickAtAngle = false; + RobotFeedback.prototype.estimatedYaw = 0; /** - * RobotCommand kickType. - * @member {proto.RobotCommand.KickType} kickType - * @memberof proto.RobotCommand + * RobotFeedback xsensIsCalibrated. + * @member {boolean} xsensIsCalibrated + * @memberof proto.RobotFeedback * @instance */ - RobotCommand.prototype.kickType = 0; + RobotFeedback.prototype.xsensIsCalibrated = false; /** - * RobotCommand dribblerSpeed. - * @member {number} dribblerSpeed - * @memberof proto.RobotCommand + * RobotFeedback capacitorIsCharged. + * @member {boolean} capacitorIsCharged + * @memberof proto.RobotFeedback * @instance */ - RobotCommand.prototype.dribblerSpeed = 0; + RobotFeedback.prototype.capacitorIsCharged = false; /** - * RobotCommand ignorePacket. - * @member {boolean} ignorePacket - * @memberof proto.RobotCommand + * RobotFeedback batteryLevel. + * @member {number} batteryLevel + * @memberof proto.RobotFeedback * @instance */ - RobotCommand.prototype.ignorePacket = false; + RobotFeedback.prototype.batteryLevel = 0; /** - * Creates a new RobotCommand instance using the specified properties. + * Creates a new RobotFeedback instance using the specified properties. * @function create - * @memberof proto.RobotCommand + * @memberof proto.RobotFeedback * @static - * @param {proto.IRobotCommand=} [properties] Properties to set - * @returns {proto.RobotCommand} RobotCommand instance + * @param {proto.IRobotFeedback=} [properties] Properties to set + * @returns {proto.RobotFeedback} RobotFeedback instance */ - RobotCommand.create = function create(properties) { - return new RobotCommand(properties); + RobotFeedback.create = function create(properties) { + return new RobotFeedback(properties); }; /** - * Encodes the specified RobotCommand message. Does not implicitly {@link proto.RobotCommand.verify|verify} messages. + * Encodes the specified RobotFeedback message. Does not implicitly {@link proto.RobotFeedback.verify|verify} messages. * @function encode - * @memberof proto.RobotCommand + * @memberof proto.RobotFeedback * @static - * @param {proto.IRobotCommand} message RobotCommand message or plain object to encode + * @param {proto.IRobotFeedback} message RobotFeedback message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ - RobotCommand.encode = function encode(message, writer) { + RobotFeedback.encode = function encode(message, writer) { if (!writer) writer = $Writer.create(); if (message.id != null && Object.hasOwnProperty.call(message, "id")) writer.uint32(/* id 1, wireType 0 =*/8).int32(message.id); - if (message.velocityX != null && Object.hasOwnProperty.call(message, "velocityX")) - writer.uint32(/* id 2, wireType 1 =*/17).double(message.velocityX); - if (message.velocityY != null && Object.hasOwnProperty.call(message, "velocityY")) - writer.uint32(/* id 3, wireType 1 =*/25).double(message.velocityY); - if (message.angle != null && Object.hasOwnProperty.call(message, "angle")) - writer.uint32(/* id 4, wireType 1 =*/33).double(message.angle); - if (message.angularVelocity != null && Object.hasOwnProperty.call(message, "angularVelocity")) - writer.uint32(/* id 5, wireType 1 =*/41).double(message.angularVelocity); - if (message.useAngularVelocity != null && Object.hasOwnProperty.call(message, "useAngularVelocity")) - writer.uint32(/* id 6, wireType 0 =*/48).bool(message.useAngularVelocity); - if (message.cameraAngleOfRobot != null && Object.hasOwnProperty.call(message, "cameraAngleOfRobot")) - writer.uint32(/* id 7, wireType 1 =*/57).double(message.cameraAngleOfRobot); - if (message.cameraAngleOfRobotIsSet != null && Object.hasOwnProperty.call(message, "cameraAngleOfRobotIsSet")) - writer.uint32(/* id 8, wireType 0 =*/64).bool(message.cameraAngleOfRobotIsSet); - if (message.kickSpeed != null && Object.hasOwnProperty.call(message, "kickSpeed")) - writer.uint32(/* id 9, wireType 1 =*/73).double(message.kickSpeed); - if (message.waitForBall != null && Object.hasOwnProperty.call(message, "waitForBall")) - writer.uint32(/* id 10, wireType 0 =*/80).bool(message.waitForBall); - if (message.kickAtAngle != null && Object.hasOwnProperty.call(message, "kickAtAngle")) - writer.uint32(/* id 11, wireType 0 =*/88).bool(message.kickAtAngle); - if (message.kickType != null && Object.hasOwnProperty.call(message, "kickType")) - writer.uint32(/* id 12, wireType 0 =*/96).int32(message.kickType); - if (message.dribblerSpeed != null && Object.hasOwnProperty.call(message, "dribblerSpeed")) - writer.uint32(/* id 13, wireType 1 =*/105).double(message.dribblerSpeed); - if (message.ignorePacket != null && Object.hasOwnProperty.call(message, "ignorePacket")) - writer.uint32(/* id 14, wireType 0 =*/112).bool(message.ignorePacket); + if (message.ballSensorSeesBall != null && Object.hasOwnProperty.call(message, "ballSensorSeesBall")) + writer.uint32(/* id 2, wireType 0 =*/16).bool(message.ballSensorSeesBall); + if (message.ballSensorIsWorking != null && Object.hasOwnProperty.call(message, "ballSensorIsWorking")) + writer.uint32(/* id 4, wireType 0 =*/32).bool(message.ballSensorIsWorking); + if (message.dribblerSeesBall != null && Object.hasOwnProperty.call(message, "dribblerSeesBall")) + writer.uint32(/* id 5, wireType 0 =*/40).bool(message.dribblerSeesBall); + if (message.estimatedVelocityX != null && Object.hasOwnProperty.call(message, "estimatedVelocityX")) + writer.uint32(/* id 6, wireType 1 =*/49).double(message.estimatedVelocityX); + if (message.estimatedVelocityY != null && Object.hasOwnProperty.call(message, "estimatedVelocityY")) + writer.uint32(/* id 7, wireType 1 =*/57).double(message.estimatedVelocityY); + if (message.estimatedYaw != null && Object.hasOwnProperty.call(message, "estimatedYaw")) + writer.uint32(/* id 8, wireType 1 =*/65).double(message.estimatedYaw); + if (message.xsensIsCalibrated != null && Object.hasOwnProperty.call(message, "xsensIsCalibrated")) + writer.uint32(/* id 9, wireType 0 =*/72).bool(message.xsensIsCalibrated); + if (message.capacitorIsCharged != null && Object.hasOwnProperty.call(message, "capacitorIsCharged")) + writer.uint32(/* id 10, wireType 0 =*/80).bool(message.capacitorIsCharged); + if (message.batteryLevel != null && Object.hasOwnProperty.call(message, "batteryLevel")) + writer.uint32(/* id 13, wireType 5 =*/109).float(message.batteryLevel); return writer; }; /** - * Encodes the specified RobotCommand message, length delimited. Does not implicitly {@link proto.RobotCommand.verify|verify} messages. + * Encodes the specified RobotFeedback message, length delimited. Does not implicitly {@link proto.RobotFeedback.verify|verify} messages. * @function encodeDelimited - * @memberof proto.RobotCommand + * @memberof proto.RobotFeedback * @static - * @param {proto.IRobotCommand} message RobotCommand message or plain object to encode + * @param {proto.IRobotFeedback} message RobotFeedback message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ - RobotCommand.encodeDelimited = function encodeDelimited(message, writer) { + RobotFeedback.encodeDelimited = function encodeDelimited(message, writer) { return this.encode(message, writer).ldelim(); }; /** - * Decodes a RobotCommand message from the specified reader or buffer. + * Decodes a RobotFeedback message from the specified reader or buffer. * @function decode - * @memberof proto.RobotCommand + * @memberof proto.RobotFeedback * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from * @param {number} [length] Message length if known beforehand - * @returns {proto.RobotCommand} RobotCommand + * @returns {proto.RobotFeedback} RobotFeedback * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - RobotCommand.decode = function decode(reader, length) { + RobotFeedback.decode = function decode(reader, length) { if (!(reader instanceof $Reader)) reader = $Reader.create(reader); - let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.RobotCommand(); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.RobotFeedback(); while (reader.pos < end) { let tag = reader.uint32(); switch (tag >>> 3) { @@ -28644,55 +29094,39 @@ export const proto = $root.proto = (() => { break; } case 2: { - message.velocityX = reader.double(); - break; - } - case 3: { - message.velocityY = reader.double(); + message.ballSensorSeesBall = reader.bool(); break; } case 4: { - message.angle = reader.double(); + message.ballSensorIsWorking = reader.bool(); break; } case 5: { - message.angularVelocity = reader.double(); + message.dribblerSeesBall = reader.bool(); break; } case 6: { - message.useAngularVelocity = reader.bool(); + message.estimatedVelocityX = reader.double(); break; } case 7: { - message.cameraAngleOfRobot = reader.double(); + message.estimatedVelocityY = reader.double(); break; } case 8: { - message.cameraAngleOfRobotIsSet = reader.bool(); + message.estimatedYaw = reader.double(); break; } case 9: { - message.kickSpeed = reader.double(); + message.xsensIsCalibrated = reader.bool(); break; } case 10: { - message.waitForBall = reader.bool(); - break; - } - case 11: { - message.kickAtAngle = reader.bool(); - break; - } - case 12: { - message.kickType = reader.int32(); + message.capacitorIsCharged = reader.bool(); break; } case 13: { - message.dribblerSpeed = reader.double(); - break; - } - case 14: { - message.ignorePacket = reader.bool(); + message.batteryLevel = reader.float(); break; } default: @@ -28704,268 +29138,198 @@ export const proto = $root.proto = (() => { }; /** - * Decodes a RobotCommand message from the specified reader or buffer, length delimited. + * Decodes a RobotFeedback message from the specified reader or buffer, length delimited. * @function decodeDelimited - * @memberof proto.RobotCommand + * @memberof proto.RobotFeedback * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @returns {proto.RobotCommand} RobotCommand + * @returns {proto.RobotFeedback} RobotFeedback * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - RobotCommand.decodeDelimited = function decodeDelimited(reader) { + RobotFeedback.decodeDelimited = function decodeDelimited(reader) { if (!(reader instanceof $Reader)) reader = new $Reader(reader); return this.decode(reader, reader.uint32()); }; /** - * Verifies a RobotCommand message. + * Verifies a RobotFeedback message. * @function verify - * @memberof proto.RobotCommand + * @memberof proto.RobotFeedback * @static * @param {Object.} message Plain object to verify * @returns {string|null} `null` if valid, otherwise the reason why it is not */ - RobotCommand.verify = function verify(message) { + RobotFeedback.verify = function verify(message) { if (typeof message !== "object" || message === null) return "object expected"; if (message.id != null && message.hasOwnProperty("id")) if (!$util.isInteger(message.id)) return "id: integer expected"; - if (message.velocityX != null && message.hasOwnProperty("velocityX")) - if (typeof message.velocityX !== "number") - return "velocityX: number expected"; - if (message.velocityY != null && message.hasOwnProperty("velocityY")) - if (typeof message.velocityY !== "number") - return "velocityY: number expected"; - if (message.angle != null && message.hasOwnProperty("angle")) - if (typeof message.angle !== "number") - return "angle: number expected"; - if (message.angularVelocity != null && message.hasOwnProperty("angularVelocity")) - if (typeof message.angularVelocity !== "number") - return "angularVelocity: number expected"; - if (message.useAngularVelocity != null && message.hasOwnProperty("useAngularVelocity")) - if (typeof message.useAngularVelocity !== "boolean") - return "useAngularVelocity: boolean expected"; - if (message.cameraAngleOfRobot != null && message.hasOwnProperty("cameraAngleOfRobot")) - if (typeof message.cameraAngleOfRobot !== "number") - return "cameraAngleOfRobot: number expected"; - if (message.cameraAngleOfRobotIsSet != null && message.hasOwnProperty("cameraAngleOfRobotIsSet")) - if (typeof message.cameraAngleOfRobotIsSet !== "boolean") - return "cameraAngleOfRobotIsSet: boolean expected"; - if (message.kickSpeed != null && message.hasOwnProperty("kickSpeed")) - if (typeof message.kickSpeed !== "number") - return "kickSpeed: number expected"; - if (message.waitForBall != null && message.hasOwnProperty("waitForBall")) - if (typeof message.waitForBall !== "boolean") - return "waitForBall: boolean expected"; - if (message.kickAtAngle != null && message.hasOwnProperty("kickAtAngle")) - if (typeof message.kickAtAngle !== "boolean") - return "kickAtAngle: boolean expected"; - if (message.kickType != null && message.hasOwnProperty("kickType")) - switch (message.kickType) { - default: - return "kickType: enum value expected"; - case 0: - case 1: - case 2: - break; - } - if (message.dribblerSpeed != null && message.hasOwnProperty("dribblerSpeed")) - if (typeof message.dribblerSpeed !== "number") - return "dribblerSpeed: number expected"; - if (message.ignorePacket != null && message.hasOwnProperty("ignorePacket")) - if (typeof message.ignorePacket !== "boolean") - return "ignorePacket: boolean expected"; + if (message.ballSensorSeesBall != null && message.hasOwnProperty("ballSensorSeesBall")) + if (typeof message.ballSensorSeesBall !== "boolean") + return "ballSensorSeesBall: boolean expected"; + if (message.ballSensorIsWorking != null && message.hasOwnProperty("ballSensorIsWorking")) + if (typeof message.ballSensorIsWorking !== "boolean") + return "ballSensorIsWorking: boolean expected"; + if (message.dribblerSeesBall != null && message.hasOwnProperty("dribblerSeesBall")) + if (typeof message.dribblerSeesBall !== "boolean") + return "dribblerSeesBall: boolean expected"; + if (message.estimatedVelocityX != null && message.hasOwnProperty("estimatedVelocityX")) + if (typeof message.estimatedVelocityX !== "number") + return "estimatedVelocityX: number expected"; + if (message.estimatedVelocityY != null && message.hasOwnProperty("estimatedVelocityY")) + if (typeof message.estimatedVelocityY !== "number") + return "estimatedVelocityY: number expected"; + if (message.estimatedYaw != null && message.hasOwnProperty("estimatedYaw")) + if (typeof message.estimatedYaw !== "number") + return "estimatedYaw: number expected"; + if (message.xsensIsCalibrated != null && message.hasOwnProperty("xsensIsCalibrated")) + if (typeof message.xsensIsCalibrated !== "boolean") + return "xsensIsCalibrated: boolean expected"; + if (message.capacitorIsCharged != null && message.hasOwnProperty("capacitorIsCharged")) + if (typeof message.capacitorIsCharged !== "boolean") + return "capacitorIsCharged: boolean expected"; + if (message.batteryLevel != null && message.hasOwnProperty("batteryLevel")) + if (typeof message.batteryLevel !== "number") + return "batteryLevel: number expected"; return null; }; /** - * Creates a RobotCommand message from a plain object. Also converts values to their respective internal types. + * Creates a RobotFeedback message from a plain object. Also converts values to their respective internal types. * @function fromObject - * @memberof proto.RobotCommand + * @memberof proto.RobotFeedback * @static * @param {Object.} object Plain object - * @returns {proto.RobotCommand} RobotCommand + * @returns {proto.RobotFeedback} RobotFeedback */ - RobotCommand.fromObject = function fromObject(object) { - if (object instanceof $root.proto.RobotCommand) + RobotFeedback.fromObject = function fromObject(object) { + if (object instanceof $root.proto.RobotFeedback) return object; - let message = new $root.proto.RobotCommand(); + let message = new $root.proto.RobotFeedback(); if (object.id != null) message.id = object.id | 0; - if (object.velocityX != null) - message.velocityX = Number(object.velocityX); - if (object.velocityY != null) - message.velocityY = Number(object.velocityY); - if (object.angle != null) - message.angle = Number(object.angle); - if (object.angularVelocity != null) - message.angularVelocity = Number(object.angularVelocity); - if (object.useAngularVelocity != null) - message.useAngularVelocity = Boolean(object.useAngularVelocity); - if (object.cameraAngleOfRobot != null) - message.cameraAngleOfRobot = Number(object.cameraAngleOfRobot); - if (object.cameraAngleOfRobotIsSet != null) - message.cameraAngleOfRobotIsSet = Boolean(object.cameraAngleOfRobotIsSet); - if (object.kickSpeed != null) - message.kickSpeed = Number(object.kickSpeed); - if (object.waitForBall != null) - message.waitForBall = Boolean(object.waitForBall); - if (object.kickAtAngle != null) - message.kickAtAngle = Boolean(object.kickAtAngle); - switch (object.kickType) { - default: - if (typeof object.kickType === "number") { - message.kickType = object.kickType; - break; - } - break; - case "NO_KICK": - case 0: - message.kickType = 0; - break; - case "KICK": - case 1: - message.kickType = 1; - break; - case "CHIP": - case 2: - message.kickType = 2; - break; - } - if (object.dribblerSpeed != null) - message.dribblerSpeed = Number(object.dribblerSpeed); - if (object.ignorePacket != null) - message.ignorePacket = Boolean(object.ignorePacket); + if (object.ballSensorSeesBall != null) + message.ballSensorSeesBall = Boolean(object.ballSensorSeesBall); + if (object.ballSensorIsWorking != null) + message.ballSensorIsWorking = Boolean(object.ballSensorIsWorking); + if (object.dribblerSeesBall != null) + message.dribblerSeesBall = Boolean(object.dribblerSeesBall); + if (object.estimatedVelocityX != null) + message.estimatedVelocityX = Number(object.estimatedVelocityX); + if (object.estimatedVelocityY != null) + message.estimatedVelocityY = Number(object.estimatedVelocityY); + if (object.estimatedYaw != null) + message.estimatedYaw = Number(object.estimatedYaw); + if (object.xsensIsCalibrated != null) + message.xsensIsCalibrated = Boolean(object.xsensIsCalibrated); + if (object.capacitorIsCharged != null) + message.capacitorIsCharged = Boolean(object.capacitorIsCharged); + if (object.batteryLevel != null) + message.batteryLevel = Number(object.batteryLevel); return message; }; /** - * Creates a plain object from a RobotCommand message. Also converts values to other types if specified. + * Creates a plain object from a RobotFeedback message. Also converts values to other types if specified. * @function toObject - * @memberof proto.RobotCommand + * @memberof proto.RobotFeedback * @static - * @param {proto.RobotCommand} message RobotCommand + * @param {proto.RobotFeedback} message RobotFeedback * @param {$protobuf.IConversionOptions} [options] Conversion options * @returns {Object.} Plain object */ - RobotCommand.toObject = function toObject(message, options) { + RobotFeedback.toObject = function toObject(message, options) { if (!options) options = {}; let object = {}; if (options.defaults) { object.id = 0; - object.velocityX = 0; - object.velocityY = 0; - object.angle = 0; - object.angularVelocity = 0; - object.useAngularVelocity = false; - object.cameraAngleOfRobot = 0; - object.cameraAngleOfRobotIsSet = false; - object.kickSpeed = 0; - object.waitForBall = false; - object.kickAtAngle = false; - object.kickType = options.enums === String ? "NO_KICK" : 0; - object.dribblerSpeed = 0; - object.ignorePacket = false; + object.ballSensorSeesBall = false; + object.ballSensorIsWorking = false; + object.dribblerSeesBall = false; + object.estimatedVelocityX = 0; + object.estimatedVelocityY = 0; + object.estimatedYaw = 0; + object.xsensIsCalibrated = false; + object.capacitorIsCharged = false; + object.batteryLevel = 0; } if (message.id != null && message.hasOwnProperty("id")) object.id = message.id; - if (message.velocityX != null && message.hasOwnProperty("velocityX")) - object.velocityX = options.json && !isFinite(message.velocityX) ? String(message.velocityX) : message.velocityX; - if (message.velocityY != null && message.hasOwnProperty("velocityY")) - object.velocityY = options.json && !isFinite(message.velocityY) ? String(message.velocityY) : message.velocityY; - if (message.angle != null && message.hasOwnProperty("angle")) - object.angle = options.json && !isFinite(message.angle) ? String(message.angle) : message.angle; - if (message.angularVelocity != null && message.hasOwnProperty("angularVelocity")) - object.angularVelocity = options.json && !isFinite(message.angularVelocity) ? String(message.angularVelocity) : message.angularVelocity; - if (message.useAngularVelocity != null && message.hasOwnProperty("useAngularVelocity")) - object.useAngularVelocity = message.useAngularVelocity; - if (message.cameraAngleOfRobot != null && message.hasOwnProperty("cameraAngleOfRobot")) - object.cameraAngleOfRobot = options.json && !isFinite(message.cameraAngleOfRobot) ? String(message.cameraAngleOfRobot) : message.cameraAngleOfRobot; - if (message.cameraAngleOfRobotIsSet != null && message.hasOwnProperty("cameraAngleOfRobotIsSet")) - object.cameraAngleOfRobotIsSet = message.cameraAngleOfRobotIsSet; - if (message.kickSpeed != null && message.hasOwnProperty("kickSpeed")) - object.kickSpeed = options.json && !isFinite(message.kickSpeed) ? String(message.kickSpeed) : message.kickSpeed; - if (message.waitForBall != null && message.hasOwnProperty("waitForBall")) - object.waitForBall = message.waitForBall; - if (message.kickAtAngle != null && message.hasOwnProperty("kickAtAngle")) - object.kickAtAngle = message.kickAtAngle; - if (message.kickType != null && message.hasOwnProperty("kickType")) - object.kickType = options.enums === String ? $root.proto.RobotCommand.KickType[message.kickType] === undefined ? message.kickType : $root.proto.RobotCommand.KickType[message.kickType] : message.kickType; - if (message.dribblerSpeed != null && message.hasOwnProperty("dribblerSpeed")) - object.dribblerSpeed = options.json && !isFinite(message.dribblerSpeed) ? String(message.dribblerSpeed) : message.dribblerSpeed; - if (message.ignorePacket != null && message.hasOwnProperty("ignorePacket")) - object.ignorePacket = message.ignorePacket; + if (message.ballSensorSeesBall != null && message.hasOwnProperty("ballSensorSeesBall")) + object.ballSensorSeesBall = message.ballSensorSeesBall; + if (message.ballSensorIsWorking != null && message.hasOwnProperty("ballSensorIsWorking")) + object.ballSensorIsWorking = message.ballSensorIsWorking; + if (message.dribblerSeesBall != null && message.hasOwnProperty("dribblerSeesBall")) + object.dribblerSeesBall = message.dribblerSeesBall; + if (message.estimatedVelocityX != null && message.hasOwnProperty("estimatedVelocityX")) + object.estimatedVelocityX = options.json && !isFinite(message.estimatedVelocityX) ? String(message.estimatedVelocityX) : message.estimatedVelocityX; + if (message.estimatedVelocityY != null && message.hasOwnProperty("estimatedVelocityY")) + object.estimatedVelocityY = options.json && !isFinite(message.estimatedVelocityY) ? String(message.estimatedVelocityY) : message.estimatedVelocityY; + if (message.estimatedYaw != null && message.hasOwnProperty("estimatedYaw")) + object.estimatedYaw = options.json && !isFinite(message.estimatedYaw) ? String(message.estimatedYaw) : message.estimatedYaw; + if (message.xsensIsCalibrated != null && message.hasOwnProperty("xsensIsCalibrated")) + object.xsensIsCalibrated = message.xsensIsCalibrated; + if (message.capacitorIsCharged != null && message.hasOwnProperty("capacitorIsCharged")) + object.capacitorIsCharged = message.capacitorIsCharged; + if (message.batteryLevel != null && message.hasOwnProperty("batteryLevel")) + object.batteryLevel = options.json && !isFinite(message.batteryLevel) ? String(message.batteryLevel) : message.batteryLevel; return object; }; /** - * Converts this RobotCommand to JSON. + * Converts this RobotFeedback to JSON. * @function toJSON - * @memberof proto.RobotCommand + * @memberof proto.RobotFeedback * @instance * @returns {Object.} JSON object */ - RobotCommand.prototype.toJSON = function toJSON() { + RobotFeedback.prototype.toJSON = function toJSON() { return this.constructor.toObject(this, $protobuf.util.toJSONOptions); }; /** - * Gets the default type url for RobotCommand + * Gets the default type url for RobotFeedback * @function getTypeUrl - * @memberof proto.RobotCommand + * @memberof proto.RobotFeedback * @static * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns {string} The default type url */ - RobotCommand.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + RobotFeedback.getTypeUrl = function getTypeUrl(typeUrlPrefix) { if (typeUrlPrefix === undefined) { typeUrlPrefix = "type.googleapis.com"; } - return typeUrlPrefix + "/proto.RobotCommand"; + return typeUrlPrefix + "/proto.RobotFeedback"; }; - /** - * KickType enum. - * @name proto.RobotCommand.KickType - * @enum {number} - * @property {number} NO_KICK=0 NO_KICK value - * @property {number} KICK=1 KICK value - * @property {number} CHIP=2 CHIP value - */ - RobotCommand.KickType = (function() { - const valuesById = {}, values = Object.create(valuesById); - values[valuesById[0] = "NO_KICK"] = 0; - values[valuesById[1] = "KICK"] = 1; - values[valuesById[2] = "CHIP"] = 2; - return values; - })(); - - return RobotCommand; + return RobotFeedback; })(); - proto.RobotCommands = (function() { + proto.RobotsFeedback = (function() { /** - * Properties of a RobotCommands. + * Properties of a RobotsFeedback. * @memberof proto - * @interface IRobotCommands - * @property {Array.|null} [robotCommands] RobotCommands robotCommands + * @interface IRobotsFeedback + * @property {proto.RobotTeam|null} [team] RobotsFeedback team + * @property {proto.RobotFeedbackSource|null} [source] RobotsFeedback source + * @property {Array.|null} [robotsFeedback] RobotsFeedback robotsFeedback */ /** - * Constructs a new RobotCommands. + * Constructs a new RobotsFeedback. * @memberof proto - * @classdesc Represents a RobotCommands. - * @implements IRobotCommands + * @classdesc Represents a RobotsFeedback. + * @implements IRobotsFeedback * @constructor - * @param {proto.IRobotCommands=} [properties] Properties to set + * @param {proto.IRobotsFeedback=} [properties] Properties to set */ - function RobotCommands(properties) { - this.robotCommands = []; + function RobotsFeedback(properties) { + this.robotsFeedback = []; if (properties) for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) if (properties[keys[i]] != null) @@ -28973,78 +29337,106 @@ export const proto = $root.proto = (() => { } /** - * RobotCommands robotCommands. - * @member {Array.} robotCommands - * @memberof proto.RobotCommands + * RobotsFeedback team. + * @member {proto.RobotTeam} team + * @memberof proto.RobotsFeedback * @instance */ - RobotCommands.prototype.robotCommands = $util.emptyArray; + RobotsFeedback.prototype.team = 0; /** - * Creates a new RobotCommands instance using the specified properties. + * RobotsFeedback source. + * @member {proto.RobotFeedbackSource} source + * @memberof proto.RobotsFeedback + * @instance + */ + RobotsFeedback.prototype.source = 0; + + /** + * RobotsFeedback robotsFeedback. + * @member {Array.} robotsFeedback + * @memberof proto.RobotsFeedback + * @instance + */ + RobotsFeedback.prototype.robotsFeedback = $util.emptyArray; + + /** + * Creates a new RobotsFeedback instance using the specified properties. * @function create - * @memberof proto.RobotCommands + * @memberof proto.RobotsFeedback * @static - * @param {proto.IRobotCommands=} [properties] Properties to set - * @returns {proto.RobotCommands} RobotCommands instance + * @param {proto.IRobotsFeedback=} [properties] Properties to set + * @returns {proto.RobotsFeedback} RobotsFeedback instance */ - RobotCommands.create = function create(properties) { - return new RobotCommands(properties); + RobotsFeedback.create = function create(properties) { + return new RobotsFeedback(properties); }; /** - * Encodes the specified RobotCommands message. Does not implicitly {@link proto.RobotCommands.verify|verify} messages. + * Encodes the specified RobotsFeedback message. Does not implicitly {@link proto.RobotsFeedback.verify|verify} messages. * @function encode - * @memberof proto.RobotCommands + * @memberof proto.RobotsFeedback * @static - * @param {proto.IRobotCommands} message RobotCommands message or plain object to encode + * @param {proto.IRobotsFeedback} message RobotsFeedback message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ - RobotCommands.encode = function encode(message, writer) { + RobotsFeedback.encode = function encode(message, writer) { if (!writer) writer = $Writer.create(); - if (message.robotCommands != null && message.robotCommands.length) - for (let i = 0; i < message.robotCommands.length; ++i) - $root.proto.RobotCommand.encode(message.robotCommands[i], writer.uint32(/* id 1, wireType 2 =*/10).fork()).ldelim(); + if (message.team != null && Object.hasOwnProperty.call(message, "team")) + writer.uint32(/* id 1, wireType 0 =*/8).int32(message.team); + if (message.source != null && Object.hasOwnProperty.call(message, "source")) + writer.uint32(/* id 2, wireType 0 =*/16).int32(message.source); + if (message.robotsFeedback != null && message.robotsFeedback.length) + for (let i = 0; i < message.robotsFeedback.length; ++i) + $root.proto.RobotFeedback.encode(message.robotsFeedback[i], writer.uint32(/* id 3, wireType 2 =*/26).fork()).ldelim(); return writer; }; /** - * Encodes the specified RobotCommands message, length delimited. Does not implicitly {@link proto.RobotCommands.verify|verify} messages. + * Encodes the specified RobotsFeedback message, length delimited. Does not implicitly {@link proto.RobotsFeedback.verify|verify} messages. * @function encodeDelimited - * @memberof proto.RobotCommands + * @memberof proto.RobotsFeedback * @static - * @param {proto.IRobotCommands} message RobotCommands message or plain object to encode + * @param {proto.IRobotsFeedback} message RobotsFeedback message or plain object to encode * @param {$protobuf.Writer} [writer] Writer to encode to * @returns {$protobuf.Writer} Writer */ - RobotCommands.encodeDelimited = function encodeDelimited(message, writer) { + RobotsFeedback.encodeDelimited = function encodeDelimited(message, writer) { return this.encode(message, writer).ldelim(); }; /** - * Decodes a RobotCommands message from the specified reader or buffer. + * Decodes a RobotsFeedback message from the specified reader or buffer. * @function decode - * @memberof proto.RobotCommands + * @memberof proto.RobotsFeedback * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from * @param {number} [length] Message length if known beforehand - * @returns {proto.RobotCommands} RobotCommands + * @returns {proto.RobotsFeedback} RobotsFeedback * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - RobotCommands.decode = function decode(reader, length) { + RobotsFeedback.decode = function decode(reader, length) { if (!(reader instanceof $Reader)) reader = $Reader.create(reader); - let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.RobotCommands(); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.RobotsFeedback(); while (reader.pos < end) { let tag = reader.uint32(); switch (tag >>> 3) { case 1: { - if (!(message.robotCommands && message.robotCommands.length)) - message.robotCommands = []; - message.robotCommands.push($root.proto.RobotCommand.decode(reader, reader.uint32())); + message.team = reader.int32(); + break; + } + case 2: { + message.source = reader.int32(); + break; + } + case 3: { + if (!(message.robotsFeedback && message.robotsFeedback.length)) + message.robotsFeedback = []; + message.robotsFeedback.push($root.proto.RobotFeedback.decode(reader, reader.uint32())); break; } default: @@ -29056,119 +29448,175 @@ export const proto = $root.proto = (() => { }; /** - * Decodes a RobotCommands message from the specified reader or buffer, length delimited. + * Decodes a RobotsFeedback message from the specified reader or buffer, length delimited. * @function decodeDelimited - * @memberof proto.RobotCommands + * @memberof proto.RobotsFeedback * @static * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @returns {proto.RobotCommands} RobotCommands + * @returns {proto.RobotsFeedback} RobotsFeedback * @throws {Error} If the payload is not a reader or valid buffer * @throws {$protobuf.util.ProtocolError} If required fields are missing */ - RobotCommands.decodeDelimited = function decodeDelimited(reader) { + RobotsFeedback.decodeDelimited = function decodeDelimited(reader) { if (!(reader instanceof $Reader)) reader = new $Reader(reader); return this.decode(reader, reader.uint32()); }; /** - * Verifies a RobotCommands message. + * Verifies a RobotsFeedback message. * @function verify - * @memberof proto.RobotCommands + * @memberof proto.RobotsFeedback * @static * @param {Object.} message Plain object to verify * @returns {string|null} `null` if valid, otherwise the reason why it is not */ - RobotCommands.verify = function verify(message) { + RobotsFeedback.verify = function verify(message) { if (typeof message !== "object" || message === null) return "object expected"; - if (message.robotCommands != null && message.hasOwnProperty("robotCommands")) { - if (!Array.isArray(message.robotCommands)) - return "robotCommands: array expected"; - for (let i = 0; i < message.robotCommands.length; ++i) { - let error = $root.proto.RobotCommand.verify(message.robotCommands[i]); + if (message.team != null && message.hasOwnProperty("team")) + switch (message.team) { + default: + return "team: enum value expected"; + case 0: + case 1: + break; + } + if (message.source != null && message.hasOwnProperty("source")) + switch (message.source) { + default: + return "source: enum value expected"; + case 0: + case 1: + break; + } + if (message.robotsFeedback != null && message.hasOwnProperty("robotsFeedback")) { + if (!Array.isArray(message.robotsFeedback)) + return "robotsFeedback: array expected"; + for (let i = 0; i < message.robotsFeedback.length; ++i) { + let error = $root.proto.RobotFeedback.verify(message.robotsFeedback[i]); if (error) - return "robotCommands." + error; + return "robotsFeedback." + error; } } return null; }; /** - * Creates a RobotCommands message from a plain object. Also converts values to their respective internal types. + * Creates a RobotsFeedback message from a plain object. Also converts values to their respective internal types. * @function fromObject - * @memberof proto.RobotCommands + * @memberof proto.RobotsFeedback * @static * @param {Object.} object Plain object - * @returns {proto.RobotCommands} RobotCommands + * @returns {proto.RobotsFeedback} RobotsFeedback */ - RobotCommands.fromObject = function fromObject(object) { - if (object instanceof $root.proto.RobotCommands) + RobotsFeedback.fromObject = function fromObject(object) { + if (object instanceof $root.proto.RobotsFeedback) return object; - let message = new $root.proto.RobotCommands(); - if (object.robotCommands) { - if (!Array.isArray(object.robotCommands)) - throw TypeError(".proto.RobotCommands.robotCommands: array expected"); - message.robotCommands = []; - for (let i = 0; i < object.robotCommands.length; ++i) { - if (typeof object.robotCommands[i] !== "object") - throw TypeError(".proto.RobotCommands.robotCommands: object expected"); - message.robotCommands[i] = $root.proto.RobotCommand.fromObject(object.robotCommands[i]); + let message = new $root.proto.RobotsFeedback(); + switch (object.team) { + default: + if (typeof object.team === "number") { + message.team = object.team; + break; + } + break; + case "YELLOW_TEAM": + case 0: + message.team = 0; + break; + case "BLUE_TEAM": + case 1: + message.team = 1; + break; + } + switch (object.source) { + default: + if (typeof object.source === "number") { + message.source = object.source; + break; + } + break; + case "SIMULATOR": + case 0: + message.source = 0; + break; + case "BASESTATION": + case 1: + message.source = 1; + break; + } + if (object.robotsFeedback) { + if (!Array.isArray(object.robotsFeedback)) + throw TypeError(".proto.RobotsFeedback.robotsFeedback: array expected"); + message.robotsFeedback = []; + for (let i = 0; i < object.robotsFeedback.length; ++i) { + if (typeof object.robotsFeedback[i] !== "object") + throw TypeError(".proto.RobotsFeedback.robotsFeedback: object expected"); + message.robotsFeedback[i] = $root.proto.RobotFeedback.fromObject(object.robotsFeedback[i]); } } return message; }; /** - * Creates a plain object from a RobotCommands message. Also converts values to other types if specified. + * Creates a plain object from a RobotsFeedback message. Also converts values to other types if specified. * @function toObject - * @memberof proto.RobotCommands + * @memberof proto.RobotsFeedback * @static - * @param {proto.RobotCommands} message RobotCommands + * @param {proto.RobotsFeedback} message RobotsFeedback * @param {$protobuf.IConversionOptions} [options] Conversion options * @returns {Object.} Plain object */ - RobotCommands.toObject = function toObject(message, options) { + RobotsFeedback.toObject = function toObject(message, options) { if (!options) options = {}; let object = {}; if (options.arrays || options.defaults) - object.robotCommands = []; - if (message.robotCommands && message.robotCommands.length) { - object.robotCommands = []; - for (let j = 0; j < message.robotCommands.length; ++j) - object.robotCommands[j] = $root.proto.RobotCommand.toObject(message.robotCommands[j], options); + object.robotsFeedback = []; + if (options.defaults) { + object.team = options.enums === String ? "YELLOW_TEAM" : 0; + object.source = options.enums === String ? "SIMULATOR" : 0; + } + if (message.team != null && message.hasOwnProperty("team")) + object.team = options.enums === String ? $root.proto.RobotTeam[message.team] === undefined ? message.team : $root.proto.RobotTeam[message.team] : message.team; + if (message.source != null && message.hasOwnProperty("source")) + object.source = options.enums === String ? $root.proto.RobotFeedbackSource[message.source] === undefined ? message.source : $root.proto.RobotFeedbackSource[message.source] : message.source; + if (message.robotsFeedback && message.robotsFeedback.length) { + object.robotsFeedback = []; + for (let j = 0; j < message.robotsFeedback.length; ++j) + object.robotsFeedback[j] = $root.proto.RobotFeedback.toObject(message.robotsFeedback[j], options); } return object; }; /** - * Converts this RobotCommands to JSON. + * Converts this RobotsFeedback to JSON. * @function toJSON - * @memberof proto.RobotCommands + * @memberof proto.RobotsFeedback * @instance * @returns {Object.} JSON object */ - RobotCommands.prototype.toJSON = function toJSON() { + RobotsFeedback.prototype.toJSON = function toJSON() { return this.constructor.toObject(this, $protobuf.util.toJSONOptions); }; /** - * Gets the default type url for RobotCommands + * Gets the default type url for RobotsFeedback * @function getTypeUrl - * @memberof proto.RobotCommands + * @memberof proto.RobotsFeedback * @static * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns {string} The default type url */ - RobotCommands.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + RobotsFeedback.getTypeUrl = function getTypeUrl(typeUrlPrefix) { if (typeUrlPrefix === undefined) { typeUrlPrefix = "type.googleapis.com"; } - return typeUrlPrefix + "/proto.RobotCommands"; + return typeUrlPrefix + "/proto.RobotsFeedback"; }; - return RobotCommands; + return RobotsFeedback; })(); proto.RoboCup2014Legacy = (function() { @@ -29848,357 +30296,1124 @@ export const proto = $root.proto = (() => { if (error) return "field." + error; } - if (message.calib != null && message.hasOwnProperty("calib")) { - if (!Array.isArray(message.calib)) - return "calib: array expected"; - for (let i = 0; i < message.calib.length; ++i) { - let error = $root.proto.SSL_GeometryCameraCalibration.verify(message.calib[i]); - if (error) - return "calib." + error; - } + if (message.calib != null && message.hasOwnProperty("calib")) { + if (!Array.isArray(message.calib)) + return "calib: array expected"; + for (let i = 0; i < message.calib.length; ++i) { + let error = $root.proto.SSL_GeometryCameraCalibration.verify(message.calib[i]); + if (error) + return "calib." + error; + } + } + return null; + }; + + /** + * Creates a SSL_GeometryData message from a plain object. Also converts values to their respective internal types. + * @function fromObject + * @memberof proto.RoboCup2014Legacy.Geometry.SSL_GeometryData + * @static + * @param {Object.} object Plain object + * @returns {proto.RoboCup2014Legacy.Geometry.SSL_GeometryData} SSL_GeometryData + */ + SSL_GeometryData.fromObject = function fromObject(object) { + if (object instanceof $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryData) + return object; + let message = new $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryData(); + if (object.field != null) { + if (typeof object.field !== "object") + throw TypeError(".proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.field: object expected"); + message.field = $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryFieldSize.fromObject(object.field); + } + if (object.calib) { + if (!Array.isArray(object.calib)) + throw TypeError(".proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.calib: array expected"); + message.calib = []; + for (let i = 0; i < object.calib.length; ++i) { + if (typeof object.calib[i] !== "object") + throw TypeError(".proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.calib: object expected"); + message.calib[i] = $root.proto.SSL_GeometryCameraCalibration.fromObject(object.calib[i]); + } + } + return message; + }; + + /** + * Creates a plain object from a SSL_GeometryData message. Also converts values to other types if specified. + * @function toObject + * @memberof proto.RoboCup2014Legacy.Geometry.SSL_GeometryData + * @static + * @param {proto.RoboCup2014Legacy.Geometry.SSL_GeometryData} message SSL_GeometryData + * @param {$protobuf.IConversionOptions} [options] Conversion options + * @returns {Object.} Plain object + */ + SSL_GeometryData.toObject = function toObject(message, options) { + if (!options) + options = {}; + let object = {}; + if (options.arrays || options.defaults) + object.calib = []; + if (options.defaults) + object.field = null; + if (message.field != null && message.hasOwnProperty("field")) + object.field = $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryFieldSize.toObject(message.field, options); + if (message.calib && message.calib.length) { + object.calib = []; + for (let j = 0; j < message.calib.length; ++j) + object.calib[j] = $root.proto.SSL_GeometryCameraCalibration.toObject(message.calib[j], options); + } + return object; + }; + + /** + * Converts this SSL_GeometryData to JSON. + * @function toJSON + * @memberof proto.RoboCup2014Legacy.Geometry.SSL_GeometryData + * @instance + * @returns {Object.} JSON object + */ + SSL_GeometryData.prototype.toJSON = function toJSON() { + return this.constructor.toObject(this, $protobuf.util.toJSONOptions); + }; + + /** + * Gets the default type url for SSL_GeometryData + * @function getTypeUrl + * @memberof proto.RoboCup2014Legacy.Geometry.SSL_GeometryData + * @static + * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns {string} The default type url + */ + SSL_GeometryData.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + if (typeUrlPrefix === undefined) { + typeUrlPrefix = "type.googleapis.com"; + } + return typeUrlPrefix + "/proto.RoboCup2014Legacy.Geometry.SSL_GeometryData"; + }; + + return SSL_GeometryData; + })(); + + return Geometry; + })(); + + RoboCup2014Legacy.Wrapper = (function() { + + /** + * Namespace Wrapper. + * @memberof proto.RoboCup2014Legacy + * @namespace + */ + const Wrapper = {}; + + Wrapper.SSL_WrapperPacket = (function() { + + /** + * Properties of a SSL_WrapperPacket. + * @memberof proto.RoboCup2014Legacy.Wrapper + * @interface ISSL_WrapperPacket + * @property {proto.ISSL_DetectionFrame|null} [detection] SSL_WrapperPacket detection + * @property {proto.RoboCup2014Legacy.Geometry.ISSL_GeometryData|null} [geometry] SSL_WrapperPacket geometry + */ + + /** + * Constructs a new SSL_WrapperPacket. + * @memberof proto.RoboCup2014Legacy.Wrapper + * @classdesc Represents a SSL_WrapperPacket. + * @implements ISSL_WrapperPacket + * @constructor + * @param {proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket=} [properties] Properties to set + */ + function SSL_WrapperPacket(properties) { + if (properties) + for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) + if (properties[keys[i]] != null) + this[keys[i]] = properties[keys[i]]; + } + + /** + * SSL_WrapperPacket detection. + * @member {proto.ISSL_DetectionFrame|null|undefined} detection + * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket + * @instance + */ + SSL_WrapperPacket.prototype.detection = null; + + /** + * SSL_WrapperPacket geometry. + * @member {proto.RoboCup2014Legacy.Geometry.ISSL_GeometryData|null|undefined} geometry + * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket + * @instance + */ + SSL_WrapperPacket.prototype.geometry = null; + + /** + * Creates a new SSL_WrapperPacket instance using the specified properties. + * @function create + * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket + * @static + * @param {proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket=} [properties] Properties to set + * @returns {proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket} SSL_WrapperPacket instance + */ + SSL_WrapperPacket.create = function create(properties) { + return new SSL_WrapperPacket(properties); + }; + + /** + * Encodes the specified SSL_WrapperPacket message. Does not implicitly {@link proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket.verify|verify} messages. + * @function encode + * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket + * @static + * @param {proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket} message SSL_WrapperPacket message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + SSL_WrapperPacket.encode = function encode(message, writer) { + if (!writer) + writer = $Writer.create(); + if (message.detection != null && Object.hasOwnProperty.call(message, "detection")) + $root.proto.SSL_DetectionFrame.encode(message.detection, writer.uint32(/* id 1, wireType 2 =*/10).fork()).ldelim(); + if (message.geometry != null && Object.hasOwnProperty.call(message, "geometry")) + $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.encode(message.geometry, writer.uint32(/* id 2, wireType 2 =*/18).fork()).ldelim(); + return writer; + }; + + /** + * Encodes the specified SSL_WrapperPacket message, length delimited. Does not implicitly {@link proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket.verify|verify} messages. + * @function encodeDelimited + * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket + * @static + * @param {proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket} message SSL_WrapperPacket message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + SSL_WrapperPacket.encodeDelimited = function encodeDelimited(message, writer) { + return this.encode(message, writer).ldelim(); + }; + + /** + * Decodes a SSL_WrapperPacket message from the specified reader or buffer. + * @function decode + * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @param {number} [length] Message length if known beforehand + * @returns {proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket} SSL_WrapperPacket + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + SSL_WrapperPacket.decode = function decode(reader, length) { + if (!(reader instanceof $Reader)) + reader = $Reader.create(reader); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket(); + while (reader.pos < end) { + let tag = reader.uint32(); + switch (tag >>> 3) { + case 1: { + message.detection = $root.proto.SSL_DetectionFrame.decode(reader, reader.uint32()); + break; + } + case 2: { + message.geometry = $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.decode(reader, reader.uint32()); + break; + } + default: + reader.skipType(tag & 7); + break; + } + } + return message; + }; + + /** + * Decodes a SSL_WrapperPacket message from the specified reader or buffer, length delimited. + * @function decodeDelimited + * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @returns {proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket} SSL_WrapperPacket + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + SSL_WrapperPacket.decodeDelimited = function decodeDelimited(reader) { + if (!(reader instanceof $Reader)) + reader = new $Reader(reader); + return this.decode(reader, reader.uint32()); + }; + + /** + * Verifies a SSL_WrapperPacket message. + * @function verify + * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket + * @static + * @param {Object.} message Plain object to verify + * @returns {string|null} `null` if valid, otherwise the reason why it is not + */ + SSL_WrapperPacket.verify = function verify(message) { + if (typeof message !== "object" || message === null) + return "object expected"; + if (message.detection != null && message.hasOwnProperty("detection")) { + let error = $root.proto.SSL_DetectionFrame.verify(message.detection); + if (error) + return "detection." + error; + } + if (message.geometry != null && message.hasOwnProperty("geometry")) { + let error = $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.verify(message.geometry); + if (error) + return "geometry." + error; } return null; }; /** - * Creates a SSL_GeometryData message from a plain object. Also converts values to their respective internal types. + * Creates a SSL_WrapperPacket message from a plain object. Also converts values to their respective internal types. * @function fromObject - * @memberof proto.RoboCup2014Legacy.Geometry.SSL_GeometryData + * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket * @static * @param {Object.} object Plain object - * @returns {proto.RoboCup2014Legacy.Geometry.SSL_GeometryData} SSL_GeometryData + * @returns {proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket} SSL_WrapperPacket */ - SSL_GeometryData.fromObject = function fromObject(object) { - if (object instanceof $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryData) + SSL_WrapperPacket.fromObject = function fromObject(object) { + if (object instanceof $root.proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket) return object; - let message = new $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryData(); - if (object.field != null) { - if (typeof object.field !== "object") - throw TypeError(".proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.field: object expected"); - message.field = $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryFieldSize.fromObject(object.field); + let message = new $root.proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket(); + if (object.detection != null) { + if (typeof object.detection !== "object") + throw TypeError(".proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket.detection: object expected"); + message.detection = $root.proto.SSL_DetectionFrame.fromObject(object.detection); } - if (object.calib) { - if (!Array.isArray(object.calib)) - throw TypeError(".proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.calib: array expected"); - message.calib = []; - for (let i = 0; i < object.calib.length; ++i) { - if (typeof object.calib[i] !== "object") - throw TypeError(".proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.calib: object expected"); - message.calib[i] = $root.proto.SSL_GeometryCameraCalibration.fromObject(object.calib[i]); - } + if (object.geometry != null) { + if (typeof object.geometry !== "object") + throw TypeError(".proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket.geometry: object expected"); + message.geometry = $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.fromObject(object.geometry); } return message; }; /** - * Creates a plain object from a SSL_GeometryData message. Also converts values to other types if specified. + * Creates a plain object from a SSL_WrapperPacket message. Also converts values to other types if specified. * @function toObject - * @memberof proto.RoboCup2014Legacy.Geometry.SSL_GeometryData + * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket * @static - * @param {proto.RoboCup2014Legacy.Geometry.SSL_GeometryData} message SSL_GeometryData + * @param {proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket} message SSL_WrapperPacket * @param {$protobuf.IConversionOptions} [options] Conversion options * @returns {Object.} Plain object */ - SSL_GeometryData.toObject = function toObject(message, options) { + SSL_WrapperPacket.toObject = function toObject(message, options) { if (!options) options = {}; let object = {}; - if (options.arrays || options.defaults) - object.calib = []; - if (options.defaults) - object.field = null; - if (message.field != null && message.hasOwnProperty("field")) - object.field = $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryFieldSize.toObject(message.field, options); - if (message.calib && message.calib.length) { - object.calib = []; - for (let j = 0; j < message.calib.length; ++j) - object.calib[j] = $root.proto.SSL_GeometryCameraCalibration.toObject(message.calib[j], options); + if (options.defaults) { + object.detection = null; + object.geometry = null; } + if (message.detection != null && message.hasOwnProperty("detection")) + object.detection = $root.proto.SSL_DetectionFrame.toObject(message.detection, options); + if (message.geometry != null && message.hasOwnProperty("geometry")) + object.geometry = $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.toObject(message.geometry, options); return object; }; /** - * Converts this SSL_GeometryData to JSON. + * Converts this SSL_WrapperPacket to JSON. * @function toJSON - * @memberof proto.RoboCup2014Legacy.Geometry.SSL_GeometryData + * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket * @instance * @returns {Object.} JSON object */ - SSL_GeometryData.prototype.toJSON = function toJSON() { + SSL_WrapperPacket.prototype.toJSON = function toJSON() { return this.constructor.toObject(this, $protobuf.util.toJSONOptions); }; /** - * Gets the default type url for SSL_GeometryData + * Gets the default type url for SSL_WrapperPacket * @function getTypeUrl - * @memberof proto.RoboCup2014Legacy.Geometry.SSL_GeometryData + * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket * @static * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") * @returns {string} The default type url */ - SSL_GeometryData.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + SSL_WrapperPacket.getTypeUrl = function getTypeUrl(typeUrlPrefix) { if (typeUrlPrefix === undefined) { typeUrlPrefix = "type.googleapis.com"; } - return typeUrlPrefix + "/proto.RoboCup2014Legacy.Geometry.SSL_GeometryData"; + return typeUrlPrefix + "/proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket"; }; - return SSL_GeometryData; + return SSL_WrapperPacket; })(); - return Geometry; + return Wrapper; })(); - RoboCup2014Legacy.Wrapper = (function() { + return RoboCup2014Legacy; + })(); - /** - * Namespace Wrapper. - * @memberof proto.RoboCup2014Legacy - * @namespace - */ - const Wrapper = {}; + proto.RobotCommand = (function() { + + /** + * Properties of a RobotCommand. + * @memberof proto + * @interface IRobotCommand + * @property {number|null} [id] RobotCommand id + * @property {number|null} [velocityX] RobotCommand velocityX + * @property {number|null} [velocityY] RobotCommand velocityY + * @property {number|null} [yaw] RobotCommand yaw + * @property {number|null} [angularVelocity] RobotCommand angularVelocity + * @property {boolean|null} [useAngularVelocity] RobotCommand useAngularVelocity + * @property {number|null} [cameraYawOfRobot] RobotCommand cameraYawOfRobot + * @property {boolean|null} [cameraYawOfRobotIsSet] RobotCommand cameraYawOfRobotIsSet + * @property {number|null} [kickSpeed] RobotCommand kickSpeed + * @property {boolean|null} [waitForBall] RobotCommand waitForBall + * @property {boolean|null} [kickAtYaw] RobotCommand kickAtYaw + * @property {proto.RobotCommand.KickType|null} [kickType] RobotCommand kickType + * @property {boolean|null} [dribblerOn] RobotCommand dribblerOn + * @property {boolean|null} [wheelsOff] RobotCommand wheelsOff + */ + + /** + * Constructs a new RobotCommand. + * @memberof proto + * @classdesc Represents a RobotCommand. + * @implements IRobotCommand + * @constructor + * @param {proto.IRobotCommand=} [properties] Properties to set + */ + function RobotCommand(properties) { + if (properties) + for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) + if (properties[keys[i]] != null) + this[keys[i]] = properties[keys[i]]; + } + + /** + * RobotCommand id. + * @member {number} id + * @memberof proto.RobotCommand + * @instance + */ + RobotCommand.prototype.id = 0; + + /** + * RobotCommand velocityX. + * @member {number} velocityX + * @memberof proto.RobotCommand + * @instance + */ + RobotCommand.prototype.velocityX = 0; + + /** + * RobotCommand velocityY. + * @member {number} velocityY + * @memberof proto.RobotCommand + * @instance + */ + RobotCommand.prototype.velocityY = 0; + + /** + * RobotCommand yaw. + * @member {number} yaw + * @memberof proto.RobotCommand + * @instance + */ + RobotCommand.prototype.yaw = 0; + + /** + * RobotCommand angularVelocity. + * @member {number} angularVelocity + * @memberof proto.RobotCommand + * @instance + */ + RobotCommand.prototype.angularVelocity = 0; + + /** + * RobotCommand useAngularVelocity. + * @member {boolean} useAngularVelocity + * @memberof proto.RobotCommand + * @instance + */ + RobotCommand.prototype.useAngularVelocity = false; + + /** + * RobotCommand cameraYawOfRobot. + * @member {number} cameraYawOfRobot + * @memberof proto.RobotCommand + * @instance + */ + RobotCommand.prototype.cameraYawOfRobot = 0; + + /** + * RobotCommand cameraYawOfRobotIsSet. + * @member {boolean} cameraYawOfRobotIsSet + * @memberof proto.RobotCommand + * @instance + */ + RobotCommand.prototype.cameraYawOfRobotIsSet = false; + + /** + * RobotCommand kickSpeed. + * @member {number} kickSpeed + * @memberof proto.RobotCommand + * @instance + */ + RobotCommand.prototype.kickSpeed = 0; + + /** + * RobotCommand waitForBall. + * @member {boolean} waitForBall + * @memberof proto.RobotCommand + * @instance + */ + RobotCommand.prototype.waitForBall = false; + + /** + * RobotCommand kickAtYaw. + * @member {boolean} kickAtYaw + * @memberof proto.RobotCommand + * @instance + */ + RobotCommand.prototype.kickAtYaw = false; + + /** + * RobotCommand kickType. + * @member {proto.RobotCommand.KickType} kickType + * @memberof proto.RobotCommand + * @instance + */ + RobotCommand.prototype.kickType = 0; + + /** + * RobotCommand dribblerOn. + * @member {boolean} dribblerOn + * @memberof proto.RobotCommand + * @instance + */ + RobotCommand.prototype.dribblerOn = false; + + /** + * RobotCommand wheelsOff. + * @member {boolean} wheelsOff + * @memberof proto.RobotCommand + * @instance + */ + RobotCommand.prototype.wheelsOff = false; + + /** + * Creates a new RobotCommand instance using the specified properties. + * @function create + * @memberof proto.RobotCommand + * @static + * @param {proto.IRobotCommand=} [properties] Properties to set + * @returns {proto.RobotCommand} RobotCommand instance + */ + RobotCommand.create = function create(properties) { + return new RobotCommand(properties); + }; + + /** + * Encodes the specified RobotCommand message. Does not implicitly {@link proto.RobotCommand.verify|verify} messages. + * @function encode + * @memberof proto.RobotCommand + * @static + * @param {proto.IRobotCommand} message RobotCommand message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + RobotCommand.encode = function encode(message, writer) { + if (!writer) + writer = $Writer.create(); + if (message.id != null && Object.hasOwnProperty.call(message, "id")) + writer.uint32(/* id 1, wireType 0 =*/8).int32(message.id); + if (message.velocityX != null && Object.hasOwnProperty.call(message, "velocityX")) + writer.uint32(/* id 2, wireType 1 =*/17).double(message.velocityX); + if (message.velocityY != null && Object.hasOwnProperty.call(message, "velocityY")) + writer.uint32(/* id 3, wireType 1 =*/25).double(message.velocityY); + if (message.yaw != null && Object.hasOwnProperty.call(message, "yaw")) + writer.uint32(/* id 4, wireType 1 =*/33).double(message.yaw); + if (message.angularVelocity != null && Object.hasOwnProperty.call(message, "angularVelocity")) + writer.uint32(/* id 5, wireType 1 =*/41).double(message.angularVelocity); + if (message.useAngularVelocity != null && Object.hasOwnProperty.call(message, "useAngularVelocity")) + writer.uint32(/* id 6, wireType 0 =*/48).bool(message.useAngularVelocity); + if (message.cameraYawOfRobot != null && Object.hasOwnProperty.call(message, "cameraYawOfRobot")) + writer.uint32(/* id 7, wireType 1 =*/57).double(message.cameraYawOfRobot); + if (message.cameraYawOfRobotIsSet != null && Object.hasOwnProperty.call(message, "cameraYawOfRobotIsSet")) + writer.uint32(/* id 8, wireType 0 =*/64).bool(message.cameraYawOfRobotIsSet); + if (message.kickSpeed != null && Object.hasOwnProperty.call(message, "kickSpeed")) + writer.uint32(/* id 9, wireType 1 =*/73).double(message.kickSpeed); + if (message.waitForBall != null && Object.hasOwnProperty.call(message, "waitForBall")) + writer.uint32(/* id 10, wireType 0 =*/80).bool(message.waitForBall); + if (message.kickAtYaw != null && Object.hasOwnProperty.call(message, "kickAtYaw")) + writer.uint32(/* id 11, wireType 0 =*/88).bool(message.kickAtYaw); + if (message.kickType != null && Object.hasOwnProperty.call(message, "kickType")) + writer.uint32(/* id 12, wireType 0 =*/96).int32(message.kickType); + if (message.dribblerOn != null && Object.hasOwnProperty.call(message, "dribblerOn")) + writer.uint32(/* id 13, wireType 0 =*/104).bool(message.dribblerOn); + if (message.wheelsOff != null && Object.hasOwnProperty.call(message, "wheelsOff")) + writer.uint32(/* id 14, wireType 0 =*/112).bool(message.wheelsOff); + return writer; + }; + + /** + * Encodes the specified RobotCommand message, length delimited. Does not implicitly {@link proto.RobotCommand.verify|verify} messages. + * @function encodeDelimited + * @memberof proto.RobotCommand + * @static + * @param {proto.IRobotCommand} message RobotCommand message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + RobotCommand.encodeDelimited = function encodeDelimited(message, writer) { + return this.encode(message, writer).ldelim(); + }; + + /** + * Decodes a RobotCommand message from the specified reader or buffer. + * @function decode + * @memberof proto.RobotCommand + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @param {number} [length] Message length if known beforehand + * @returns {proto.RobotCommand} RobotCommand + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + RobotCommand.decode = function decode(reader, length) { + if (!(reader instanceof $Reader)) + reader = $Reader.create(reader); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.RobotCommand(); + while (reader.pos < end) { + let tag = reader.uint32(); + switch (tag >>> 3) { + case 1: { + message.id = reader.int32(); + break; + } + case 2: { + message.velocityX = reader.double(); + break; + } + case 3: { + message.velocityY = reader.double(); + break; + } + case 4: { + message.yaw = reader.double(); + break; + } + case 5: { + message.angularVelocity = reader.double(); + break; + } + case 6: { + message.useAngularVelocity = reader.bool(); + break; + } + case 7: { + message.cameraYawOfRobot = reader.double(); + break; + } + case 8: { + message.cameraYawOfRobotIsSet = reader.bool(); + break; + } + case 9: { + message.kickSpeed = reader.double(); + break; + } + case 10: { + message.waitForBall = reader.bool(); + break; + } + case 11: { + message.kickAtYaw = reader.bool(); + break; + } + case 12: { + message.kickType = reader.int32(); + break; + } + case 13: { + message.dribblerOn = reader.bool(); + break; + } + case 14: { + message.wheelsOff = reader.bool(); + break; + } + default: + reader.skipType(tag & 7); + break; + } + } + return message; + }; + + /** + * Decodes a RobotCommand message from the specified reader or buffer, length delimited. + * @function decodeDelimited + * @memberof proto.RobotCommand + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @returns {proto.RobotCommand} RobotCommand + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + RobotCommand.decodeDelimited = function decodeDelimited(reader) { + if (!(reader instanceof $Reader)) + reader = new $Reader(reader); + return this.decode(reader, reader.uint32()); + }; + + /** + * Verifies a RobotCommand message. + * @function verify + * @memberof proto.RobotCommand + * @static + * @param {Object.} message Plain object to verify + * @returns {string|null} `null` if valid, otherwise the reason why it is not + */ + RobotCommand.verify = function verify(message) { + if (typeof message !== "object" || message === null) + return "object expected"; + if (message.id != null && message.hasOwnProperty("id")) + if (!$util.isInteger(message.id)) + return "id: integer expected"; + if (message.velocityX != null && message.hasOwnProperty("velocityX")) + if (typeof message.velocityX !== "number") + return "velocityX: number expected"; + if (message.velocityY != null && message.hasOwnProperty("velocityY")) + if (typeof message.velocityY !== "number") + return "velocityY: number expected"; + if (message.yaw != null && message.hasOwnProperty("yaw")) + if (typeof message.yaw !== "number") + return "yaw: number expected"; + if (message.angularVelocity != null && message.hasOwnProperty("angularVelocity")) + if (typeof message.angularVelocity !== "number") + return "angularVelocity: number expected"; + if (message.useAngularVelocity != null && message.hasOwnProperty("useAngularVelocity")) + if (typeof message.useAngularVelocity !== "boolean") + return "useAngularVelocity: boolean expected"; + if (message.cameraYawOfRobot != null && message.hasOwnProperty("cameraYawOfRobot")) + if (typeof message.cameraYawOfRobot !== "number") + return "cameraYawOfRobot: number expected"; + if (message.cameraYawOfRobotIsSet != null && message.hasOwnProperty("cameraYawOfRobotIsSet")) + if (typeof message.cameraYawOfRobotIsSet !== "boolean") + return "cameraYawOfRobotIsSet: boolean expected"; + if (message.kickSpeed != null && message.hasOwnProperty("kickSpeed")) + if (typeof message.kickSpeed !== "number") + return "kickSpeed: number expected"; + if (message.waitForBall != null && message.hasOwnProperty("waitForBall")) + if (typeof message.waitForBall !== "boolean") + return "waitForBall: boolean expected"; + if (message.kickAtYaw != null && message.hasOwnProperty("kickAtYaw")) + if (typeof message.kickAtYaw !== "boolean") + return "kickAtYaw: boolean expected"; + if (message.kickType != null && message.hasOwnProperty("kickType")) + switch (message.kickType) { + default: + return "kickType: enum value expected"; + case 0: + case 1: + case 2: + break; + } + if (message.dribblerOn != null && message.hasOwnProperty("dribblerOn")) + if (typeof message.dribblerOn !== "boolean") + return "dribblerOn: boolean expected"; + if (message.wheelsOff != null && message.hasOwnProperty("wheelsOff")) + if (typeof message.wheelsOff !== "boolean") + return "wheelsOff: boolean expected"; + return null; + }; + + /** + * Creates a RobotCommand message from a plain object. Also converts values to their respective internal types. + * @function fromObject + * @memberof proto.RobotCommand + * @static + * @param {Object.} object Plain object + * @returns {proto.RobotCommand} RobotCommand + */ + RobotCommand.fromObject = function fromObject(object) { + if (object instanceof $root.proto.RobotCommand) + return object; + let message = new $root.proto.RobotCommand(); + if (object.id != null) + message.id = object.id | 0; + if (object.velocityX != null) + message.velocityX = Number(object.velocityX); + if (object.velocityY != null) + message.velocityY = Number(object.velocityY); + if (object.yaw != null) + message.yaw = Number(object.yaw); + if (object.angularVelocity != null) + message.angularVelocity = Number(object.angularVelocity); + if (object.useAngularVelocity != null) + message.useAngularVelocity = Boolean(object.useAngularVelocity); + if (object.cameraYawOfRobot != null) + message.cameraYawOfRobot = Number(object.cameraYawOfRobot); + if (object.cameraYawOfRobotIsSet != null) + message.cameraYawOfRobotIsSet = Boolean(object.cameraYawOfRobotIsSet); + if (object.kickSpeed != null) + message.kickSpeed = Number(object.kickSpeed); + if (object.waitForBall != null) + message.waitForBall = Boolean(object.waitForBall); + if (object.kickAtYaw != null) + message.kickAtYaw = Boolean(object.kickAtYaw); + switch (object.kickType) { + default: + if (typeof object.kickType === "number") { + message.kickType = object.kickType; + break; + } + break; + case "NO_KICK": + case 0: + message.kickType = 0; + break; + case "KICK": + case 1: + message.kickType = 1; + break; + case "CHIP": + case 2: + message.kickType = 2; + break; + } + if (object.dribblerOn != null) + message.dribblerOn = Boolean(object.dribblerOn); + if (object.wheelsOff != null) + message.wheelsOff = Boolean(object.wheelsOff); + return message; + }; + + /** + * Creates a plain object from a RobotCommand message. Also converts values to other types if specified. + * @function toObject + * @memberof proto.RobotCommand + * @static + * @param {proto.RobotCommand} message RobotCommand + * @param {$protobuf.IConversionOptions} [options] Conversion options + * @returns {Object.} Plain object + */ + RobotCommand.toObject = function toObject(message, options) { + if (!options) + options = {}; + let object = {}; + if (options.defaults) { + object.id = 0; + object.velocityX = 0; + object.velocityY = 0; + object.yaw = 0; + object.angularVelocity = 0; + object.useAngularVelocity = false; + object.cameraYawOfRobot = 0; + object.cameraYawOfRobotIsSet = false; + object.kickSpeed = 0; + object.waitForBall = false; + object.kickAtYaw = false; + object.kickType = options.enums === String ? "NO_KICK" : 0; + object.dribblerOn = false; + object.wheelsOff = false; + } + if (message.id != null && message.hasOwnProperty("id")) + object.id = message.id; + if (message.velocityX != null && message.hasOwnProperty("velocityX")) + object.velocityX = options.json && !isFinite(message.velocityX) ? String(message.velocityX) : message.velocityX; + if (message.velocityY != null && message.hasOwnProperty("velocityY")) + object.velocityY = options.json && !isFinite(message.velocityY) ? String(message.velocityY) : message.velocityY; + if (message.yaw != null && message.hasOwnProperty("yaw")) + object.yaw = options.json && !isFinite(message.yaw) ? String(message.yaw) : message.yaw; + if (message.angularVelocity != null && message.hasOwnProperty("angularVelocity")) + object.angularVelocity = options.json && !isFinite(message.angularVelocity) ? String(message.angularVelocity) : message.angularVelocity; + if (message.useAngularVelocity != null && message.hasOwnProperty("useAngularVelocity")) + object.useAngularVelocity = message.useAngularVelocity; + if (message.cameraYawOfRobot != null && message.hasOwnProperty("cameraYawOfRobot")) + object.cameraYawOfRobot = options.json && !isFinite(message.cameraYawOfRobot) ? String(message.cameraYawOfRobot) : message.cameraYawOfRobot; + if (message.cameraYawOfRobotIsSet != null && message.hasOwnProperty("cameraYawOfRobotIsSet")) + object.cameraYawOfRobotIsSet = message.cameraYawOfRobotIsSet; + if (message.kickSpeed != null && message.hasOwnProperty("kickSpeed")) + object.kickSpeed = options.json && !isFinite(message.kickSpeed) ? String(message.kickSpeed) : message.kickSpeed; + if (message.waitForBall != null && message.hasOwnProperty("waitForBall")) + object.waitForBall = message.waitForBall; + if (message.kickAtYaw != null && message.hasOwnProperty("kickAtYaw")) + object.kickAtYaw = message.kickAtYaw; + if (message.kickType != null && message.hasOwnProperty("kickType")) + object.kickType = options.enums === String ? $root.proto.RobotCommand.KickType[message.kickType] === undefined ? message.kickType : $root.proto.RobotCommand.KickType[message.kickType] : message.kickType; + if (message.dribblerOn != null && message.hasOwnProperty("dribblerOn")) + object.dribblerOn = message.dribblerOn; + if (message.wheelsOff != null && message.hasOwnProperty("wheelsOff")) + object.wheelsOff = message.wheelsOff; + return object; + }; + + /** + * Converts this RobotCommand to JSON. + * @function toJSON + * @memberof proto.RobotCommand + * @instance + * @returns {Object.} JSON object + */ + RobotCommand.prototype.toJSON = function toJSON() { + return this.constructor.toObject(this, $protobuf.util.toJSONOptions); + }; - Wrapper.SSL_WrapperPacket = (function() { + /** + * Gets the default type url for RobotCommand + * @function getTypeUrl + * @memberof proto.RobotCommand + * @static + * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns {string} The default type url + */ + RobotCommand.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + if (typeUrlPrefix === undefined) { + typeUrlPrefix = "type.googleapis.com"; + } + return typeUrlPrefix + "/proto.RobotCommand"; + }; - /** - * Properties of a SSL_WrapperPacket. - * @memberof proto.RoboCup2014Legacy.Wrapper - * @interface ISSL_WrapperPacket - * @property {proto.ISSL_DetectionFrame|null} [detection] SSL_WrapperPacket detection - * @property {proto.RoboCup2014Legacy.Geometry.ISSL_GeometryData|null} [geometry] SSL_WrapperPacket geometry - */ + /** + * KickType enum. + * @name proto.RobotCommand.KickType + * @enum {number} + * @property {number} NO_KICK=0 NO_KICK value + * @property {number} KICK=1 KICK value + * @property {number} CHIP=2 CHIP value + */ + RobotCommand.KickType = (function() { + const valuesById = {}, values = Object.create(valuesById); + values[valuesById[0] = "NO_KICK"] = 0; + values[valuesById[1] = "KICK"] = 1; + values[valuesById[2] = "CHIP"] = 2; + return values; + })(); - /** - * Constructs a new SSL_WrapperPacket. - * @memberof proto.RoboCup2014Legacy.Wrapper - * @classdesc Represents a SSL_WrapperPacket. - * @implements ISSL_WrapperPacket - * @constructor - * @param {proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket=} [properties] Properties to set - */ - function SSL_WrapperPacket(properties) { - if (properties) - for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) - if (properties[keys[i]] != null) - this[keys[i]] = properties[keys[i]]; - } + return RobotCommand; + })(); - /** - * SSL_WrapperPacket detection. - * @member {proto.ISSL_DetectionFrame|null|undefined} detection - * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket - * @instance - */ - SSL_WrapperPacket.prototype.detection = null; + proto.RobotCommands = (function() { - /** - * SSL_WrapperPacket geometry. - * @member {proto.RoboCup2014Legacy.Geometry.ISSL_GeometryData|null|undefined} geometry - * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket - * @instance - */ - SSL_WrapperPacket.prototype.geometry = null; + /** + * Properties of a RobotCommands. + * @memberof proto + * @interface IRobotCommands + * @property {Array.|null} [robotCommands] RobotCommands robotCommands + */ - /** - * Creates a new SSL_WrapperPacket instance using the specified properties. - * @function create - * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket - * @static - * @param {proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket=} [properties] Properties to set - * @returns {proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket} SSL_WrapperPacket instance - */ - SSL_WrapperPacket.create = function create(properties) { - return new SSL_WrapperPacket(properties); - }; + /** + * Constructs a new RobotCommands. + * @memberof proto + * @classdesc Represents a RobotCommands. + * @implements IRobotCommands + * @constructor + * @param {proto.IRobotCommands=} [properties] Properties to set + */ + function RobotCommands(properties) { + this.robotCommands = []; + if (properties) + for (let keys = Object.keys(properties), i = 0; i < keys.length; ++i) + if (properties[keys[i]] != null) + this[keys[i]] = properties[keys[i]]; + } - /** - * Encodes the specified SSL_WrapperPacket message. Does not implicitly {@link proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket.verify|verify} messages. - * @function encode - * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket - * @static - * @param {proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket} message SSL_WrapperPacket message or plain object to encode - * @param {$protobuf.Writer} [writer] Writer to encode to - * @returns {$protobuf.Writer} Writer - */ - SSL_WrapperPacket.encode = function encode(message, writer) { - if (!writer) - writer = $Writer.create(); - if (message.detection != null && Object.hasOwnProperty.call(message, "detection")) - $root.proto.SSL_DetectionFrame.encode(message.detection, writer.uint32(/* id 1, wireType 2 =*/10).fork()).ldelim(); - if (message.geometry != null && Object.hasOwnProperty.call(message, "geometry")) - $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.encode(message.geometry, writer.uint32(/* id 2, wireType 2 =*/18).fork()).ldelim(); - return writer; - }; + /** + * RobotCommands robotCommands. + * @member {Array.} robotCommands + * @memberof proto.RobotCommands + * @instance + */ + RobotCommands.prototype.robotCommands = $util.emptyArray; - /** - * Encodes the specified SSL_WrapperPacket message, length delimited. Does not implicitly {@link proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket.verify|verify} messages. - * @function encodeDelimited - * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket - * @static - * @param {proto.RoboCup2014Legacy.Wrapper.ISSL_WrapperPacket} message SSL_WrapperPacket message or plain object to encode - * @param {$protobuf.Writer} [writer] Writer to encode to - * @returns {$protobuf.Writer} Writer - */ - SSL_WrapperPacket.encodeDelimited = function encodeDelimited(message, writer) { - return this.encode(message, writer).ldelim(); - }; + /** + * Creates a new RobotCommands instance using the specified properties. + * @function create + * @memberof proto.RobotCommands + * @static + * @param {proto.IRobotCommands=} [properties] Properties to set + * @returns {proto.RobotCommands} RobotCommands instance + */ + RobotCommands.create = function create(properties) { + return new RobotCommands(properties); + }; - /** - * Decodes a SSL_WrapperPacket message from the specified reader or buffer. - * @function decode - * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket - * @static - * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @param {number} [length] Message length if known beforehand - * @returns {proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket} SSL_WrapperPacket - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - SSL_WrapperPacket.decode = function decode(reader, length) { - if (!(reader instanceof $Reader)) - reader = $Reader.create(reader); - let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket(); - while (reader.pos < end) { - let tag = reader.uint32(); - switch (tag >>> 3) { - case 1: { - message.detection = $root.proto.SSL_DetectionFrame.decode(reader, reader.uint32()); - break; - } - case 2: { - message.geometry = $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.decode(reader, reader.uint32()); - break; - } - default: - reader.skipType(tag & 7); - break; - } - } - return message; - }; + /** + * Encodes the specified RobotCommands message. Does not implicitly {@link proto.RobotCommands.verify|verify} messages. + * @function encode + * @memberof proto.RobotCommands + * @static + * @param {proto.IRobotCommands} message RobotCommands message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + RobotCommands.encode = function encode(message, writer) { + if (!writer) + writer = $Writer.create(); + if (message.robotCommands != null && message.robotCommands.length) + for (let i = 0; i < message.robotCommands.length; ++i) + $root.proto.RobotCommand.encode(message.robotCommands[i], writer.uint32(/* id 1, wireType 2 =*/10).fork()).ldelim(); + return writer; + }; - /** - * Decodes a SSL_WrapperPacket message from the specified reader or buffer, length delimited. - * @function decodeDelimited - * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket - * @static - * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from - * @returns {proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket} SSL_WrapperPacket - * @throws {Error} If the payload is not a reader or valid buffer - * @throws {$protobuf.util.ProtocolError} If required fields are missing - */ - SSL_WrapperPacket.decodeDelimited = function decodeDelimited(reader) { - if (!(reader instanceof $Reader)) - reader = new $Reader(reader); - return this.decode(reader, reader.uint32()); - }; + /** + * Encodes the specified RobotCommands message, length delimited. Does not implicitly {@link proto.RobotCommands.verify|verify} messages. + * @function encodeDelimited + * @memberof proto.RobotCommands + * @static + * @param {proto.IRobotCommands} message RobotCommands message or plain object to encode + * @param {$protobuf.Writer} [writer] Writer to encode to + * @returns {$protobuf.Writer} Writer + */ + RobotCommands.encodeDelimited = function encodeDelimited(message, writer) { + return this.encode(message, writer).ldelim(); + }; - /** - * Verifies a SSL_WrapperPacket message. - * @function verify - * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket - * @static - * @param {Object.} message Plain object to verify - * @returns {string|null} `null` if valid, otherwise the reason why it is not - */ - SSL_WrapperPacket.verify = function verify(message) { - if (typeof message !== "object" || message === null) - return "object expected"; - if (message.detection != null && message.hasOwnProperty("detection")) { - let error = $root.proto.SSL_DetectionFrame.verify(message.detection); - if (error) - return "detection." + error; - } - if (message.geometry != null && message.hasOwnProperty("geometry")) { - let error = $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.verify(message.geometry); - if (error) - return "geometry." + error; + /** + * Decodes a RobotCommands message from the specified reader or buffer. + * @function decode + * @memberof proto.RobotCommands + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @param {number} [length] Message length if known beforehand + * @returns {proto.RobotCommands} RobotCommands + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + RobotCommands.decode = function decode(reader, length) { + if (!(reader instanceof $Reader)) + reader = $Reader.create(reader); + let end = length === undefined ? reader.len : reader.pos + length, message = new $root.proto.RobotCommands(); + while (reader.pos < end) { + let tag = reader.uint32(); + switch (tag >>> 3) { + case 1: { + if (!(message.robotCommands && message.robotCommands.length)) + message.robotCommands = []; + message.robotCommands.push($root.proto.RobotCommand.decode(reader, reader.uint32())); + break; } - return null; - }; + default: + reader.skipType(tag & 7); + break; + } + } + return message; + }; - /** - * Creates a SSL_WrapperPacket message from a plain object. Also converts values to their respective internal types. - * @function fromObject - * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket - * @static - * @param {Object.} object Plain object - * @returns {proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket} SSL_WrapperPacket - */ - SSL_WrapperPacket.fromObject = function fromObject(object) { - if (object instanceof $root.proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket) - return object; - let message = new $root.proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket(); - if (object.detection != null) { - if (typeof object.detection !== "object") - throw TypeError(".proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket.detection: object expected"); - message.detection = $root.proto.SSL_DetectionFrame.fromObject(object.detection); - } - if (object.geometry != null) { - if (typeof object.geometry !== "object") - throw TypeError(".proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket.geometry: object expected"); - message.geometry = $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.fromObject(object.geometry); - } - return message; - }; + /** + * Decodes a RobotCommands message from the specified reader or buffer, length delimited. + * @function decodeDelimited + * @memberof proto.RobotCommands + * @static + * @param {$protobuf.Reader|Uint8Array} reader Reader or buffer to decode from + * @returns {proto.RobotCommands} RobotCommands + * @throws {Error} If the payload is not a reader or valid buffer + * @throws {$protobuf.util.ProtocolError} If required fields are missing + */ + RobotCommands.decodeDelimited = function decodeDelimited(reader) { + if (!(reader instanceof $Reader)) + reader = new $Reader(reader); + return this.decode(reader, reader.uint32()); + }; - /** - * Creates a plain object from a SSL_WrapperPacket message. Also converts values to other types if specified. - * @function toObject - * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket - * @static - * @param {proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket} message SSL_WrapperPacket - * @param {$protobuf.IConversionOptions} [options] Conversion options - * @returns {Object.} Plain object - */ - SSL_WrapperPacket.toObject = function toObject(message, options) { - if (!options) - options = {}; - let object = {}; - if (options.defaults) { - object.detection = null; - object.geometry = null; - } - if (message.detection != null && message.hasOwnProperty("detection")) - object.detection = $root.proto.SSL_DetectionFrame.toObject(message.detection, options); - if (message.geometry != null && message.hasOwnProperty("geometry")) - object.geometry = $root.proto.RoboCup2014Legacy.Geometry.SSL_GeometryData.toObject(message.geometry, options); - return object; - }; + /** + * Verifies a RobotCommands message. + * @function verify + * @memberof proto.RobotCommands + * @static + * @param {Object.} message Plain object to verify + * @returns {string|null} `null` if valid, otherwise the reason why it is not + */ + RobotCommands.verify = function verify(message) { + if (typeof message !== "object" || message === null) + return "object expected"; + if (message.robotCommands != null && message.hasOwnProperty("robotCommands")) { + if (!Array.isArray(message.robotCommands)) + return "robotCommands: array expected"; + for (let i = 0; i < message.robotCommands.length; ++i) { + let error = $root.proto.RobotCommand.verify(message.robotCommands[i]); + if (error) + return "robotCommands." + error; + } + } + return null; + }; - /** - * Converts this SSL_WrapperPacket to JSON. - * @function toJSON - * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket - * @instance - * @returns {Object.} JSON object - */ - SSL_WrapperPacket.prototype.toJSON = function toJSON() { - return this.constructor.toObject(this, $protobuf.util.toJSONOptions); - }; + /** + * Creates a RobotCommands message from a plain object. Also converts values to their respective internal types. + * @function fromObject + * @memberof proto.RobotCommands + * @static + * @param {Object.} object Plain object + * @returns {proto.RobotCommands} RobotCommands + */ + RobotCommands.fromObject = function fromObject(object) { + if (object instanceof $root.proto.RobotCommands) + return object; + let message = new $root.proto.RobotCommands(); + if (object.robotCommands) { + if (!Array.isArray(object.robotCommands)) + throw TypeError(".proto.RobotCommands.robotCommands: array expected"); + message.robotCommands = []; + for (let i = 0; i < object.robotCommands.length; ++i) { + if (typeof object.robotCommands[i] !== "object") + throw TypeError(".proto.RobotCommands.robotCommands: object expected"); + message.robotCommands[i] = $root.proto.RobotCommand.fromObject(object.robotCommands[i]); + } + } + return message; + }; - /** - * Gets the default type url for SSL_WrapperPacket - * @function getTypeUrl - * @memberof proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket - * @static - * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") - * @returns {string} The default type url - */ - SSL_WrapperPacket.getTypeUrl = function getTypeUrl(typeUrlPrefix) { - if (typeUrlPrefix === undefined) { - typeUrlPrefix = "type.googleapis.com"; - } - return typeUrlPrefix + "/proto.RoboCup2014Legacy.Wrapper.SSL_WrapperPacket"; - }; + /** + * Creates a plain object from a RobotCommands message. Also converts values to other types if specified. + * @function toObject + * @memberof proto.RobotCommands + * @static + * @param {proto.RobotCommands} message RobotCommands + * @param {$protobuf.IConversionOptions} [options] Conversion options + * @returns {Object.} Plain object + */ + RobotCommands.toObject = function toObject(message, options) { + if (!options) + options = {}; + let object = {}; + if (options.arrays || options.defaults) + object.robotCommands = []; + if (message.robotCommands && message.robotCommands.length) { + object.robotCommands = []; + for (let j = 0; j < message.robotCommands.length; ++j) + object.robotCommands[j] = $root.proto.RobotCommand.toObject(message.robotCommands[j], options); + } + return object; + }; - return SSL_WrapperPacket; - })(); + /** + * Converts this RobotCommands to JSON. + * @function toJSON + * @memberof proto.RobotCommands + * @instance + * @returns {Object.} JSON object + */ + RobotCommands.prototype.toJSON = function toJSON() { + return this.constructor.toObject(this, $protobuf.util.toJSONOptions); + }; - return Wrapper; - })(); + /** + * Gets the default type url for RobotCommands + * @function getTypeUrl + * @memberof proto.RobotCommands + * @static + * @param {string} [typeUrlPrefix] your custom typeUrlPrefix(default "type.googleapis.com") + * @returns {string} The default type url + */ + RobotCommands.getTypeUrl = function getTypeUrl(typeUrlPrefix) { + if (typeUrlPrefix === undefined) { + typeUrlPrefix = "type.googleapis.com"; + } + return typeUrlPrefix + "/proto.RobotCommands"; + }; - return RoboCup2014Legacy; + return RobotCommands; })(); return proto; @@ -34633,6 +35848,12 @@ export const SSL_GeometryFieldSize = $root.SSL_GeometryFieldSize = (() => { * @property {Array.|null} [fieldArcs] SSL_GeometryFieldSize fieldArcs * @property {number|null} [penaltyAreaDepth] SSL_GeometryFieldSize penaltyAreaDepth * @property {number|null} [penaltyAreaWidth] SSL_GeometryFieldSize penaltyAreaWidth + * @property {number|null} [centerCircleRadius] SSL_GeometryFieldSize centerCircleRadius + * @property {number|null} [lineThickness] SSL_GeometryFieldSize lineThickness + * @property {number|null} [goalCenterToPenaltyMark] SSL_GeometryFieldSize goalCenterToPenaltyMark + * @property {number|null} [goalHeight] SSL_GeometryFieldSize goalHeight + * @property {number|null} [ballRadius] SSL_GeometryFieldSize ballRadius + * @property {number|null} [maxRobotRadius] SSL_GeometryFieldSize maxRobotRadius */ /** @@ -34724,6 +35945,54 @@ export const SSL_GeometryFieldSize = $root.SSL_GeometryFieldSize = (() => { */ SSL_GeometryFieldSize.prototype.penaltyAreaWidth = 0; + /** + * SSL_GeometryFieldSize centerCircleRadius. + * @member {number} centerCircleRadius + * @memberof SSL_GeometryFieldSize + * @instance + */ + SSL_GeometryFieldSize.prototype.centerCircleRadius = 0; + + /** + * SSL_GeometryFieldSize lineThickness. + * @member {number} lineThickness + * @memberof SSL_GeometryFieldSize + * @instance + */ + SSL_GeometryFieldSize.prototype.lineThickness = 0; + + /** + * SSL_GeometryFieldSize goalCenterToPenaltyMark. + * @member {number} goalCenterToPenaltyMark + * @memberof SSL_GeometryFieldSize + * @instance + */ + SSL_GeometryFieldSize.prototype.goalCenterToPenaltyMark = 0; + + /** + * SSL_GeometryFieldSize goalHeight. + * @member {number} goalHeight + * @memberof SSL_GeometryFieldSize + * @instance + */ + SSL_GeometryFieldSize.prototype.goalHeight = 0; + + /** + * SSL_GeometryFieldSize ballRadius. + * @member {number} ballRadius + * @memberof SSL_GeometryFieldSize + * @instance + */ + SSL_GeometryFieldSize.prototype.ballRadius = 0; + + /** + * SSL_GeometryFieldSize maxRobotRadius. + * @member {number} maxRobotRadius + * @memberof SSL_GeometryFieldSize + * @instance + */ + SSL_GeometryFieldSize.prototype.maxRobotRadius = 0; + /** * Creates a new SSL_GeometryFieldSize instance using the specified properties. * @function create @@ -34763,6 +36032,18 @@ export const SSL_GeometryFieldSize = $root.SSL_GeometryFieldSize = (() => { writer.uint32(/* id 8, wireType 0 =*/64).int32(message.penaltyAreaDepth); if (message.penaltyAreaWidth != null && Object.hasOwnProperty.call(message, "penaltyAreaWidth")) writer.uint32(/* id 9, wireType 0 =*/72).int32(message.penaltyAreaWidth); + if (message.centerCircleRadius != null && Object.hasOwnProperty.call(message, "centerCircleRadius")) + writer.uint32(/* id 10, wireType 0 =*/80).int32(message.centerCircleRadius); + if (message.lineThickness != null && Object.hasOwnProperty.call(message, "lineThickness")) + writer.uint32(/* id 11, wireType 0 =*/88).int32(message.lineThickness); + if (message.goalCenterToPenaltyMark != null && Object.hasOwnProperty.call(message, "goalCenterToPenaltyMark")) + writer.uint32(/* id 12, wireType 0 =*/96).int32(message.goalCenterToPenaltyMark); + if (message.goalHeight != null && Object.hasOwnProperty.call(message, "goalHeight")) + writer.uint32(/* id 13, wireType 0 =*/104).int32(message.goalHeight); + if (message.ballRadius != null && Object.hasOwnProperty.call(message, "ballRadius")) + writer.uint32(/* id 14, wireType 5 =*/117).float(message.ballRadius); + if (message.maxRobotRadius != null && Object.hasOwnProperty.call(message, "maxRobotRadius")) + writer.uint32(/* id 15, wireType 5 =*/125).float(message.maxRobotRadius); return writer; }; @@ -34837,6 +36118,30 @@ export const SSL_GeometryFieldSize = $root.SSL_GeometryFieldSize = (() => { message.penaltyAreaWidth = reader.int32(); break; } + case 10: { + message.centerCircleRadius = reader.int32(); + break; + } + case 11: { + message.lineThickness = reader.int32(); + break; + } + case 12: { + message.goalCenterToPenaltyMark = reader.int32(); + break; + } + case 13: { + message.goalHeight = reader.int32(); + break; + } + case 14: { + message.ballRadius = reader.float(); + break; + } + case 15: { + message.maxRobotRadius = reader.float(); + break; + } default: reader.skipType(tag & 7); break; @@ -34916,6 +36221,24 @@ export const SSL_GeometryFieldSize = $root.SSL_GeometryFieldSize = (() => { if (message.penaltyAreaWidth != null && message.hasOwnProperty("penaltyAreaWidth")) if (!$util.isInteger(message.penaltyAreaWidth)) return "penaltyAreaWidth: integer expected"; + if (message.centerCircleRadius != null && message.hasOwnProperty("centerCircleRadius")) + if (!$util.isInteger(message.centerCircleRadius)) + return "centerCircleRadius: integer expected"; + if (message.lineThickness != null && message.hasOwnProperty("lineThickness")) + if (!$util.isInteger(message.lineThickness)) + return "lineThickness: integer expected"; + if (message.goalCenterToPenaltyMark != null && message.hasOwnProperty("goalCenterToPenaltyMark")) + if (!$util.isInteger(message.goalCenterToPenaltyMark)) + return "goalCenterToPenaltyMark: integer expected"; + if (message.goalHeight != null && message.hasOwnProperty("goalHeight")) + if (!$util.isInteger(message.goalHeight)) + return "goalHeight: integer expected"; + if (message.ballRadius != null && message.hasOwnProperty("ballRadius")) + if (typeof message.ballRadius !== "number") + return "ballRadius: number expected"; + if (message.maxRobotRadius != null && message.hasOwnProperty("maxRobotRadius")) + if (typeof message.maxRobotRadius !== "number") + return "maxRobotRadius: number expected"; return null; }; @@ -34965,6 +36288,18 @@ export const SSL_GeometryFieldSize = $root.SSL_GeometryFieldSize = (() => { message.penaltyAreaDepth = object.penaltyAreaDepth | 0; if (object.penaltyAreaWidth != null) message.penaltyAreaWidth = object.penaltyAreaWidth | 0; + if (object.centerCircleRadius != null) + message.centerCircleRadius = object.centerCircleRadius | 0; + if (object.lineThickness != null) + message.lineThickness = object.lineThickness | 0; + if (object.goalCenterToPenaltyMark != null) + message.goalCenterToPenaltyMark = object.goalCenterToPenaltyMark | 0; + if (object.goalHeight != null) + message.goalHeight = object.goalHeight | 0; + if (object.ballRadius != null) + message.ballRadius = Number(object.ballRadius); + if (object.maxRobotRadius != null) + message.maxRobotRadius = Number(object.maxRobotRadius); return message; }; @@ -34993,6 +36328,12 @@ export const SSL_GeometryFieldSize = $root.SSL_GeometryFieldSize = (() => { object.boundaryWidth = 0; object.penaltyAreaDepth = 0; object.penaltyAreaWidth = 0; + object.centerCircleRadius = 0; + object.lineThickness = 0; + object.goalCenterToPenaltyMark = 0; + object.goalHeight = 0; + object.ballRadius = 0; + object.maxRobotRadius = 0; } if (message.fieldLength != null && message.hasOwnProperty("fieldLength")) object.fieldLength = message.fieldLength; @@ -35018,6 +36359,18 @@ export const SSL_GeometryFieldSize = $root.SSL_GeometryFieldSize = (() => { object.penaltyAreaDepth = message.penaltyAreaDepth; if (message.penaltyAreaWidth != null && message.hasOwnProperty("penaltyAreaWidth")) object.penaltyAreaWidth = message.penaltyAreaWidth; + if (message.centerCircleRadius != null && message.hasOwnProperty("centerCircleRadius")) + object.centerCircleRadius = message.centerCircleRadius; + if (message.lineThickness != null && message.hasOwnProperty("lineThickness")) + object.lineThickness = message.lineThickness; + if (message.goalCenterToPenaltyMark != null && message.hasOwnProperty("goalCenterToPenaltyMark")) + object.goalCenterToPenaltyMark = message.goalCenterToPenaltyMark; + if (message.goalHeight != null && message.hasOwnProperty("goalHeight")) + object.goalHeight = message.goalHeight; + if (message.ballRadius != null && message.hasOwnProperty("ballRadius")) + object.ballRadius = options.json && !isFinite(message.ballRadius) ? String(message.ballRadius) : message.ballRadius; + if (message.maxRobotRadius != null && message.hasOwnProperty("maxRobotRadius")) + object.maxRobotRadius = options.json && !isFinite(message.maxRobotRadius) ? String(message.maxRobotRadius) : message.maxRobotRadius; return object; }; diff --git a/roboteam_interface/src/index.css b/roboteam_interface/src/index.css index ad155a332..6bf8e07e8 100644 --- a/roboteam_interface/src/index.css +++ b/roboteam_interface/src/index.css @@ -26,5 +26,5 @@ /* Handle on hover */ .subtile-scroll-bar::-webkit-scrollbar-thumb:hover { - background: hsl(var(--bc));; + background: hsl(var(--bc)); } diff --git a/roboteam_interface/src/modules/components/canvas/ball.vue b/roboteam_interface/src/modules/components/canvas/ball.vue index 47c777d62..55518ac95 100644 --- a/roboteam_interface/src/modules/components/canvas/ball.vue +++ b/roboteam_interface/src/modules/components/canvas/ball.vue @@ -1,5 +1,4 @@ - \ No newline at end of file + diff --git a/roboteam_interface/src/modules/composables/ai-controller.ts b/roboteam_interface/src/modules/composables/ai-controller.ts index 58823db2a..240d182e9 100644 --- a/roboteam_interface/src/modules/composables/ai-controller.ts +++ b/roboteam_interface/src/modules/composables/ai-controller.ts @@ -29,7 +29,7 @@ export const useAiController = defineStore('aiController', () => { // Actions const setBallPos = (x: number, y: number) => send('setBallPos', { x, y }) - const sendSimulatorCommand = (command: ISimulatorCommand) => send('simulatorCommand', command); + const sendSimulatorCommand = (command: ISimulatorCommand) => send('simulatorCommand', command) // Writable computed properties const useReferee = computed({ diff --git a/roboteam_interface/src/modules/stores/data-stores/ai-data-store.ts b/roboteam_interface/src/modules/stores/data-stores/ai-data-store.ts index d87571e53..2c9995002 100644 --- a/roboteam_interface/src/modules/stores/data-stores/ai-data-store.ts +++ b/roboteam_interface/src/modules/stores/data-stores/ai-data-store.ts @@ -17,9 +17,7 @@ export const useAIDataStore = defineStore('aiDataStore', () => { // Getters const fieldOrientation = computed(() => { - return state.value?.gameSettings?.isLeft - ? { x: 1, y: -1, angle: 0 } - : { x: -1, y: 1, angle: 180 } + return state.value?.gameSettings?.isLeft ? { x: 1, y: -1, yaw: 0 } : { x: -1, y: 1, yaw: 180 } }) return { diff --git a/roboteam_interface/src/modules/stores/ui-store.ts b/roboteam_interface/src/modules/stores/ui-store.ts index 5bc116a53..f3ff15f73 100644 --- a/roboteam_interface/src/modules/stores/ui-store.ts +++ b/roboteam_interface/src/modules/stores/ui-store.ts @@ -15,11 +15,11 @@ export type DualState = 'SHOW' | 'HIDE' export type UiStore = { bottomPanel: Panel leftPanel: Panel - selectedRobots: Set, + selectedRobots: Set pointerLocation: { x: number y: number - } | null, + } | null scaling: { ball: number robots: number @@ -95,8 +95,7 @@ export const useUIStore = defineStore('uiStore', { return (id: number) => state.selectedRobots.has(id) }, showMargins(state) { - return (forRobot?: number | null) => - state.visualizations.margins === 'SHOW' + return () => state.visualizations.margins === 'SHOW' }, showDebug(state) { return (forRobot?: number | null) => diff --git a/roboteam_interface/src/tabs.ts b/roboteam_interface/src/tabs.ts index 2f85325b3..333e98be1 100644 --- a/roboteam_interface/src/tabs.ts +++ b/roboteam_interface/src/tabs.ts @@ -1,18 +1,18 @@ import { markRaw } from 'vue' -import GameSettings from './modules/components/game-settings.vue' -import Simulator from './modules/components/panels/simulator-widget.vue' -import StpStatus from './modules/components/panels/stp-panel/stp-widget.vue' -import Feedback from './modules/components/panels/feedback-widget.vue' +import GameSettings from './modules/components/game-settings.vue' +import Simulator from './modules/components/panels/simulator-widget.vue' +import StpStatus from './modules/components/panels/stp-panel/stp-widget.vue' +import Feedback from './modules/components/panels/feedback-widget.vue' import PlayEvaluation from './modules/components/panels/play-evaluation-widget.vue' -import Metrics from './modules/components/panels/metrics-widget.vue' -import UiSettings from './modules/components/ui-settings/ui-settings.vue' +import Metrics from './modules/components/panels/metrics-widget.vue' +import UiSettings from './modules/components/ui-settings/ui-settings.vue' export const TABS_DEFINITION = { 'Game Settings': { icon: 'fa-gear', component: markRaw(GameSettings) }, - 'Simulator': { + Simulator: { icon: 'fa-gamepad', component: markRaw(Simulator) }, diff --git a/roboteam_interface/src/utils.ts b/roboteam_interface/src/utils.ts index 28a9b2fb9..d0cb1ebfa 100644 --- a/roboteam_interface/src/utils.ts +++ b/roboteam_interface/src/utils.ts @@ -15,7 +15,7 @@ export const sleep = (time: number) => { export const OUT_OF_CANVAS_COORDINATES = { x: 100, y: 100, - angle: 0 + yaw: 0 } export const robotNameMap = (team: 'BLACK' | 'PURPLE', id: number) => { diff --git a/roboteam_interface/yarn.lock b/roboteam_interface/yarn.lock index 491102cee..2b8d3ec09 100644 --- a/roboteam_interface/yarn.lock +++ b/roboteam_interface/yarn.lock @@ -2230,9 +2230,9 @@ protobufjs-cli@^1.1.1: uglify-js "^3.7.7" protobufjs@^7.2.3: - version "7.2.3" - resolved "https://registry.npmjs.org/protobufjs/-/protobufjs-7.2.3.tgz" - integrity sha512-TtpvOqwB5Gdz/PQmOjgsrGH1nHjAQVCN7JG4A6r1sXRWESL5rNMAiRcBQlCAdKxZcAbstExQePYG8xof/JVRgg== + version "7.3.0" + resolved "https://registry.yarnpkg.com/protobufjs/-/protobufjs-7.3.0.tgz#a32ec0422c039798c41a0700306a6e305b9cb32c" + integrity sha512-YWD03n3shzV9ImZRX3ccbjqLxj7NokGN0V/ESiBV5xWqrommYHYiihuIyavq03pWSGqlyvYUFmfoMKd+1rPA/g== dependencies: "@protobufjs/aspromise" "^1.1.2" "@protobufjs/base64" "^1.1.2" diff --git a/roboteam_networking/proto/GUI.proto b/roboteam_networking/proto/GUI.proto index 2e74554f1..1370f4667 100644 --- a/roboteam_networking/proto/GUI.proto +++ b/roboteam_networking/proto/GUI.proto @@ -23,7 +23,8 @@ message Drawing { CYAN = 4; MAGENTA = 5; WHITE = 6; - BLACK = 7; + GREY = 7; + BLACK = 8; } enum Category { diff --git a/roboteam_networking/proto/RobotCommands.proto b/roboteam_networking/proto/RobotCommands.proto index d785033ea..43efddcb5 100644 --- a/roboteam_networking/proto/RobotCommands.proto +++ b/roboteam_networking/proto/RobotCommands.proto @@ -7,16 +7,16 @@ message RobotCommand { double velocity_x = 2; // (m/s) Target x velocity of the robot double velocity_y = 3; // (m/s) Target y velocity of the robot - double angle = 4; // (rad) [-PI, PI] Target angle + double yaw = 4; // (rad) [-PI, PI] Target yaw double angular_velocity = 5; // (rad/s) Target angular velocity - bool use_angular_velocity = 6; // If true, the angular velocity has priority over angle + bool use_angular_velocity = 6; // If true, the angular velocity has priority over yaw - double camera_angle_of_robot = 7; // (rad) Angle of robot according to camera - bool camera_angle_of_robot_is_set = 8; // If true, the camera angle can be used + double camera_yaw_of_robot = 7; // (rad) Angle of robot according to camera + bool camera_yaw_of_robot_is_set = 8; // If true, the camera yaw can be used double kick_speed = 9; // (m/s) Target speed of the ball after kicking bool wait_for_ball = 10; // If true, the robot will wait with kicking until it has the ball - bool kick_at_angle = 11; // Makes robot kick once it arrives at the specified angle, used in combination with angular velocity + bool kick_at_yaw = 11; // Makes robot kick once it arrives at the specified yaw, used in combination with angular velocity enum KickType { NO_KICK = 0; @@ -25,8 +25,8 @@ message RobotCommand { } KickType kick_type = 12; // Decides if and how the ball should be kicked - double dribbler_speed = 13; // [0, 1] Speed of the dribbler - bool ignore_packet = 14; // If true, the robot will ignore this packet, but will reply with feedback + bool dribbler_on = 13; // If true, the robot will turn on its dribbler + bool wheels_off = 14; // If true, the robot will not move its wheels } message RobotCommands { diff --git a/roboteam_networking/proto/RobotFeedback.proto b/roboteam_networking/proto/RobotFeedback.proto index e3bac6b08..ee1b66722 100644 --- a/roboteam_networking/proto/RobotFeedback.proto +++ b/roboteam_networking/proto/RobotFeedback.proto @@ -15,18 +15,14 @@ enum RobotFeedbackSource { message RobotFeedback { int32 id = 1; // ID of the robot bool ball_sensor_sees_ball = 2; // The ball sensor sees the ball - float ball_position = 3; // [-0.5, 0.5] The position of the ball relative to the sensor bool ball_sensor_is_working = 4; // The sensor is working bool dribbler_sees_ball = 5; // The ball sensor sees the ball double estimated_velocity_x = 6; // The x velocity according to the robot double estimated_velocity_y = 7; // The y velocity according to the robot - double estimated_angle = 8; // [-PI, PI] (rad) The angle according to the robot + double estimated_yaw = 8; // [-PI, PI] (rad) The yaw according to the robot bool xsens_is_calibrated = 9; // The xSens is calibrated bool capacitor_is_charged = 10; // The capacitor is charged - int32 wheels_locked = 11; // Indicates which wheels are locked. One bit per wheel - int32 wheels_braking = 12; // Indicates which wheels are braking. One bit per wheel float battery_level = 13; // Battery level of the robot // TODO: Figure out if this is voltage or percentage - int32 signal_strength = 14; // Signal strength of the robot } message RobotsFeedback { diff --git a/roboteam_networking/proto/RobotParameters.proto b/roboteam_networking/proto/RobotParameters.proto index 934eabb55..2570b4cdf 100644 --- a/roboteam_networking/proto/RobotParameters.proto +++ b/roboteam_networking/proto/RobotParameters.proto @@ -7,7 +7,7 @@ message RobotParameters{ float height = 2; float front_width = 3; float dribbler_width = 4; - float angle_offset = 5; + float yaw_offset = 5; } message TeamParameters{ diff --git a/roboteam_networking/proto/RobotProcessedFeedback.proto b/roboteam_networking/proto/RobotProcessedFeedback.proto index ba24c99c1..38c6b726a 100644 --- a/roboteam_networking/proto/RobotProcessedFeedback.proto +++ b/roboteam_networking/proto/RobotProcessedFeedback.proto @@ -2,29 +2,13 @@ syntax = "proto3"; package proto; -message RobotWheel{ - bool locked = 1; //Indicates if this wheel is locked - bool braking = 2; //Indicates if this wheel is braking -} - - -message RobotWheels{ - RobotWheel rightFront = 1; //Right front wheel when considering the robots POV - RobotWheel rightBack = 2; //Right back wheel when considering the robots POV - RobotWheel leftBack = 3; //Left back wheel when considering the robots POV - RobotWheel leftFront = 4; //Left front wheel when considering the robots POV -} - message RobotProcessedFeedback { bool ball_sensor_sees_ball = 1; // The ball sensor sees the ball - float ball_position = 2; // [-0.5, 0.5] The position of the ball relative to the sensor bool ball_sensor_is_working = 3; // The sensor is working bool dribbler_sees_ball = 4; // The dribbler sees the ball bool xsens_is_calibrated = 5; // The xSens is calibrated bool capacitor_is_charged = 6; // The capacitor is charged - RobotWheels wheelInformation = 7; // Information on the wheels float battery_level = 8; // Battery level of the robot // TODO: Figure out if this is voltage or percentage - int32 signal_strength = 9; // Signal strength of the robot //TODO: units?? } message FeedbackOnlyRobot{ diff --git a/roboteam_networking/proto/WorldRobot.proto b/roboteam_networking/proto/WorldRobot.proto index 6d5deea01..55e003a8e 100644 --- a/roboteam_networking/proto/WorldRobot.proto +++ b/roboteam_networking/proto/WorldRobot.proto @@ -8,7 +8,7 @@ package proto; message WorldRobot { uint32 id = 1; Vector2f pos = 2; - float angle = 3; + float yaw = 3; Vector2f vel = 4; float w = 5; RobotProcessedFeedback feedbackInfo = 6; diff --git a/roboteam_networking/src/RobotCommandsNetworker.cpp b/roboteam_networking/src/RobotCommandsNetworker.cpp index 5a49a26c2..9b488b5bc 100644 --- a/roboteam_networking/src/RobotCommandsNetworker.cpp +++ b/roboteam_networking/src/RobotCommandsNetworker.cpp @@ -39,20 +39,20 @@ proto::RobotCommands robotCommandsToProto(const rtt::RobotCommands& commands) { protoCommand->set_id(command.id); protoCommand->set_velocity_x(command.velocity.x); protoCommand->set_velocity_y(command.velocity.y); - protoCommand->set_angle(command.targetAngle.getValue()); + protoCommand->set_yaw(command.yaw.getValue()); protoCommand->set_angular_velocity(command.targetAngularVelocity); protoCommand->set_use_angular_velocity(command.useAngularVelocity); - protoCommand->set_camera_angle_of_robot(command.cameraAngleOfRobot.getValue()); - protoCommand->set_camera_angle_of_robot_is_set(command.cameraAngleOfRobotIsSet); + protoCommand->set_camera_yaw_of_robot(command.cameraYawOfRobot.getValue()); + protoCommand->set_camera_yaw_of_robot_is_set(command.cameraYawOfRobotIsSet); protoCommand->set_kick_speed(command.kickSpeed); protoCommand->set_wait_for_ball(command.waitForBall); protoCommand->set_kick_type(kickTypeToProto(command.kickType)); - protoCommand->set_kick_at_angle(command.kickAtAngle); + protoCommand->set_kick_at_yaw(command.kickAtYaw); - protoCommand->set_dribbler_speed(command.dribblerSpeed); - protoCommand->set_ignore_packet(command.ignorePacket); + protoCommand->set_dribbler_on(command.dribblerOn); + protoCommand->set_wheels_off(command.wheelsOff); } return protoCommands; @@ -64,20 +64,20 @@ rtt::RobotCommands protoToRobotCommands(const proto::RobotCommands& protoCommand for (const auto& protoCommand : protoCommands.robot_commands()) { rtt::RobotCommand robotCommand = {.id = protoCommand.id(), .velocity = Vector2(protoCommand.velocity_x(), protoCommand.velocity_y()), - .targetAngle = protoCommand.angle(), + .yaw = protoCommand.yaw(), .targetAngularVelocity = protoCommand.angular_velocity(), .useAngularVelocity = protoCommand.use_angular_velocity(), - .cameraAngleOfRobot = protoCommand.camera_angle_of_robot(), - .cameraAngleOfRobotIsSet = protoCommand.camera_angle_of_robot_is_set(), + .cameraYawOfRobot = protoCommand.camera_yaw_of_robot(), + .cameraYawOfRobotIsSet = protoCommand.camera_yaw_of_robot_is_set(), .kickSpeed = protoCommand.kick_speed(), .waitForBall = protoCommand.wait_for_ball(), .kickType = protoToKickType(protoCommand.kick_type()), - .kickAtAngle = protoCommand.kick_at_angle(), + .kickAtYaw = protoCommand.kick_at_yaw(), - .dribblerSpeed = protoCommand.dribbler_speed(), - .ignorePacket = protoCommand.ignore_packet()}; + .dribblerOn = protoCommand.dribbler_on(), + .wheelsOff = protoCommand.wheels_off()}; robotCommands.push_back(robotCommand); } diff --git a/roboteam_networking/src/RobotFeedbackNetworker.cpp b/roboteam_networking/src/RobotFeedbackNetworker.cpp index 0fd8861d4..34584ae56 100644 --- a/roboteam_networking/src/RobotFeedbackNetworker.cpp +++ b/roboteam_networking/src/RobotFeedbackNetworker.cpp @@ -55,18 +55,14 @@ proto::RobotsFeedback feedbackToProto(const rtt::RobotsFeedback& robotsFeedback) auto protoRobot = protoFeedback.add_robots_feedback(); protoRobot->set_id(feedback.id); protoRobot->set_ball_sensor_sees_ball(feedback.ballSensorSeesBall); - protoRobot->set_ball_position(feedback.ballPosition); protoRobot->set_ball_sensor_is_working(feedback.ballSensorIsWorking); protoRobot->set_dribbler_sees_ball(feedback.dribblerSeesBall); protoRobot->set_estimated_velocity_x(feedback.velocity.x); protoRobot->set_estimated_velocity_y(feedback.velocity.y); - protoRobot->set_estimated_angle(feedback.angle.getValue()); + protoRobot->set_estimated_yaw(feedback.yaw.getValue()); protoRobot->set_xsens_is_calibrated(feedback.xSensIsCalibrated); protoRobot->set_capacitor_is_charged(feedback.capacitorIsCharged); - protoRobot->set_wheels_locked(feedback.wheelLocked); - protoRobot->set_wheels_braking(feedback.wheelBraking); protoRobot->set_battery_level(feedback.batteryLevel); - protoRobot->set_signal_strength(feedback.signalStrength); } return protoFeedback; @@ -80,17 +76,13 @@ rtt::RobotsFeedback protoFeedbackToRobotsFeedback(const proto::RobotsFeedback& p for (const auto& protoFeedback : protoFeedbacks.robots_feedback()) { rtt::RobotFeedback feedback = {.id = protoFeedback.id(), .ballSensorSeesBall = protoFeedback.ball_sensor_sees_ball(), - .ballPosition = protoFeedback.ball_position(), .ballSensorIsWorking = protoFeedback.ball_sensor_is_working(), .dribblerSeesBall = protoFeedback.dribbler_sees_ball(), .velocity = Vector2(protoFeedback.estimated_velocity_x(), protoFeedback.estimated_velocity_y()), - .angle = Angle(protoFeedback.estimated_angle()), + .yaw = Angle(protoFeedback.estimated_yaw()), .xSensIsCalibrated = protoFeedback.xsens_is_calibrated(), .capacitorIsCharged = protoFeedback.capacitor_is_charged(), - .wheelLocked = protoFeedback.wheels_locked(), - .wheelBraking = protoFeedback.wheels_braking(), - .batteryLevel = protoFeedback.battery_level(), - .signalStrength = protoFeedback.signal_strength()}; + .batteryLevel = protoFeedback.battery_level()}; robotsFeedback.feedback.push_back(feedback); } diff --git a/roboteam_observer/observer/include/observer/data/RobotParameters.h b/roboteam_observer/observer/include/observer/data/RobotParameters.h index 3200068fa..ae37523fe 100644 --- a/roboteam_observer/observer/include/observer/data/RobotParameters.h +++ b/roboteam_observer/observer/include/observer/data/RobotParameters.h @@ -6,7 +6,7 @@ class RobotParameters { public: RobotParameters(); - RobotParameters(double radius, double height, double frontWidth, double dribblerWidth, double angleOffset); + RobotParameters(double radius, double height, double frontWidth, double dribblerWidth, double yawOffset); explicit RobotParameters(const proto::RobotParameters& protoParams); [[nodiscard]] proto::RobotParameters toProto() const; static RobotParameters from_default(); @@ -17,7 +17,7 @@ class RobotParameters { double height; double frontWidth; double dribblerWidth; - double angleOffset; + double yawOffset; }; #endif // RTT_ROBOTPARAMETERS_H diff --git a/roboteam_observer/observer/include/observer/filters/vision/robot/CameraRobotFilter.h b/roboteam_observer/observer/include/observer/filters/vision/robot/CameraRobotFilter.h index 6f636e625..8ef8c42ba 100644 --- a/roboteam_observer/observer/include/observer/filters/vision/robot/CameraRobotFilter.h +++ b/roboteam_observer/observer/include/observer/filters/vision/robot/CameraRobotFilter.h @@ -31,7 +31,7 @@ class CameraRobotFilter : public CameraObjectFilter { private: void updatePreviousInfo(); PosVelFilter2D positionFilter; - RobotOrientationFilter angleFilter; + RobotOrientationFilter yawFilter; bool just_updated; // keeps track if the filter was just updated e.g. a observation was given to it // so that we can efficiently find filters which were not updated TeamRobotID robot; diff --git a/roboteam_observer/observer/include/observer/filters/vision/robot/FilteredRobot.h b/roboteam_observer/observer/include/observer/filters/vision/robot/FilteredRobot.h index 10280c260..a7b8d6da9 100644 --- a/roboteam_observer/observer/include/observer/filters/vision/robot/FilteredRobot.h +++ b/roboteam_observer/observer/include/observer/filters/vision/robot/FilteredRobot.h @@ -5,7 +5,7 @@ #include "RobotPos.h" struct FilteredRobot { - explicit FilteredRobot(TeamRobotID id, RobotPos position, RobotVel velocity, double health, double posUncertainty, double velocityUncertainty, double angleUncertainty, + explicit FilteredRobot(TeamRobotID id, RobotPos position, RobotVel velocity, double health, double posUncertainty, double velocityUncertainty, double yawUncertainty, double angularVelUncertainty) : id{id}, position{std::move(position)}, @@ -13,13 +13,13 @@ struct FilteredRobot { health{health}, posUncertainty{posUncertainty}, velocityUncertainty{velocityUncertainty}, - angleUncertainty{angleUncertainty}, + yawUncertainty{yawUncertainty}, angularVelUncertainty{angularVelUncertainty} {} [[nodiscard]] proto::WorldRobot asWorldRobot() const { proto::WorldRobot robot; robot.mutable_pos()->set_x(position.position.x()); robot.mutable_pos()->set_y(position.position.y()); - robot.set_angle(position.angle); + robot.set_yaw(position.yaw); robot.mutable_vel()->set_x(velocity.velocity.x()); robot.mutable_vel()->set_y(velocity.velocity.y()); robot.set_w(velocity.angularVelocity); @@ -32,7 +32,7 @@ struct FilteredRobot { double health; double posUncertainty; double velocityUncertainty; - double angleUncertainty; + double yawUncertainty; double angularVelUncertainty; }; diff --git a/roboteam_observer/observer/include/observer/filters/vision/robot/RobotOrientationFilter.h b/roboteam_observer/observer/include/observer/filters/vision/robot/RobotOrientationFilter.h index 8b63b8448..975a8115e 100644 --- a/roboteam_observer/observer/include/observer/filters/vision/robot/RobotOrientationFilter.h +++ b/roboteam_observer/observer/include/observer/filters/vision/robot/RobotOrientationFilter.h @@ -4,32 +4,32 @@ #include "observer/filters/vision/PosVelFilter1D.h" /** - * @brief A class which tracks robot angle; this is a 1 dimensional posvelFilter which applies mod 2pi, essentially + * @brief A class which tracks robot yaw; this is a 1 dimensional posvelFilter which applies mod 2pi, essentially */ class RobotOrientationFilter : public PosVelFilter1D { public: RobotOrientationFilter() : PosVelFilter1D() {} RobotOrientationFilter(const Eigen::Vector2d &initialState, const Eigen::Matrix2d &initialCovariance, double modelError, double measurementError, const Time &timeStamp); /** - * @param kalman update, making sure the angle is safe + * @param kalman update, making sure the yaw is safe */ void update(const double &position) override; /** - * @return get's the current robot angle + * @return get's the current robot yaw */ [[nodiscard]] double getPosition() const override; /** - * @brief Gets the angle estimate at the given time + * @brief Gets the yaw estimate at the given time * @param time - * @return the estimate of the angle at the given timm + * @return the estimate of the yaw at the given timm */ [[nodiscard]] double getPositionEstimate(const Time &time) const override; /** - * @brief projects the angle from any value x to the range [-pi,pi) - * @param angle - * @return the limited angle + * @brief projects the yaw from any value x to the range [-pi,pi) + * @param yaw + * @return the limited yaw */ - [[nodiscard]] static double limitAngle(double angle); + [[nodiscard]] static double limitAngle(double yaw); }; #endif // RTT_ROBOTEAM_OBSERVER_OBSERVER_SRC_FILTERS_VISION_ROBOT_ROBOTORIENTATIONFILTER_H_ diff --git a/roboteam_observer/observer/include/observer/filters/vision/robot/RobotPos.h b/roboteam_observer/observer/include/observer/filters/vision/robot/RobotPos.h index c4503a87b..09ef00cc5 100644 --- a/roboteam_observer/observer/include/observer/filters/vision/robot/RobotPos.h +++ b/roboteam_observer/observer/include/observer/filters/vision/robot/RobotPos.h @@ -10,9 +10,9 @@ class RobotPos { public: RobotPos() = default; - RobotPos(Eigen::Vector2d pos, double angle) : position{std::move(pos)}, angle{angle} {} + RobotPos(Eigen::Vector2d pos, double yaw) : position{std::move(pos)}, yaw{yaw} {} Eigen::Vector2d position; - rtt::Angle angle = 0.0; + rtt::Angle yaw = 0.0; }; class RobotVel { public: diff --git a/roboteam_observer/observer/src/data/RobotParameters.cpp b/roboteam_observer/observer/src/data/RobotParameters.cpp index 815a1ce33..078971312 100644 --- a/roboteam_observer/observer/src/data/RobotParameters.cpp +++ b/roboteam_observer/observer/src/data/RobotParameters.cpp @@ -17,7 +17,7 @@ proto::RobotParameters RobotParameters::toProto() const { protoMsg.set_height(height); protoMsg.set_front_width(frontWidth); protoMsg.set_dribbler_width(dribblerWidth); - protoMsg.set_angle_offset(angleOffset); + protoMsg.set_yaw_offset(yawOffset); return protoMsg; } @@ -26,10 +26,10 @@ RobotParameters::RobotParameters(const proto::RobotParameters &protoParams) height{protoParams.height()}, frontWidth{protoParams.front_width()}, dribblerWidth{protoParams.dribbler_width()}, - angleOffset{protoParams.angle_offset()} {} + yawOffset{protoParams.yaw_offset()} {} // TODO fix correct values -RobotParameters::RobotParameters() : radius{0.09}, height{0.15}, frontWidth{0.1}, dribblerWidth{0.1}, angleOffset{0.0} {} +RobotParameters::RobotParameters() : radius{0.09}, height{0.15}, frontWidth{0.1}, dribblerWidth{0.1}, yawOffset{0.0} {} -RobotParameters::RobotParameters(double radius, double height, double frontWidth, double dribblerWidth, double angleOffset) - : radius{radius}, height{height}, frontWidth{frontWidth}, dribblerWidth{dribblerWidth}, angleOffset{angleOffset} {} +RobotParameters::RobotParameters(double radius, double height, double frontWidth, double dribblerWidth, double yawOffset) + : radius{radius}, height{height}, frontWidth{frontWidth}, dribblerWidth{dribblerWidth}, yawOffset{yawOffset} {} diff --git a/roboteam_observer/observer/src/filters/vision/RobotFeedbackFilter.cpp b/roboteam_observer/observer/src/filters/vision/RobotFeedbackFilter.cpp index f716503ef..431636add 100644 --- a/roboteam_observer/observer/src/filters/vision/RobotFeedbackFilter.cpp +++ b/roboteam_observer/observer/src/filters/vision/RobotFeedbackFilter.cpp @@ -36,26 +36,11 @@ void SingleRobotFeedbackFilter::process(const rtt::RobotFeedback& feedback) { st proto::RobotProcessedFeedback SingleRobotFeedbackFilter::getFilteredFeedback() const { proto::RobotProcessedFeedback feedback; feedback.set_ball_sensor_sees_ball(storedFeedback.ballSensorSeesBall); - feedback.set_ball_position(storedFeedback.ballPosition); feedback.set_ball_sensor_is_working(storedFeedback.ballSensorIsWorking); feedback.set_dribbler_sees_ball(storedFeedback.dribblerSeesBall); feedback.set_battery_level(storedFeedback.batteryLevel); feedback.set_xsens_is_calibrated(storedFeedback.xSensIsCalibrated); - feedback.set_signal_strength(storedFeedback.signalStrength); feedback.set_capacitor_is_charged(storedFeedback.capacitorIsCharged); - // TODO: wheel ordering? which bit corresponds to which wheel? - feedback.mutable_wheelinformation()->mutable_rightfront()->set_braking(storedFeedback.wheelBraking & 1); - feedback.mutable_wheelinformation()->mutable_rightfront()->set_locked(storedFeedback.wheelLocked & 1); - - feedback.mutable_wheelinformation()->mutable_rightback()->set_braking(storedFeedback.wheelBraking & 2); - feedback.mutable_wheelinformation()->mutable_rightback()->set_locked(storedFeedback.wheelLocked & 2); - - feedback.mutable_wheelinformation()->mutable_leftback()->set_braking(storedFeedback.wheelBraking & 4); - feedback.mutable_wheelinformation()->mutable_leftback()->set_locked(storedFeedback.wheelLocked & 4); - - feedback.mutable_wheelinformation()->mutable_leftfront()->set_braking(storedFeedback.wheelBraking & 8); - feedback.mutable_wheelinformation()->mutable_leftfront()->set_locked(storedFeedback.wheelLocked & 8); - return feedback; } diff --git a/roboteam_observer/observer/src/filters/vision/robot/CameraRobotFilter.cpp b/roboteam_observer/observer/src/filters/vision/robot/CameraRobotFilter.cpp index b8ebee4bc..a7c6ca33e 100644 --- a/roboteam_observer/observer/src/filters/vision/robot/CameraRobotFilter.cpp +++ b/roboteam_observer/observer/src/filters/vision/robot/CameraRobotFilter.cpp @@ -28,7 +28,7 @@ CameraRobotFilter::CameraRobotFilter(const RobotObservation &observation, RobotV Eigen::Matrix2d initialAngleCov = Eigen::Matrix2d::Zero(); initialAngleCov(0, 0) = ROBOT_ANGLE_INITIAL_COV; initialAngleCov(1, 1) = ROBOT_ANGULAR_VEL_INITIAL_COV; - angleFilter = RobotOrientationFilter(initialAngle, initialAngleCov, ROBOT_ANGLE_MODEL_ERROR, ROBOT_ANGLE_MEASUREMENT_ERROR, observation.timeCaptured); + yawFilter = RobotOrientationFilter(initialAngle, initialAngleCov, ROBOT_ANGLE_MODEL_ERROR, ROBOT_ANGLE_MEASUREMENT_ERROR, observation.timeCaptured); previousPosition = RobotPos(observation.position, rtt::Angle(observation.orientation)); @@ -40,7 +40,7 @@ CameraRobotFilter::CameraRobotFilter(const RobotObservation &observation, RobotV void CameraRobotFilter::predict(Time time) { updatePreviousInfo(); positionFilter.predict(time); - angleFilter.predict(time); + yawFilter.predict(time); just_updated = false; } @@ -49,8 +49,8 @@ void CameraRobotFilter::update(const RobotObservation &observation) { assert(observation.cameraID == cameraID); // Update position kalman filter positionFilter.update(observation.position); - // Update angle kalman filter - angleFilter.update(observation.orientation); + // Update yaw kalman filter + yawFilter.update(observation.orientation); // update object seen settings objectSeen(observation.timeCaptured); just_updated = true; @@ -64,26 +64,26 @@ bool CameraRobotFilter::updateRobotNotSeen(const Time &time) { bool CameraRobotFilter::justUpdated() const { return just_updated; } FilteredRobot CameraRobotFilter::estimate(const Time &time) const { - FilteredRobot bot(robot, RobotPos(positionFilter.getPositionEstimate(time), angleFilter.getPositionEstimate(time)), - RobotVel(positionFilter.getVelocity(), angleFilter.getVelocity()), getHealth(), positionFilter.getPositionUncertainty().norm(), - positionFilter.getVelocityUncertainty().norm(), angleFilter.getPositionUncertainty(), angleFilter.getVelocityUncertainty()); + FilteredRobot bot(robot, RobotPos(positionFilter.getPositionEstimate(time), yawFilter.getPositionEstimate(time)), + RobotVel(positionFilter.getVelocity(), yawFilter.getVelocity()), getHealth(), positionFilter.getPositionUncertainty().norm(), + positionFilter.getVelocityUncertainty().norm(), yawFilter.getPositionUncertainty(), yawFilter.getVelocityUncertainty()); return bot; } bool CameraRobotFilter::acceptObservation(const RobotObservation &observation) const { - double angleDif = abs(rtt::Angle(angleFilter.getPosition() - observation.orientation)); + double yawDif = abs(rtt::Angle(yawFilter.getPosition() - observation.orientation)); double posDifSq = (observation.position - positionFilter.getPosition()).squaredNorm(); - return posDifSq < 0.4 * 0.4 && angleDif < M_PI_2; // TODO: remove hardcoded constants + return posDifSq < 0.4 * 0.4 && yawDif < M_PI_2; // TODO: remove hardcoded constants } RobotVel CameraRobotFilter::velocityEstimate() const { Eigen::Vector2d vel = positionFilter.getVelocity(); - double angVel = angleFilter.getVelocity(); + double angVel = yawFilter.getVelocity(); return RobotVel(vel, angVel); } void CameraRobotFilter::updatePreviousInfo() { - previousPosition = RobotPos(positionFilter.getPosition(), angleFilter.getPosition()); + previousPosition = RobotPos(positionFilter.getPosition(), yawFilter.getPosition()); previousTime = positionFilter.lastUpdated(); } \ No newline at end of file diff --git a/roboteam_observer/observer/src/filters/vision/robot/RobotFilter.cpp b/roboteam_observer/observer/src/filters/vision/robot/RobotFilter.cpp index 2d55a9ed7..cf20a7438 100644 --- a/roboteam_observer/observer/src/filters/vision/robot/RobotFilter.cpp +++ b/roboteam_observer/observer/src/filters/vision/robot/RobotFilter.cpp @@ -62,14 +62,14 @@ FilteredRobot RobotFilter::mergeRobots(const Time &time) const { double mergeFactor = 1.5; Eigen::Vector2d vel(0, 0); Eigen::Vector2d pos(0, 0); - double angle = 0; + double yaw = 0; double angularVel = 0; double totalPosUncertainty = 0; double totalVelUncertainty = 0; double totalAngleUncertainty = 0; double totalAngleVelUncertainty = 0; // We cannot take averages of angular coordinates easily, so we take the averages of the offsets (this works) - double angleOffset = cameraFilters.begin()->second.estimate(time).position.angle; + double yawOffset = cameraFilters.begin()->second.estimate(time).position.yaw; // TODO: consider more fancy merging using covariance matrices, which is not reliant on the health information for (const auto &filter : cameraFilters) { @@ -79,25 +79,25 @@ FilteredRobot RobotFilter::mergeRobots(const Time &time) const { double weight = 100.0 / health; // TODO: call MAXIMUM here from object double posWeight = pow(robot.posUncertainty * weight, -mergeFactor); double velWeight = pow(robot.velocityUncertainty * weight, -mergeFactor); - double angleWeight = pow(robot.angleUncertainty * weight, -mergeFactor); - double angleVelWeight = pow(robot.angularVelUncertainty * weight, -mergeFactor); + double yawWeight = pow(robot.yawUncertainty * weight, -mergeFactor); + double yawVelWeight = pow(robot.angularVelUncertainty * weight, -mergeFactor); pos += robot.position.position * posWeight; vel += robot.velocity.velocity * velWeight; - angle += double(robot.position.angle - rtt::Angle(angleOffset)) * angleWeight; - angularVel += robot.velocity.angularVelocity * angleVelWeight; + yaw += double(robot.position.yaw - rtt::Angle(yawOffset)) * yawWeight; + angularVel += robot.velocity.angularVelocity * yawVelWeight; totalPosUncertainty += posWeight; totalVelUncertainty += velWeight; - totalAngleUncertainty += angleWeight; - totalAngleVelUncertainty += angleVelWeight; + totalAngleUncertainty += yawWeight; + totalAngleVelUncertainty += yawVelWeight; } pos /= totalPosUncertainty; vel /= totalVelUncertainty; - angle /= totalAngleUncertainty; + yaw /= totalAngleUncertainty; angularVel /= totalAngleVelUncertainty; - angle += angleOffset; - FilteredRobot result(id, RobotPos(pos, angle), RobotVel(vel, angularVel), -1, -1, -1, -1, -1); // TODO define health and merged uncertainties? + yaw += yawOffset; + FilteredRobot result(id, RobotPos(pos, yaw), RobotVel(vel, angularVel), -1, -1, -1, -1, -1); // TODO define health and merged uncertainties? return result; } diff --git a/roboteam_observer/observer/src/filters/vision/robot/RobotOrientationFilter.cpp b/roboteam_observer/observer/src/filters/vision/robot/RobotOrientationFilter.cpp index 1616e52f5..ddfce0dd2 100644 --- a/roboteam_observer/observer/src/filters/vision/robot/RobotOrientationFilter.cpp +++ b/roboteam_observer/observer/src/filters/vision/robot/RobotOrientationFilter.cpp @@ -3,12 +3,12 @@ RobotOrientationFilter::RobotOrientationFilter(const Eigen::Vector2d &initialSta const Time &timeStamp) : PosVelFilter1D(initialState, initialCovariance, modelError, measurementError, timeStamp) {} -double RobotOrientationFilter::limitAngle(double angle) { - angle += M_PI; - angle = fmod(angle, 2 * M_PI); - angle -= M_PI; +double RobotOrientationFilter::limitAngle(double yaw) { + yaw += M_PI; + yaw = fmod(yaw, 2 * M_PI); + yaw -= M_PI; - return angle; + return yaw; } void RobotOrientationFilter::update(const double &position) { diff --git a/roboteam_robothub/REMParser.py b/roboteam_robothub/REMParser.py index 607840cc1..74690a0cd 100644 --- a/roboteam_robothub/REMParser.py +++ b/roboteam_robothub/REMParser.py @@ -72,20 +72,20 @@ def process(self, parse_file=False): # raise Exception(f"[REMParser][process] Error! Received invalid packet type {packet_type}!") continue - # Make sure that at least the entire default REM_Packet header is in the buffer + # Make sure that at least the entire default REM_Packet packetType is in the buffer # This is need to call functions such as get_remVersion()and get_payloadSize() if len(self.byte_buffer) < BaseTypes.REM_PACKET_SIZE_REM_PACKET: if DEBUG: print(f"- Complete REM_Packet not yet in buffer. {len(self.byte_buffer)}/{BaseTypes.REM_PACKET_SIZE_REM_PACKET} bytes") break - # At least the REM_Packet headers are in the buffer. Decode it + # At least the REM_Packet packetTypes are in the buffer. Decode it packet = REM_Packet() packet.decode(self.byte_buffer[:BaseTypes.REM_PACKET_SIZE_REM_PACKET]) # Get the expected packet size as expected by REM - rem_packet_size = BaseTypes.REM_PACKET_TYPE_TO_SIZE(packet.header) + rem_packet_size = BaseTypes.REM_PACKET_TYPE_TO_SIZE(packet.packetType) - if DEBUG: print(f"- type={packet.header} ({BaseTypes.REM_PACKET_TYPE_TO_OBJ(packet.header).__name__}), size={packet.payloadSize}, REM_size={rem_packet_size}") + if DEBUG: print(f"- type={packet.packetType} ({BaseTypes.REM_PACKET_TYPE_TO_OBJ(packet.packetType).__name__}), size={packet.payloadSize}, REM_size={rem_packet_size}") # Ensure that the entire payload is in the byte buffer if len(self.byte_buffer) < packet.payloadSize: @@ -93,7 +93,7 @@ def process(self, parse_file=False): break # if not REM_log, packet->payloadSize should be equal to expected REM_PACKET_SIZE - if packet.header != BaseTypes.REM_PACKET_TYPE_REM_LOG: + if packet.packetType != BaseTypes.REM_PACKET_TYPE_REM_LOG: if packet.payloadSize != rem_packet_size: self.byte_buffer = bytes() # raise Exception(f"[REMParser][process] Error! REM_Packet->payloadSize={packet.payloadSize} does not equal expected REM_PACKET_SIZE_*={rem_packet_size}! ") @@ -106,8 +106,8 @@ def process(self, parse_file=False): # Decode the packet packet.decode(packet_bytes) - if packet.header == BaseTypes.REM_PACKET_TYPE_REM_LOG: - # Get the message from the buffer. The message is everything after the REM_Packet header + if packet.packetType == BaseTypes.REM_PACKET_TYPE_REM_LOG: + # Get the message from the buffer. The message is everything after the REM_Packet packetType message = packet_bytes[BaseTypes.REM_PACKET_SIZE_REM_LOG:] # Convert bytes into string, and store in REM_Log object packet.message = message.decode() @@ -209,8 +209,8 @@ def parseFile(self, filepath, print_statistics=True): # CSV output_file_csv = f"{output_file_no_ext}_{type_str}.csv" with open(output_file_csv, 'w') as file: - header = ",".join(list(packets[0].keys())) - file.write(header + "\n") + packetType = ",".join(list(packets[0].keys())) + file.write(packetType + "\n") for packet in packets: values = list(packet.values()) string = ",".join([str(v) for v in values]) diff --git a/roboteam_robothub/RobotCommands_pb2.py b/roboteam_robothub/RobotCommands_pb2.py index 7ae8ad3e8..0411d5b1a 100644 --- a/roboteam_robothub/RobotCommands_pb2.py +++ b/roboteam_robothub/RobotCommands_pb2.py @@ -14,7 +14,7 @@ -DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x13RobotCommands.proto\x12\x05proto\"\x9d\x03\n\x0cRobotCommand\x12\n\n\x02id\x18\x01 \x01(\x05\x12\x12\n\nvelocity_x\x18\x02 \x01(\x01\x12\x12\n\nvelocity_y\x18\x03 \x01(\x01\x12\r\n\x05\x61ngle\x18\x04 \x01(\x01\x12\x18\n\x10\x61ngular_velocity\x18\x05 \x01(\x01\x12\x1c\n\x14use_angular_velocity\x18\x06 \x01(\x08\x12\x1d\n\x15\x63\x61mera_angle_of_robot\x18\x07 \x01(\x01\x12$\n\x1c\x63\x61mera_angle_of_robot_is_set\x18\x08 \x01(\x08\x12\x12\n\nkick_speed\x18\t \x01(\x01\x12\x15\n\rwait_for_ball\x18\n \x01(\x08\x12\x15\n\rkick_at_angle\x18\x0b \x01(\x08\x12/\n\tkick_type\x18\x0c \x01(\x0e\x32\x1c.proto.RobotCommand.KickType\x12\x16\n\x0e\x64ribbler_speed\x18\r \x01(\x01\x12\x15\n\rignore_packet\x18\x0e \x01(\x08\"+\n\x08KickType\x12\x0b\n\x07NO_KICK\x10\x00\x12\x08\n\x04KICK\x10\x01\x12\x08\n\x04\x43HIP\x10\x02\"<\n\rRobotCommands\x12+\n\x0erobot_commands\x18\x01 \x03(\x0b\x32\x13.proto.RobotCommandb\x06proto3') +DESCRIPTOR = _descriptor_pool.Default().AddSerializedFile(b'\n\x13RobotCommands.proto\x12\x05proto\"\x9d\x03\n\x0cRobotCommand\x12\n\n\x02id\x18\x01 \x01(\x05\x12\x12\n\nvelocity_x\x18\x02 \x01(\x01\x12\x12\n\nvelocity_y\x18\x03 \x01(\x01\x12\r\n\x05\x61ngle\x18\x04 \x01(\x01\x12\x18\n\x10\x61ngular_velocity\x18\x05 \x01(\x01\x12\x1c\n\x14use_angular_velocity\x18\x06 \x01(\x08\x12\x1d\n\x15\x63\x61mera_angle_of_robot\x18\x07 \x01(\x01\x12$\n\x1c\x63\x61mera_angle_of_robot_is_set\x18\x08 \x01(\x08\x12\x12\n\nkick_speed\x18\t \x01(\x01\x12\x15\n\rwait_for_ball\x18\n \x01(\x08\x12\x15\n\rkick_at_angle\x18\x0b \x01(\x08\x12/\n\tkick_type\x18\x0c \x01(\x0e\x32\x1c.proto.RobotCommand.KickType\x12\x16\n\x0e\x64ribbler_speed\x18\r \x01(\x01\x12\x15\n\rwheels_off\x18\x0e \x01(\x08\"+\n\x08KickType\x12\x0b\n\x07NO_KICK\x10\x00\x12\x08\n\x04KICK\x10\x01\x12\x08\n\x04\x43HIP\x10\x02\"<\n\rRobotCommands\x12+\n\x0erobot_commands\x18\x01 \x03(\x0b\x32\x13.proto.RobotCommandb\x06proto3') diff --git a/roboteam_robothub/include/simulation/RobotControlCommand.hpp b/roboteam_robothub/include/simulation/RobotControlCommand.hpp index ae75abc25..b442d7650 100644 --- a/roboteam_robothub/include/simulation/RobotControlCommand.hpp +++ b/roboteam_robothub/include/simulation/RobotControlCommand.hpp @@ -10,10 +10,10 @@ namespace rtt::robothub::simulation { speeds relative to the field. */ class RobotControlCommand { public: - void addRobotControlWithWheelSpeeds(int robotId, float kickSpeed, float kickAngle, float dribblerSpeed, float frontRightWheelVelocity, float backRightWheelVelocity, + void addRobotControlWithWheelSpeeds(int robotId, float kickSpeed, float kickAngle, float dribblerOn, float frontRightWheelVelocity, float backRightWheelVelocity, float backLeftWheelVelocity, float frontLeftWheelVelocity); - void addRobotControlWithLocalSpeeds(int robotId, float kickSpeed, float kickAngle, float dribblerSpeed, float forwardVelocity, float leftVelocity, float angularVelocity); - void addRobotControlWithGlobalSpeeds(int robotId, float kickSpeed, float kickAngle, float dribblerSpeed, float xVelocity, float yVelocity, float angularVelocity); + void addRobotControlWithLocalSpeeds(int robotId, float kickSpeed, float kickAngle, float dribblerOn, float forwardVelocity, float leftVelocity, float angularVelocity); + void addRobotControlWithGlobalSpeeds(int robotId, float kickSpeed, float kickAngle, float dribblerOn, float xVelocity, float yVelocity, float angularVelocity); proto::simulation::RobotControl& getPacket(); private: diff --git a/roboteam_robothub/roboteam_embedded_messages b/roboteam_robothub/roboteam_embedded_messages index c1874134d..169668f96 160000 --- a/roboteam_robothub/roboteam_embedded_messages +++ b/roboteam_robothub/roboteam_embedded_messages @@ -1 +1 @@ -Subproject commit c1874134df942ddce27c86d80ed2fefa2cb3641c +Subproject commit 169668f96aa6b3eef4c4409bc947110956d7ae0a diff --git a/roboteam_robothub/robothub.py b/roboteam_robothub/robothub.py index 8338cd7b1..b9983b446 100644 --- a/roboteam_robothub/robothub.py +++ b/roboteam_robothub/robothub.py @@ -39,13 +39,13 @@ def handleREM_LOG(rem_log): time.sleep(2) cmd_blue = REM_RobotCommand() -cmd_blue.header = BaseTypes.REM_PACKET_TYPE_REM_ROBOT_COMMAND +cmd_blue.packetType = BaseTypes.REM_PACKET_TYPE_REM_ROBOT_COMMAND cmd_blue.fromPC = True cmd_blue.remVersion = BaseTypes.REM_LOCAL_VERSION cmd_blue.payloadSize = BaseTypes.REM_PACKET_SIZE_REM_ROBOT_COMMAND cmd_yellow = REM_RobotCommand() -cmd_yellow.header = BaseTypes.REM_PACKET_TYPE_REM_ROBOT_COMMAND +cmd_yellow.packetType = BaseTypes.REM_PACKET_TYPE_REM_ROBOT_COMMAND cmd_yellow.fromPC = True cmd_yellow.remVersion = BaseTypes.REM_LOCAL_VERSION cmd_yellow.payloadSize = BaseTypes.REM_PACKET_SIZE_REM_ROBOT_COMMAND @@ -116,18 +116,18 @@ def thread_listen_to_commands(arg): cmd.toColor = 0 if arg['name'] == 'Yellow' else 1 cmd.rho = min(rho, 4) cmd.theta = -theta - cmd.angle = proto_command.angle + cmd.yaw = proto_command.yaw cmd.angularVelocity = proto_command.angular_velocity - cmd.cameraAngle = proto_command.camera_angle_of_robot - cmd.useCameraAngle = proto_command.camera_angle_of_robot_is_set - cmd.useAbsoluteAngle = proto_command.camera_angle_of_robot_is_set - cmd.dribbler = proto_command.dribbler_speed + cmd.cameraYaw = proto_command.camera_yaw_of_robot + cmd.useCameraYaw = proto_command.camera_yaw_of_robot_is_set + cmd.useYaw = proto_command.camera_yaw_of_robot_is_set + cmd.dribblerOn = proto_command.dribbler_on cmd.doKick = proto_command.kick_type != 0#RobotCommand.KickType.KICK # cmd.doChip = proto_command.kick_type == RobotCommand.KickType.CHIP - cmd.kickAtAngle = proto_command.kick_at_angle + cmd.kickAtYaw = proto_command.kick_at_yaw cmd.kickChipPower = 6#proto_command.kick_speed cmd.doForce = True#proto_command.wait_for_ball - cmd.feedback = proto_command.ignore_packet + cmd.feedback = proto_command.wheels_off command_queue.put(cmd.encode()) diff --git a/roboteam_robothub/scripts/RobotControlScript.cpp b/roboteam_robothub/scripts/RobotControlScript.cpp index 0ac21250a..f11f917a6 100644 --- a/roboteam_robothub/scripts/RobotControlScript.cpp +++ b/roboteam_robothub/scripts/RobotControlScript.cpp @@ -11,7 +11,6 @@ using namespace rtt::net; constexpr int MAX_AMOUNT_OF_ROBOTS = 16; constexpr float MAX_ANGULAR_VELOCITY = 2.0f; -constexpr float MAX_DRIBBLER_SPEED = 100; constexpr float MAX_VELOCITY = 1.0f; constexpr int COMMAND_TRANSMISSION_INTERVAL_MS = 100; constexpr int SETTINGS_TRANSMISSION_INTERVAL_MS = 1000; @@ -46,7 +45,7 @@ Movement currentMovement = Movement::STILL; int targetRobotID = 0; bool targetAllRobotIDs = false; rtt::Vector2 targetVelocity(0, 0); -rtt::Angle targetAngle(0.0); +rtt::Angle yaw(0.0); double targetAngularVelocity = 0.0; bool useDribbler = false; bool useAngularVelocity = false; @@ -57,13 +56,13 @@ void updateCommandValues() { auto timeSinceLastCommand = static_cast(timeSinceLastCommandMS) / 1000; if (currentRotation == Rotation::LEFT_ROTATION) { - targetAngle = rtt::Angle(timeSinceLastCommand * MAX_ANGULAR_VELOCITY); + yaw = rtt::Angle(timeSinceLastCommand * MAX_ANGULAR_VELOCITY); targetAngularVelocity = MAX_ANGULAR_VELOCITY; } else if (currentRotation == Rotation::RIGHT_ROTATION) { - targetAngle = rtt::Angle(timeSinceLastCommand * MAX_ANGULAR_VELOCITY * -1); + yaw = rtt::Angle(timeSinceLastCommand * MAX_ANGULAR_VELOCITY * -1); targetAngularVelocity = -MAX_ANGULAR_VELOCITY; } else { - targetAngle = rtt::Angle(0.0); + yaw = rtt::Angle(0.0); targetAngularVelocity = 0.0; } @@ -88,20 +87,20 @@ void updateCommandValues() { rtt::RobotCommand createCommandForRobot(int id) { rtt::RobotCommand cmd = {.id = id, .velocity = targetVelocity, - .targetAngle = targetAngle, + .yaw = yaw, .targetAngularVelocity = targetAngularVelocity, .useAngularVelocity = useAngularVelocity, - .cameraAngleOfRobot = 0.0, - .cameraAngleOfRobotIsSet = false, + .cameraYawOfRobot = 0.0, + .cameraYawOfRobotIsSet = false, .kickSpeed = 0.0, .waitForBall = false, .kickType = rtt::KickType::NO_KICK, - .dribblerSpeed = useDribbler ? MAX_DRIBBLER_SPEED : 0.0f, + .dribblerOn = useDribbler, - .ignorePacket = false}; + .wheelsOff = false}; return cmd; } @@ -322,7 +321,7 @@ std::string currentMovementToString() { } } std::string currentRotationToString() { - std::string method = useAngularVelocity ? "in angular velocity" : "in absolute angles"; + std::string method = useAngularVelocity ? "in angular velocity" : "in absolute yaws"; switch (currentRotation) { case Rotation::NO_ROTATION: diff --git a/roboteam_robothub/src/RobotHub.cpp b/roboteam_robothub/src/RobotHub.cpp index cde601772..ab5914f8e 100644 --- a/roboteam_robothub/src/RobotHub.cpp +++ b/roboteam_robothub/src/RobotHub.cpp @@ -91,15 +91,15 @@ void RobotHub::sendCommandsToSimulator(const rtt::RobotCommands &commands, rtt:: int id = robotCommand.id; auto kickSpeed = static_cast(robotCommand.kickSpeed); float kickAngle = robotCommand.kickType == rtt::KickType::CHIP ? SIM_CHIPPER_ANGLE_DEGREES : 0.0f; - float dribblerSpeed = static_cast(robotCommand.dribblerSpeed) * SIM_MAX_DRIBBLER_SPEED_RPM; // dribblerSpeed is range of 0 to 1 + float dribblerSpeed = static_cast(robotCommand.dribblerOn) * SIM_MAX_DRIBBLER_SPEED_RPM; // dribblerOn is range of 0 to 1 auto angularVelocity = static_cast(robotCommand.targetAngularVelocity); if (!robotCommand.useAngularVelocity) { - RTT_WARNING("Robot command used absolute angle, but simulator requires angular velocity") + RTT_WARNING("Robot command used absolute yaw, but simulator requires angular velocity") } /* addRobotControlWithLocalSpeeds works with both grSim and ER-Force sim, while addRobotControlWithGlobalSpeeds only works with grSim*/ - auto relativeVelocity = robotCommand.velocity.rotate(-robotCommand.cameraAngleOfRobot); + auto relativeVelocity = robotCommand.velocity.rotate(-robotCommand.cameraYawOfRobot); auto forward = relativeVelocity.x; auto left = relativeVelocity.y; simCommand.addRobotControlWithLocalSpeeds(id, kickSpeed, kickAngle, dribblerSpeed, forward, left, angularVelocity); @@ -135,38 +135,39 @@ void RobotHub::sendCommandsToBasestation(const rtt::RobotCommands &commands, rtt // Convert the RobotCommand to a command for the basestation REM_RobotCommand command = {}; - command.header = REM_PACKET_TYPE_REM_ROBOT_COMMAND; + command.packetType = REM_PACKET_TYPE_REM_ROBOT_COMMAND; command.toRobotId = robotCommand.id; command.toColor = color == rtt::Team::BLUE; command.fromPC = true; command.remVersion = REM_LOCAL_VERSION; // command.messageId = 0; TODO implement incrementing message id command.payloadSize = REM_PACKET_SIZE_REM_ROBOT_COMMAND; - command.timestamp = static_cast(std::chrono::duration_cast(std::chrono::system_clock::now().time_since_epoch()).count() / 10); + command.timestamp = static_cast(std::chrono::duration_cast(std::chrono::system_clock::now().time_since_epoch()).count()); - command.kickAtAngle = robotCommand.kickAtAngle; + command.kickAtYaw = robotCommand.kickAtYaw; command.doKick = robotCommand.kickSpeed > 0.0 && robotCommand.kickType == KickType::KICK; command.doChip = robotCommand.kickSpeed > 0.0 && robotCommand.kickType == KickType::CHIP; command.doForce = !robotCommand.waitForBall; command.kickChipPower = static_cast(robotCommand.kickSpeed); - command.dribbler = static_cast(robotCommand.dribblerSpeed); + // command.dribblerOn = static_cast(robotCommand.dribblerOn); + command.dribblerOn = robotCommand.dribblerOn; command.rho = static_cast(robotCommand.velocity.length()); - command.theta = -1.0f * static_cast(robotCommand.velocity.angle()); + command.theta = static_cast(robotCommand.velocity.angle()); - command.useAbsoluteAngle = !robotCommand.useAngularVelocity; - command.angle = static_cast(robotCommand.targetAngle.getValue()); + command.useYaw = !robotCommand.useAngularVelocity; + command.yaw = static_cast(robotCommand.yaw.getValue()); command.angularVelocity = static_cast(robotCommand.targetAngularVelocity); - command.useCameraAngle = robotCommand.cameraAngleOfRobotIsSet; - command.cameraAngle = command.useCameraAngle ? static_cast(robotCommand.cameraAngleOfRobot) : 0.0f; + command.useCameraYaw = robotCommand.cameraYawOfRobotIsSet; + command.cameraYaw = command.useCameraYaw ? static_cast(robotCommand.cameraYawOfRobot) : 0.0f; - command.feedback = robotCommand.ignorePacket; + command.wheelsOff = robotCommand.wheelsOff; // command.rho = 0; // command.theta = 0; // command.angularVelocity = 1; - // command.useAbsoluteAngle = 0; + // command.useYaw = 0; int bytesSent = 0; { @@ -240,17 +241,13 @@ void RobotHub::handleRobotFeedbackFromSimulator(const simulation::RobotControlFe for (auto const &[robotId, hasBall] : feedback.robotIdHasBall) { rtt::RobotFeedback robotFeedback = {.id = robotId, .ballSensorSeesBall = hasBall, - .ballPosition = 0, .ballSensorIsWorking = true, .dribblerSeesBall = hasBall, .velocity = {0, 0}, - .angle = 0, + .yaw = 0, .xSensIsCalibrated = true, .capacitorIsCharged = true, - .wheelLocked = 0, - .wheelBraking = 0, - .batteryLevel = 23.0f, - .signalStrength = 0}; + .batteryLevel = 23.0f}; robotsFeedback.feedback.push_back(robotFeedback); // Increment the feedback counter of this robot @@ -270,17 +267,13 @@ void RobotHub::handleRobotFeedbackFromBasestation(const REM_RobotFeedback &feedb rtt::RobotFeedback robotFeedback = {.id = static_cast(feedback.fromRobotId), .ballSensorSeesBall = feedback.ballSensorSeesBall, - .ballPosition = feedback.ballPos, .ballSensorIsWorking = feedback.ballSensorWorking, .dribblerSeesBall = feedback.dribblerSeesBall, .velocity = Vector2(Angle(feedback.theta), feedback.rho), - .angle = Angle(feedback.angle), + .yaw = Angle(feedback.yaw), .xSensIsCalibrated = feedback.XsensCalibrated, .capacitorIsCharged = feedback.capacitorCharged, - .wheelLocked = static_cast(feedback.wheelLocked), - .wheelBraking = static_cast(feedback.wheelBraking), - .batteryLevel = static_cast(feedback.batteryLevel), - .signalStrength = static_cast(feedback.rssi)}; + .batteryLevel = static_cast(feedback.batteryLevel)}; robotsFeedback.feedback.push_back(robotFeedback); this->sendRobotFeedback(robotsFeedback); diff --git a/roboteam_robothub/src/RobotHubLogger.cpp b/roboteam_robothub/src/RobotHubLogger.cpp index 44acd355f..ebc49dc6f 100644 --- a/roboteam_robothub/src/RobotHubLogger.cpp +++ b/roboteam_robothub/src/RobotHubLogger.cpp @@ -43,7 +43,7 @@ void RobotHubLogger::write(uint8_t* byte_buffer, uint32_t size, uint64_t timesta rtt::RobotHubLogger logger("logfile.rembin"); REM_Packet packet; - packet.header = REM_PACKET_TYPE_REM_PACKET; + packet.packetType = REM_PACKET_TYPE_REM_PACKET; packet.fromPC = 1; packet.toPC = 1; packet.remVersion = REM_LOCAL_VERSION; @@ -54,7 +54,7 @@ void RobotHubLogger::write(uint8_t* byte_buffer, uint32_t size, uint64_t timesta logger.writeREM(&payload); REM_RobotCommand command; - command.header = REM_PACKET_TYPE_REM_ROBOT_COMMAND; + command.packetType = REM_PACKET_TYPE_REM_ROBOT_COMMAND; command.fromPC = 1; command.toPC = 1; command.remVersion = REM_LOCAL_VERSION; @@ -64,7 +64,7 @@ void RobotHubLogger::write(uint8_t* byte_buffer, uint32_t size, uint64_t timesta encodeREM_RobotCommand(&commandPayload, &command); REM_RobotFeedback feedback; - feedback.header = REM_PACKET_TYPE_REM_ROBOT_FEEDBACK; + feedback.packetType = REM_PACKET_TYPE_REM_ROBOT_FEEDBACK; feedback.fromPC = 1; feedback.toPC = 1; feedback.remVersion = REM_LOCAL_VERSION; diff --git a/roboteam_robothub/src/basestation/BasestationCollection.cpp b/roboteam_robothub/src/basestation/BasestationCollection.cpp index 2d1171705..56133529a 100644 --- a/roboteam_robothub/src/basestation/BasestationCollection.cpp +++ b/roboteam_robothub/src/basestation/BasestationCollection.cpp @@ -235,7 +235,7 @@ void BasestationCollection::updateBasestationSelection() { void BasestationCollection::askChannelOfBasestationsWithUnknownChannel() const { // Create the channel request message REM_BasestationGetConfiguration getConfigurationMessage = {0}; - getConfigurationMessage.header = REM_PACKET_TYPE_REM_BASESTATION_GET_CONFIGURATION; + getConfigurationMessage.packetType = REM_PACKET_TYPE_REM_BASESTATION_GET_CONFIGURATION; getConfigurationMessage.toBS = true; getConfigurationMessage.fromPC = true; getConfigurationMessage.remVersion = REM_LOCAL_VERSION; @@ -277,7 +277,7 @@ std::vector> BasestationCollection::getSelectableBa bool BasestationCollection::sendChannelChangeRequest(const std::shared_ptr& basestation, WirelessChannel newChannel) { REM_BasestationConfiguration setConfigurationCommand; - setConfigurationCommand.header = REM_PACKET_TYPE_REM_BASESTATION_CONFIGURATION; + setConfigurationCommand.packetType = REM_PACKET_TYPE_REM_BASESTATION_CONFIGURATION; setConfigurationCommand.toBS = true; setConfigurationCommand.fromPC = true; setConfigurationCommand.remVersion = REM_LOCAL_VERSION; @@ -452,13 +452,13 @@ void BasestationCollection::onMessageFromBasestation(const BasestationMessage& m // If this message contains what channel the basestation has, parse it and update our map REM_PacketPayload* packetPayload = (REM_PacketPayload*)message.payloadBuffer; - if (REM_Packet_get_header(packetPayload) == REM_PACKET_TYPE_REM_BASESTATION_CONFIGURATION) { + if (REM_Packet_get_packetType(packetPayload) == REM_PACKET_TYPE_REM_BASESTATION_CONFIGURATION) { uint8_t basestation_channel_rem = REM_BasestationConfiguration_get_channel((REM_BasestationConfigurationPayload*)message.payloadBuffer); WirelessChannel basestation_channel = BasestationCollection::remChannelToWirelessChannel(basestation_channel_rem); this->setChannelOfBasestation(basestationId, basestation_channel); } - if (REM_Packet_get_header(packetPayload) == REM_PACKET_TYPE_REM_LOG) { + if (REM_Packet_get_packetType(packetPayload) == REM_PACKET_TYPE_REM_LOG) { REM_LogPayload* logPayload = (REM_LogPayload*)message.payloadBuffer; uint32_t message_length = REM_Log_get_payloadSize(logPayload) - REM_PACKET_SIZE_REM_LOG; char* charstring = (char*)&message.payloadBuffer[REM_PACKET_SIZE_REM_LOG]; diff --git a/roboteam_robothub/src/basestation/BasestationManager.cpp b/roboteam_robothub/src/basestation/BasestationManager.cpp index dcb07fee2..e0d6d8f41 100644 --- a/roboteam_robothub/src/basestation/BasestationManager.cpp +++ b/roboteam_robothub/src/basestation/BasestationManager.cpp @@ -109,7 +109,7 @@ std::vector BasestationManager::filterBasestationDevices(libusb_ void BasestationManager::handleIncomingMessage(const BasestationMessage& message, rtt::Team color) const { REM_PacketPayload* packetPayload = (REM_PacketPayload*)message.payloadBuffer; uint32_t payloadSize = REM_Packet_get_payloadSize(packetPayload); - uint8_t packetType = REM_Packet_get_header(packetPayload); + uint8_t packetType = REM_Packet_get_packetType(packetPayload); uint32_t packetVersion = REM_Packet_get_remVersion(packetPayload); if (packetVersion != REM_LOCAL_VERSION) { @@ -118,7 +118,7 @@ void BasestationManager::handleIncomingMessage(const BasestationMessage& message } if (static_cast(message.payloadSize) != payloadSize) { - RTT_ERROR("Payload size of message does not match the size specified in the packet header. Received size: ", message.payloadSize, ", indicated size: ", payloadSize); + RTT_ERROR("Payload size of message does not match the size specified in the packet packetType. Received size: ", message.payloadSize, ", indicated size: ", payloadSize); return; } diff --git a/roboteam_utils/include/roboteam_utils/Position.h b/roboteam_utils/include/roboteam_utils/Position.h index 65a41b5f2..40e9b1026 100644 --- a/roboteam_utils/include/roboteam_utils/Position.h +++ b/roboteam_utils/include/roboteam_utils/Position.h @@ -41,7 +41,7 @@ class Position { Position translate(const Vector2 &vec) const; /** - * \brief Rotate this position by the specified angle. + * \brief Rotate this position by the specified yaw. */ Position rotate(double radians) const; diff --git a/roboteam_utils/include/roboteam_utils/Robot.hpp b/roboteam_utils/include/roboteam_utils/Robot.hpp index 522658476..fbac8ba80 100644 --- a/roboteam_utils/include/roboteam_utils/Robot.hpp +++ b/roboteam_utils/include/roboteam_utils/Robot.hpp @@ -13,26 +13,24 @@ typedef struct Robot { Team team = Team::YELLOW; // [YELLOW, BLUE] The team of the robot Vector2 position; // (m) The position of the robot on the field Vector2 velocity; // (m/s) The velocity of the robot - Angle angle; // (rad) The current angle of the robot + Angle yaw; // (rad) The current yaw of the robot double angularVelocity = 0.0; // (rad/s) The current angular velocity - bool ballSensorSeesBall = false; // Indicates if the ball sensor sees the ball - bool ballSensorIsWorking = false; // Indicates if the ball sensor is working - double ballPositionOnSensor = 0.0; // [-0.5, 0.5] The position of the ball on the sensor - bool dribblerSeesBall = false; // Indicates if the dribbler sees the ball + bool ballSensorSeesBall = false; // Indicates if the ball sensor sees the ball + bool ballSensorIsWorking = false; // Indicates if the ball sensor is working + bool dribblerSeesBall = false; // Indicates if the dribbler sees the ball - double dribblerSpeed = 0.0; // (rad/s) The current speed of the dribbler + bool dribblerOn = false; // Indicates if the dribbler is on bool xSensIsCalibrated = false; // Indicates if the xSens is calibrated bool capacitorIsCharged = false; // Indicates if the capacitor is charged - double signalStrength = 0.0; // The signal strength of the robot double batteryLevel = 0.0; // The battery level of the robot // TODO: Define units double radius = 0.09; // (m) The radius of the robot double height = 0.15; // (m) The height of the robot double frontWidth = 0.13; // (m) The width of the front assembly double dribblerWidth = 0.10; // (m) The width of the dribbler - Angle capOffset; // (rad) The difference between the angle of the cap vs the angle of the robot + Angle capOffset; // (rad) The difference between the angle of the cap vs the yaw of the robot bool operator==(const Robot& other) const; } Robot; diff --git a/roboteam_utils/include/roboteam_utils/RobotCommands.hpp b/roboteam_utils/include/roboteam_utils/RobotCommands.hpp index 0f3f22531..1388683b0 100644 --- a/roboteam_utils/include/roboteam_utils/RobotCommands.hpp +++ b/roboteam_utils/include/roboteam_utils/RobotCommands.hpp @@ -20,22 +20,22 @@ typedef struct RobotCommand { // Positioning related variables Vector2 velocity; // (m/s) Target velocity of the robot - Angle targetAngle; // (rad) [-PI, PI] The target angle of the robot + Angle yaw; // (rad) [-PI, PI] The target yaw of the robot double targetAngularVelocity = 0.0; // (rad/s) The target angular velocity of the robot - bool useAngularVelocity = 0.0; // True if angular velocity should be used instead of angle + bool useAngularVelocity = 0.0; // True if angular velocity should be used instead of yaw - Angle cameraAngleOfRobot; // (rad) The current angle of the robot according to the camera - bool cameraAngleOfRobotIsSet = false; // True if the cameraAngleOfRobot is set. If false, these fields should be ignored + Angle cameraYawOfRobot; // (rad) The current yaw of the robot according to the camera + bool cameraYawOfRobotIsSet = false; // True if the cameraYawOfRobot is set. If false, these fields should be ignored // Action related variables double kickSpeed = 0.0; // (m/s) [0, 6.5] The target speed of the ball. Speed of <= 0.0 is undefined bool waitForBall = false; // Will make the robot wait with kicking until it has the ball KickType kickType = KickType::NO_KICK; // Defines the type of kicking, either normal(horizontal) or chipping(vertical), or no kick - bool kickAtAngle = false; // Makes robot kick once it arrives at the specified angle, used in combination with angular velocity + bool kickAtYaw = false; // Makes robot kick once it arrives at the specified yaw, used in combination with angular velocity - double dribblerSpeed = 0.0; // [0, 1] Speed of the dribbler + bool dribblerOn = false; // Robot will turn on the dribbler - bool ignorePacket = false; // Robot will ignore packet, but robot will reply with feedback + bool wheelsOff = false; // Robot will turn off the wheels bool operator==(const RobotCommand &other) const; diff --git a/roboteam_utils/include/roboteam_utils/RobotFeedback.hpp b/roboteam_utils/include/roboteam_utils/RobotFeedback.hpp index 1d6fcbbdd..15ba5dbbf 100644 --- a/roboteam_utils/include/roboteam_utils/RobotFeedback.hpp +++ b/roboteam_utils/include/roboteam_utils/RobotFeedback.hpp @@ -17,17 +17,13 @@ std::string robotFeedbackSourceToString(RobotFeedbackSource source); typedef struct RobotFeedback { int id = 0; // ID of the robot bool ballSensorSeesBall = false; // The ballSensor sees the ball - float ballPosition = 0.0f; // [-0.5, 0.5] Position of the ball relative to the sensor bool ballSensorIsWorking = false; // The ball sensor is working. Can suddenly stop working! bool dribblerSeesBall = false; // The dribbler has the ball Vector2 velocity; // Estimated velocity according to the robot - Angle angle; // Estimated angle according to the robot + Angle yaw; // Estimated yaw according to the robot bool xSensIsCalibrated = false; // The xSens is calibrated bool capacitorIsCharged = false; // The capacitor is charged - int wheelLocked = 0; // Indicates if a wheel is locked. One bit per wheel - int wheelBraking = 0; // Indicates if a wheel is slipping. One bit per wheel float batteryLevel = 23.0f; // Battery level // TODO: Decide if this is in volts or percentage - int signalStrength = 0; // The signal strength of the robot bool operator==(const RobotFeedback &other) const; diff --git a/roboteam_utils/include/roboteam_utils/RobotShape.h b/roboteam_utils/include/roboteam_utils/RobotShape.h index 327af11ee..cc7044333 100644 --- a/roboteam_utils/include/roboteam_utils/RobotShape.h +++ b/roboteam_utils/include/roboteam_utils/RobotShape.h @@ -30,7 +30,7 @@ class RobotShape { [[nodiscard]] Vector2 pos() const; - [[nodiscard]] Angle angle() const; + [[nodiscard]] Angle yaw() const; [[nodiscard]] Vector2 centerOfKickerPos() const; diff --git a/roboteam_utils/src/utils/Robot.cpp b/roboteam_utils/src/utils/Robot.cpp index 01163ae19..74540acfa 100644 --- a/roboteam_utils/src/utils/Robot.cpp +++ b/roboteam_utils/src/utils/Robot.cpp @@ -3,12 +3,11 @@ namespace rtt { bool Robot::operator==(const Robot &other) const { - return this->id == other.id && this->team == other.team && this->position == other.position && this->velocity == other.velocity && this->angle == other.angle && + return this->id == other.id && this->team == other.team && this->position == other.position && this->velocity == other.velocity && this->yaw == other.yaw && this->angularVelocity == other.angularVelocity && this->ballSensorSeesBall == other.ballSensorSeesBall && this->ballSensorIsWorking == other.ballSensorIsWorking && - this->ballPositionOnSensor == other.ballPositionOnSensor && this->dribblerSeesBall == other.dribblerSeesBall && this->dribblerSpeed == other.dribblerSpeed && - this->xSensIsCalibrated == other.xSensIsCalibrated && this->capacitorIsCharged == other.capacitorIsCharged && this->signalStrength == other.signalStrength && - this->batteryLevel == other.batteryLevel && this->radius == other.radius && this->height == other.height && this->frontWidth == other.frontWidth && - this->dribblerWidth == other.dribblerWidth && this->capOffset == other.capOffset; + this->dribblerSeesBall == other.dribblerSeesBall && this->dribblerOn == other.dribblerOn && this->xSensIsCalibrated == other.xSensIsCalibrated && + this->capacitorIsCharged == other.capacitorIsCharged && this->batteryLevel == other.batteryLevel && this->radius == other.radius && this->height == other.height && + this->frontWidth == other.frontWidth && this->dribblerWidth == other.dribblerWidth && this->capOffset == other.capOffset; } } // namespace rtt \ No newline at end of file diff --git a/roboteam_utils/src/utils/RobotCommands.cpp b/roboteam_utils/src/utils/RobotCommands.cpp index f2fcf3473..7473d624b 100644 --- a/roboteam_utils/src/utils/RobotCommands.cpp +++ b/roboteam_utils/src/utils/RobotCommands.cpp @@ -17,27 +17,27 @@ std::string kickTypeToString(KickType type) { } bool RobotCommand::operator==(const RobotCommand &other) const { - return this->id == other.id && this->velocity == other.velocity && this->targetAngle == other.targetAngle && this->targetAngularVelocity == other.targetAngularVelocity && - this->useAngularVelocity == other.useAngularVelocity && this->cameraAngleOfRobot == other.cameraAngleOfRobot && - this->cameraAngleOfRobotIsSet == other.cameraAngleOfRobotIsSet && this->kickSpeed == other.kickSpeed && this->waitForBall == other.waitForBall && - this->kickType == other.kickType && this->kickAtAngle == other.kickAtAngle && this->dribblerSpeed == other.dribblerSpeed && this->ignorePacket == other.ignorePacket; + return this->id == other.id && this->velocity == other.velocity && this->yaw == other.yaw && this->targetAngularVelocity == other.targetAngularVelocity && + this->useAngularVelocity == other.useAngularVelocity && this->cameraYawOfRobot == other.cameraYawOfRobot && this->cameraYawOfRobotIsSet == other.cameraYawOfRobotIsSet && + this->kickSpeed == other.kickSpeed && this->waitForBall == other.waitForBall && this->kickType == other.kickType && this->kickAtYaw == other.kickAtYaw && + this->dribblerOn == other.dribblerOn && this->wheelsOff == other.wheelsOff; } std::ostream &RobotCommand::write(std::ostream &os) const { return os << "{" << "id: " << formatString("%2i", this->id) << ", " << "velocity: " << this->velocity << ", " - << "targetAngle: " << this->targetAngle << ", " + << "yaw: " << this->yaw << ", " << "targetAngularVel: " << formatString("%5f", this->targetAngularVelocity) << ", " << "useAngularVel: " << (this->useAngularVelocity ? " true" : "false") << ", " - << "cameraAngle: " << this->cameraAngleOfRobot << ", " - << "cameraAngleIsSet: " << (this->cameraAngleOfRobotIsSet ? " true" : "false") << ", " + << "cameraYaw: " << this->cameraYawOfRobot << ", " + << "cameraYawIsSet: " << (this->cameraYawOfRobotIsSet ? " true" : "false") << ", " << "kickSpeed: " << formatString("%5f", this->kickSpeed) << ", " << "waitForBall: " << (this->waitForBall ? " true" : "false") << ", " << "kickType: " << kickTypeToString(this->kickType) << ", " - << "kickAtAngle: " << this->kickAtAngle << ", " - << "dribblerSpeed: " << formatString("%5f", this->dribblerSpeed) << ", " - << "ignorePacket: " << (this->ignorePacket ? " true" : "false") << "}"; + << "kickAtYaw: " << this->kickAtYaw << ", " + << "dribblerOn: " << formatString("%5f", this->dribblerOn) << ", " + << "wheelsOff: " << (this->wheelsOff ? " true" : "false") << "}"; } std::ostream &operator<<(std::ostream &os, const RobotCommand &command) { return command.write(os); } diff --git a/roboteam_utils/src/utils/RobotFeedback.cpp b/roboteam_utils/src/utils/RobotFeedback.cpp index 0d52c8d10..2a401a033 100644 --- a/roboteam_utils/src/utils/RobotFeedback.cpp +++ b/roboteam_utils/src/utils/RobotFeedback.cpp @@ -15,11 +15,9 @@ std::string robotFeedbackSourceToString(RobotFeedbackSource source) { } bool RobotFeedback::operator==(const RobotFeedback &other) const { - return this->id == other.id && this->ballSensorSeesBall == other.ballSensorSeesBall && this->ballPosition == other.ballPosition && - this->ballSensorIsWorking == other.ballSensorIsWorking && this->dribblerSeesBall == other.dribblerSeesBall && this->velocity == other.velocity && - this->angle == other.angle && this->xSensIsCalibrated == other.xSensIsCalibrated && this->capacitorIsCharged == other.capacitorIsCharged && - this->wheelLocked == other.wheelLocked && this->wheelBraking == other.wheelBraking && this->batteryLevel == other.batteryLevel && - this->signalStrength == other.signalStrength; + return this->id == other.id && this->ballSensorSeesBall == other.ballSensorSeesBall && this->ballSensorIsWorking == other.ballSensorIsWorking && + this->dribblerSeesBall == other.dribblerSeesBall && this->velocity == other.velocity && this->yaw == other.yaw && this->xSensIsCalibrated == other.xSensIsCalibrated && + this->capacitorIsCharged == other.capacitorIsCharged && this->batteryLevel == other.batteryLevel; } std::string boolToString(bool b) { return (b ? " true" : "false"); } @@ -28,17 +26,13 @@ std::ostream &RobotFeedback::write(std::ostream &os) const { return os << "{" << "id: " << formatString("%2i", this->id) << ", " << "ballSensorSeesBall: " << boolToString(this->ballSensorSeesBall) << ", " - << "ballPos: " << formatString("%5f", this->ballPosition) << ", " << "ballSensorWorks: " << boolToString(this->ballSensorIsWorking) << ", " << "dribblerSeesBall: " << boolToString(this->dribblerSeesBall) << ", " << "velocity: " << this->velocity << ", " - << "angle: " << this->angle << ", " + << "yaw: " << this->yaw << ", " << "xSensCalib: " << boolToString(this->xSensIsCalibrated) << ", " << "capacitorCharged: " << boolToString(this->capacitorIsCharged) << ", " - << "wheelLocked: " << formatString("%4i", this->wheelLocked) << ", " - << "wheelBraking: " << formatString("%4i", this->wheelBraking) << ", " - << "battery: " << formatString("%4f", this->batteryLevel) << ", " - << "signalStrength: " << formatString("%3i", this->signalStrength) << "}"; + << "battery: " << formatString("%4f", this->batteryLevel) << "}"; } std::ostream &operator<<(std::ostream &os, const RobotFeedback &feedback) { return feedback.write(os); } diff --git a/roboteam_utils/src/utils/RobotShape.cpp b/roboteam_utils/src/utils/RobotShape.cpp index 46de26f00..7daeee29b 100644 --- a/roboteam_utils/src/utils/RobotShape.cpp +++ b/roboteam_utils/src/utils/RobotShape.cpp @@ -13,7 +13,7 @@ RobotShape::RobotShape(const Vector2 &pos, double centerToFront, double radius, Vector2 dribblerCenter = pos + middleToCenter; double halfFrontWidth = sqrt(radius * radius - centerToFront * centerToFront); // Pythagoras Vector2 diff = Vector2(-middleToCenter.y, middleToCenter.x).stretchToLength(halfFrontWidth); - kickerLine = LineSegment(dribblerCenter - diff, dribblerCenter + diff); // Lower corner, upper corner (when robot is facing right (e.g. angle = 0)) + kickerLine = LineSegment(dribblerCenter - diff, dribblerCenter + diff); // Lower corner, upper corner (when robot is facing right (e.g. yaw = 0)) } bool RobotShape::inFrontOfDribbler(const Vector2 &point) const { @@ -110,7 +110,7 @@ std::vector RobotShape::intersects(const LineSegment &segment) const { return {}; // This should never be hit as circle intersection always hits atleast two. } -Angle RobotShape::angle() const { return orientation; } +Angle RobotShape::yaw() const { return orientation; } Vector2 RobotShape::pos() const { return circle.center; } diff --git a/roboteam_utils/test/utils/RobotCommandsTest.cpp b/roboteam_utils/test/utils/RobotCommandsTest.cpp index dd24b7aed..27b3579b8 100644 --- a/roboteam_utils/test/utils/RobotCommandsTest.cpp +++ b/roboteam_utils/test/utils/RobotCommandsTest.cpp @@ -15,35 +15,35 @@ TEST(RobotCommandsTest, instantiation) { RobotCommand robotCommand; ASSERT_EQ(robotCommand.id, 0); ASSERT_EQ(robotCommand.velocity, Vector2()); - ASSERT_EQ(robotCommand.targetAngle, Angle()); + ASSERT_EQ(robotCommand.yaw, Angle()); ASSERT_DOUBLE_EQ(robotCommand.targetAngularVelocity, 0.0); ASSERT_FALSE(robotCommand.useAngularVelocity); - ASSERT_EQ(robotCommand.cameraAngleOfRobot, Angle()); - ASSERT_FALSE(robotCommand.cameraAngleOfRobotIsSet); + ASSERT_EQ(robotCommand.cameraYawOfRobot, Angle()); + ASSERT_FALSE(robotCommand.cameraYawOfRobotIsSet); ASSERT_DOUBLE_EQ(robotCommand.kickSpeed, 0.0); ASSERT_FALSE(robotCommand.waitForBall); ASSERT_EQ(robotCommand.kickType, KickType::NO_KICK); - ASSERT_FALSE(robotCommand.kickAtAngle); - ASSERT_DOUBLE_EQ(robotCommand.dribblerSpeed, 0.0); + ASSERT_FALSE(robotCommand.kickAtYaw); + ASSERT_FALSE(robotCommand.dribblerOn); - ASSERT_FALSE(robotCommand.ignorePacket); + ASSERT_FALSE(robotCommand.wheelsOff); } TEST(RobotCommandsTest, equals) { RobotCommand command = {.id = SimpleRandom::getInt(0, 15), .velocity = Vector2(SimpleRandom::getDouble(-10.0, 10.0), SimpleRandom::getDouble(-10.0, 10.0)), - .targetAngle = Angle(SimpleRandom::getDouble(-M_PI, M_PI)), + .yaw = Angle(SimpleRandom::getDouble(-M_PI, M_PI)), .targetAngularVelocity = SimpleRandom::getDouble(-5.0, 5.0), .useAngularVelocity = SimpleRandom::getBool(), - .cameraAngleOfRobot = Angle(SimpleRandom::getDouble(-M_PI, M_PI)), - .cameraAngleOfRobotIsSet = SimpleRandom::getBool(), + .cameraYawOfRobot = Angle(SimpleRandom::getDouble(-M_PI, M_PI)), + .cameraYawOfRobotIsSet = SimpleRandom::getBool(), .kickSpeed = SimpleRandom::getDouble(0.0, 5.0), .waitForBall = SimpleRandom::getBool(), .kickType = randomKickType(), - .kickAtAngle = SimpleRandom::getBool(), - .dribblerSpeed = SimpleRandom::getDouble(0.0, 5.0), - .ignorePacket = SimpleRandom::getBool()}; + .kickAtYaw = SimpleRandom::getBool(), + .dribblerOn = SimpleRandom::getBool(), + .wheelsOff = SimpleRandom::getBool()}; RobotCommand copy = command; ASSERT_EQ(command, copy); } \ No newline at end of file diff --git a/roboteam_utils/test/utils/RobotFeedbackTest.cpp b/roboteam_utils/test/utils/RobotFeedbackTest.cpp index b87645971..c6f23cf34 100644 --- a/roboteam_utils/test/utils/RobotFeedbackTest.cpp +++ b/roboteam_utils/test/utils/RobotFeedbackTest.cpp @@ -17,17 +17,13 @@ Team randomTeam() { RobotFeedback randomFeedback() { RobotFeedback feedback = {.id = SimpleRandom::getInt(0, 15), .ballSensorSeesBall = SimpleRandom::getBool(), - .ballPosition = static_cast(SimpleRandom::getDouble(-0.5, 0.5)), .ballSensorIsWorking = SimpleRandom::getBool(), .dribblerSeesBall = SimpleRandom::getBool(), .velocity = Vector2(SimpleRandom::getDouble(-10.0, 10.0), SimpleRandom::getDouble(-10.0, 10.0)), - .angle = Angle(SimpleRandom::getDouble(-M_PI, M_PI)), + .yaw = Angle(SimpleRandom::getDouble(-M_PI, M_PI)), .xSensIsCalibrated = SimpleRandom::getBool(), .capacitorIsCharged = SimpleRandom::getBool(), - .wheelLocked = SimpleRandom::getInt(0, 15), - .wheelBraking = SimpleRandom::getInt(0, 15), - .batteryLevel = static_cast(SimpleRandom::getDouble(18.0f, 26.0f)), - .signalStrength = SimpleRandom::getInt(0, 255)}; + .batteryLevel = static_cast(SimpleRandom::getDouble(18.0f, 26.0f))}; return feedback; } @@ -36,17 +32,13 @@ TEST(RobotFeedbackTest, instantiation) { RobotFeedback robotFeedback; ASSERT_EQ(robotFeedback.id, 0); ASSERT_FALSE(robotFeedback.ballSensorSeesBall); - ASSERT_FLOAT_EQ(robotFeedback.ballPosition, 0.0f); ASSERT_FALSE(robotFeedback.ballSensorIsWorking); ASSERT_FALSE(robotFeedback.dribblerSeesBall); ASSERT_EQ(robotFeedback.velocity, Vector2()); - ASSERT_EQ(robotFeedback.angle, Angle()); + ASSERT_EQ(robotFeedback.yaw, Angle()); ASSERT_FALSE(robotFeedback.xSensIsCalibrated); ASSERT_FALSE(robotFeedback.capacitorIsCharged); - ASSERT_EQ(robotFeedback.wheelLocked, 0); - ASSERT_EQ(robotFeedback.wheelBraking, 0); ASSERT_FLOAT_EQ(robotFeedback.batteryLevel, 23.0f); - ASSERT_EQ(robotFeedback.signalStrength, 0); } TEST(RobotFeedbackTest, equals) { diff --git a/roboteam_utils/test/utils/RobotShapeTest.cpp b/roboteam_utils/test/utils/RobotShapeTest.cpp index 0d73955d2..594d2ba82 100644 --- a/roboteam_utils/test/utils/RobotShapeTest.cpp +++ b/roboteam_utils/test/utils/RobotShapeTest.cpp @@ -9,7 +9,7 @@ TEST(RobotShapeTest, constructors) { double centerToFront = 0.05; RobotShape shape(Vector2(0, 0), centerToFront, radius, Angle(0.0)); EXPECT_EQ(shape.pos(), Vector2(0, 0)); - EXPECT_DOUBLE_EQ(shape.angle().getValue(), 0.0); + EXPECT_DOUBLE_EQ(shape.yaw().getValue(), 0.0); EXPECT_EQ(shape.centerOfKickerPos(), Vector2(centerToFront, 0)); LineSegment kicker = shape.kicker(); double diff = sqrt(radius * radius - centerToFront * centerToFront); @@ -22,7 +22,7 @@ TEST(RobotShapeTest, constructors) { // Check if rotation is applied correctly RobotShape shape2(Vector2(0, 0), centerToFront, radius, Angle(1.0)); EXPECT_EQ(shape2.pos(), Vector2(0, 0)); - EXPECT_DOUBLE_EQ(shape2.angle().getValue(), 1.0); + EXPECT_DOUBLE_EQ(shape2.yaw().getValue(), 1.0); EXPECT_DOUBLE_EQ(shape2.centerOfKickerPos().x, Vector2(centerToFront, 0).rotate(1.0).x); EXPECT_DOUBLE_EQ(shape2.centerOfKickerPos().y, Vector2(centerToFront, 0).rotate(1.0).y); } diff --git a/roboteam_utils/test/utils/RobotTest.cpp b/roboteam_utils/test/utils/RobotTest.cpp index b3b7c0543..1d928bc7f 100644 --- a/roboteam_utils/test/utils/RobotTest.cpp +++ b/roboteam_utils/test/utils/RobotTest.cpp @@ -10,16 +10,14 @@ TEST(RobotTest, instantiation) { ASSERT_EQ(r.id, 0); ASSERT_EQ(r.team, Team::YELLOW); - ASSERT_EQ(r.angle, Angle()); + ASSERT_EQ(r.yaw, Angle()); ASSERT_DOUBLE_EQ(r.angularVelocity, 0.0); ASSERT_FALSE(r.ballSensorSeesBall); ASSERT_FALSE(r.ballSensorIsWorking); - ASSERT_DOUBLE_EQ(r.ballPositionOnSensor, 0.0); ASSERT_FALSE(r.dribblerSeesBall); - ASSERT_DOUBLE_EQ(r.dribblerSpeed, 0.0); + ASSERT_FALSE(r.dribblerOn); ASSERT_FALSE(r.xSensIsCalibrated); ASSERT_FALSE(r.capacitorIsCharged); - ASSERT_DOUBLE_EQ(r.signalStrength, 0.0); ASSERT_DOUBLE_EQ(r.batteryLevel, 0.0); ASSERT_DOUBLE_EQ(r.radius, 0.09); ASSERT_DOUBLE_EQ(r.height, 0.15); @@ -36,16 +34,14 @@ TEST(RobotTest, equals) { .team = *SimpleRandom::getRandomElement(allTeams.begin(), allTeams.end()), .position = Vector2(SimpleRandom::getDouble(-20, 20), SimpleRandom::getDouble(-20, 20)), .velocity = Vector2(SimpleRandom::getDouble(-5, 5), SimpleRandom::getDouble(-5, 5)), - .angle = Angle(SimpleRandom::getDouble(0, 7)), + .yaw = Angle(SimpleRandom::getDouble(0, 7)), .angularVelocity = SimpleRandom::getDouble(-3, 3), .ballSensorSeesBall = SimpleRandom::getBool(), .ballSensorIsWorking = SimpleRandom::getBool(), - .ballPositionOnSensor = SimpleRandom::getDouble(-0.5, 0.5), .dribblerSeesBall = SimpleRandom::getBool(), - .dribblerSpeed = SimpleRandom::getDouble(0, 50), + .dribblerOn = SimpleRandom::getBool(), .xSensIsCalibrated = SimpleRandom::getBool(), .capacitorIsCharged = SimpleRandom::getBool(), - .signalStrength = SimpleRandom::getDouble(0, 10), .batteryLevel = SimpleRandom::getDouble(18, 24), .radius = SimpleRandom::getDouble(0.06, 0.09), .height = SimpleRandom::getDouble(0.10, 0.15), diff --git a/roboteam_utils/test/utils/WorldTest.cpp b/roboteam_utils/test/utils/WorldTest.cpp index d438afb07..70d561642 100644 --- a/roboteam_utils/test/utils/WorldTest.cpp +++ b/roboteam_utils/test/utils/WorldTest.cpp @@ -14,7 +14,7 @@ World randomWorld() { .yellowRobots = {Robot{.id = SimpleRandom::getInt(0, 15), .position = Vector2(SimpleRandom::getDouble(-5, 5), SimpleRandom::getDouble(-5, 5)), .velocity = Vector2(SimpleRandom::getDouble(-5, 5), SimpleRandom::getDouble(-5, 5)), - .angle = SimpleRandom::getDouble(-5, 5), + .yaw = SimpleRandom::getDouble(-5, 5), .capOffset = SimpleRandom::getDouble(-5, 5)}}, .blueRobots = {}}; }