Merge "Changes to camera extrinsic calibration to improve accuracy" into main
diff --git a/.bazelrc b/.bazelrc
index 09c943f..fcd1269 100644
--- a/.bazelrc
+++ b/.bazelrc
@@ -133,6 +133,9 @@
# Prevent cypress from using its own binary. We want to use the hermetic one.
build --action_env=CYPRESS_INSTALL_BINARY=0
+# Allow spaces in runfiles filenames.
+build --experimental_inprocess_symlink_creation
+
# From our one and only phil.schrader: https://groups.google.com/g/bazel-discuss/c/5cbRuLuTwNg :)
# Enable -Werror and warnings for our code
# TODO: It would be nice to enable Wcast-align and Wcast-qual.
diff --git a/WORKSPACE b/WORKSPACE
index ad59314..6fd635e 100644
--- a/WORKSPACE
+++ b/WORKSPACE
@@ -702,14 +702,16 @@
cc_library(
name = 'api-cpp',
visibility = ['//visibility:public'],
- hdrs = glob(['ctre/phoenix6/**/*.hpp']),
+ hdrs = glob(['ctre/phoenix6/**/*.hpp', 'ctre/unit/**/*.h']),
includes = ["."],
- deps = ["@//third_party/allwpilib/wpimath"],
+ deps = ["@//third_party/allwpilib/wpimath",
+ "@ctre_phoenix6_tools_headers//:tools",
+ ],
)
""",
- sha256 = "1b9295ac868d619d0263f285b372a22297798e45c8fdeb83ca99154a097c5c98",
+ sha256 = "67fdd9a4bf275c69666bbc8bf38312eea8a85bf9fda3901d02af3a18136ffb3e",
urls = [
- "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/api-cpp/24.1.0/api-cpp-24.1.0-headers.zip",
+ "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/api-cpp/24.50.0-alpha-2/api-cpp-24.50.0-alpha-2-headers.zip",
],
)
@@ -731,9 +733,9 @@
target_compatible_with = ['@//tools/platforms/hardware:roborio'],
)
""",
- sha256 = "51f4921f8995e3e80ba347a90f6fa5c0cb7d0e438923a1a736554f263e2d5b8e",
+ sha256 = "00da14f437cfeb2c344674dee59fe70477a3a0d612eb93a1441188dc94a5136f",
urls = [
- "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/api-cpp/24.1.0/api-cpp-24.1.0-linuxathena.zip",
+ "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/api-cpp/24.50.0-alpha-2/api-cpp-24.50.0-alpha-2-linuxathena.zip",
],
)
@@ -743,12 +745,12 @@
cc_library(
name = 'tools',
visibility = ['//visibility:public'],
- hdrs = glob(['ctre/**/*.h', 'ctre/**/*.hpp']),
+ hdrs = glob(['ctre/**/*.h', 'ctre/phoenix/**/*.hpp', 'ctre/phoenix6/**/*.hpp']),
)
""",
- sha256 = "72be3e50205e2546736361e3aba9c0de5d5318b263c195600f9b558c3d92cb9e",
+ sha256 = "77624291ec19a03c9e068347ef800e435782444722793d56c9e39f6108da33a8",
urls = [
- "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/tools/24.1.0/tools-24.1.0-headers.zip",
+ "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/tools/24.50.0-alpha-2/tools-24.50.0-alpha-2-headers.zip",
],
)
@@ -770,9 +772,9 @@
target_compatible_with = ['@//tools/platforms/hardware:roborio'],
)
""",
- sha256 = "76d30cb8c0988eb6accab10e77ceae492782edb64c06f7df628b8c161cf0220a",
+ sha256 = "217bcd6aecb71224fd32725f857da58e61a6ea451ca07f85fb55e49f83dbf113",
urls = [
- "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/tools/24.1.0/tools-24.1.0-linuxathena.zip",
+ "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/tools/24.50.0-alpha-2/tools-24.50.0-alpha-2-linuxathena.zip",
],
)
@@ -782,12 +784,13 @@
cc_library(
name = 'api-cpp',
visibility = ['//visibility:public'],
- hdrs = glob(['ctre/phoenix/**/*.h']),
+ hdrs = glob(['ctre/phoenix/**/*.h', 'ctre/unit/**/*.h']),
+ includes = ["."]
)
""",
- sha256 = "d2790e2495a59a3b14ab4b0fd03c2e25292d6874168f5642165acb0d1bab2f99",
+ sha256 = "4fba20441ea1d61f8487897682c723a48ee2c2741946eab4062b4248434c0afc",
urls = [
- "https://maven.ctr-electronics.com/release/com/ctre/phoenix/api-cpp/5.33.0/api-cpp-5.33.0-headers.zip",
+ "https://maven.ctr-electronics.com/release/com/ctre/phoenix/api-cpp/5.34.0-alpha-1/api-cpp-5.34.0-alpha-1-headers.zip",
],
)
@@ -824,9 +827,9 @@
hdrs = glob(['ctre/phoenix/**/*.h']),
)
""",
- sha256 = "56cb8272d623721560eea360730d2508f4f365e2ac1060aec5fbd546cffc0771",
+ sha256 = "cd39f32341037a7ec1074710044b332db6ca607dfd548b5f951c75f7a8506ab5",
urls = [
- "https://maven.ctr-electronics.com/release/com/ctre/phoenix/cci/5.33.0/cci-5.33.0-headers.zip",
+ "https://maven.ctr-electronics.com/release/com/ctre/phoenix/cci/5.34.0-alpha-1/cci-5.34.0-alpha-1-headers.zip",
],
)
@@ -867,6 +870,7 @@
target_compatible_with = ['@platforms//cpu:arm64'],
)
+
# TODO(max): Use cc_import once they add a defines property.
# See: https://github.com/bazelbuild/bazel/issues/19753
cc_library(
@@ -891,9 +895,9 @@
],
)
""",
- sha256 = "635b19f019d1283749fb23a95ad9e13ddd9d5013cff4c838303d898e7d9556bd",
+ sha256 = "0f1312f39eacc490fb253198c2d0e61e48ae00eff6a87cfd362358b1ad36a930",
urls = [
- "https://software.frc971.org/Build-Dependencies/phoenix6_24.2.0_5.4.2024.tar.gz",
+ "https://software.frc971.org/Build-Dependencies/phoenix6_24.50.0-alpha-2_arm64-2024.10.26.tar.gz",
],
)
diff --git a/aos/containers/error_list.h b/aos/containers/error_list.h
index 7ceb1fe..762d2ad 100644
--- a/aos/containers/error_list.h
+++ b/aos/containers/error_list.h
@@ -5,6 +5,7 @@
#include <algorithm>
+#include "absl/log/check.h"
#include "flatbuffers/buffer.h"
#include "flatbuffers/flatbuffer_builder.h"
#include "flatbuffers/vector.h"
@@ -128,7 +129,11 @@
flatbuffers::FlatBufferBuilder *fbb) const {
return fbb->CreateVector(array_.data(), array_.size());
}
-}; // namespace aos
+ template <typename StaticBuilder>
+ void ToStaticFlatbuffer(StaticBuilder *vector_builder) const {
+ CHECK(vector_builder->FromData(array_.data(), array_.size()));
+ }
+};
} // namespace aos
diff --git a/aos/events/logging/config_remapper.cc b/aos/events/logging/config_remapper.cc
index 763cbc3..edc2326 100644
--- a/aos/events/logging/config_remapper.cc
+++ b/aos/events/logging/config_remapper.cc
@@ -566,7 +566,9 @@
// Add the schema if it doesn't exist.
if (schema_map.find(c->type()->string_view()) == schema_map.end()) {
- CHECK(c->has_schema());
+ if (!c->has_schema()) {
+ LOG(FATAL) << "Could not find schema for " << c->type()->string_view();
+ }
schema_map.insert(std::make_pair(c->type()->string_view(),
RecursiveCopyFlatBuffer(c->schema())));
}
diff --git a/aos/network/team_number.cc b/aos/network/team_number.cc
index 175c3a9..bd90b96 100644
--- a/aos/network/team_number.cc
+++ b/aos/network/team_number.cc
@@ -130,6 +130,8 @@
return std::string_view("pi");
} else if (hostname.substr(0, 5) == "orin-") {
return std::string_view("orin");
+ } else if (hostname.substr(0, 4) == "imu-") {
+ return std::string_view("orin");
} else
return std::nullopt;
}
diff --git a/aos/network/team_number_test.cc b/aos/network/team_number_test.cc
index 9922b1b..278a364 100644
--- a/aos/network/team_number_test.cc
+++ b/aos/network/team_number_test.cc
@@ -28,7 +28,7 @@
EXPECT_FALSE(ParseRoborioTeamNumber("roboRIO--FRC"));
}
-TEST(TeamNumberTest, ParsePiOrOrinTeamNumber) {
+TEST(HostnameParseTest, ParsePiOrOrinTeamNumber) {
EXPECT_EQ(971u, *ParsePiOrOrinTeamNumber("pi-971-1"));
EXPECT_EQ(8971u, *ParsePiOrOrinTeamNumber("pi-8971-22"));
EXPECT_EQ(8971u, *ParsePiOrOrinTeamNumber("pi-8971-"));
@@ -37,12 +37,16 @@
EXPECT_EQ(8971u, *ParsePiOrOrinTeamNumber("orin-8971-22"));
EXPECT_EQ(8971u, *ParsePiOrOrinTeamNumber("orin-8971-"));
+ EXPECT_FALSE(ParsePiOrOrinTeamNumber("roboRIO-971-FRC"));
+
EXPECT_FALSE(ParseRoborioTeamNumber("pi"));
EXPECT_FALSE(ParseRoborioTeamNumber("pi-"));
EXPECT_FALSE(ParseRoborioTeamNumber("pi-971"));
EXPECT_FALSE(ParseRoborioTeamNumber("pi-971a-1"));
EXPECT_FALSE(ParseRoborioTeamNumber("orin-971-1"));
+}
+TEST(HostnameParseTest, ParsePiOrOrinNumber) {
EXPECT_EQ(1u, *ParsePiOrOrinNumber("pi-971-1"));
EXPECT_EQ(22u, *ParsePiOrOrinNumber("pi-8971-22"));
EXPECT_EQ(1u, *ParsePiOrOrinNumber("orin-971-1"));
@@ -59,4 +63,19 @@
EXPECT_FALSE(ParsePiOrOrinNumber("orin-971"));
}
+TEST(HostnameParseTest, ParsePiOrOrin) {
+ EXPECT_EQ("pi", *ParsePiOrOrin("pi-971-1"));
+ EXPECT_EQ("pi", *ParsePiOrOrin("pi-8971-22"));
+ EXPECT_EQ("pi", *ParsePiOrOrin("pi-8971-"));
+
+ EXPECT_EQ("orin", *ParsePiOrOrin("orin-971-1"));
+ EXPECT_EQ("orin", *ParsePiOrOrin("orin-8971-22"));
+ EXPECT_EQ("orin", *ParsePiOrOrin("orin-8971-"));
+
+ EXPECT_EQ("orin", *ParsePiOrOrin("imu-971-1"));
+
+ EXPECT_FALSE(ParsePiOrOrin("roboRIO-971-FRC"));
+ EXPECT_FALSE(ParsePiOrOrin("laptop"));
+}
+
} // namespace aos::network::testing
diff --git a/documentation/tutorials/getting-started.md b/documentation/tutorials/getting-started.md
index 8e04fcb..fb8ddaf 100644
--- a/documentation/tutorials/getting-started.md
+++ b/documentation/tutorials/getting-started.md
@@ -80,7 +80,7 @@
## Running the Code
-To run the code you'll need to download the repository from [gerrit](https://software.frc971.org/gerrit/admin/repos/971-Robot-Code), make sure to select ssh and not http.
+To run the code you'll need to download the repository from [gerrit](https://software.frc971.org/gerrit/admin/repos/971-Robot-Code), make sure to select ssh and not http. Click on SSH, and clone with commit message hook. Copy the command, and run it locally on terminal.
To learn more about git, open a terminal and run `man git`, or see [git(1)](https://manpages.debian.org/buster/git-man/git.1.en.html) (especially the NOTES section).
Once the repositoy is selected you'll want to make sure to configure your name, email on git. This is required to ensure you're following the [contributing guidelines above](#contributing). You can do this by running these following commands:
diff --git a/frc971/control_loops/dlqr.h b/frc971/control_loops/dlqr.h
index 57aa88b..d31f492 100644
--- a/frc971/control_loops/dlqr.h
+++ b/frc971/control_loops/dlqr.h
@@ -41,7 +41,9 @@
::Eigen::Matrix<double, kM, kN> *K,
::Eigen::Matrix<double, kN, kN> *S) {
*K = ::Eigen::Matrix<double, kM, kN>::Zero();
- *S = ::Eigen::Matrix<double, kN, kN>::Zero();
+ if (S != nullptr) {
+ *S = ::Eigen::Matrix<double, kN, kN>::Zero();
+ }
// Discrete (not continuous)
char DICO = 'D';
// B and R are provided instead of G.
diff --git a/frc971/control_loops/python/controls.py b/frc971/control_loops/python/controls.py
index 4cb10a2..7c7c310 100644
--- a/frc971/control_loops/python/controls.py
+++ b/frc971/control_loops/python/controls.py
@@ -85,11 +85,11 @@
J = sum(0, inf, x.T * Q * x + u.T * R * u)
"""
- # P = (A.T * P * A) - (A.T * P * B * numpy.linalg.inv(R + B.T * P *B) * (A.T * P.T * B).T + Q
- # 0.5 * X.T * P * X -> optimal cost to infinity
+ # P = (A.T * P * A) - (A.T * P * B * numpy.linalg.inv(R + B.T * P * B) * (A.T * P.T * B).T + Q
+ # X.T * P * X -> optimal cost to infinity
P = scipy.linalg.solve_discrete_are(a=A, b=B, q=Q, r=R)
- F = numpy.linalg.inv(R + B.T * P * B) * B.T * P * A
+ F = numpy.linalg.inv(R + B.T @ P @ B) @ B.T @ P @ A
if optimal_cost_function:
return F, P
else:
diff --git a/frc971/control_loops/python/drivetrain.py b/frc971/control_loops/python/drivetrain.py
index 1535432..f7262a7 100644
--- a/frc971/control_loops/python/drivetrain.py
+++ b/frc971/control_loops/python/drivetrain.py
@@ -664,8 +664,8 @@
max_battery_wattage = kMaxBreakerCurrent * (vbat -
kMaxBreakerCurrent * Rw)
if (max_current_request_left * max_voltage_left +
- max_current_request_right * max_voltage_right >
- max_battery_wattage):
+ max_current_request_right * max_voltage_right
+ > max_battery_wattage):
# Now solve the quadratic equation to figure out what the overall
# motor current can be which puts us at the max battery wattage.
max_motor_current = (
diff --git a/frc971/control_loops/swerve/BUILD b/frc971/control_loops/swerve/BUILD
index 26828e4..6be2604 100644
--- a/frc971/control_loops/swerve/BUILD
+++ b/frc971/control_loops/swerve/BUILD
@@ -14,8 +14,17 @@
)
static_flatbuffer(
+ name = "swerve_drivetrain_joystick_goal_fbs",
+ srcs = ["swerve_drivetrain_joystick_goal.fbs"],
+)
+
+static_flatbuffer(
name = "swerve_drivetrain_goal_fbs",
srcs = ["swerve_drivetrain_goal.fbs"],
+ deps = [
+ ":swerve_drivetrain_joystick_goal_fbs",
+ "//frc971/math:matrix_fbs",
+ ],
)
static_flatbuffer(
@@ -67,7 +76,10 @@
":swerve_drivetrain_output_fbs",
":swerve_drivetrain_position_fbs",
":swerve_drivetrain_status_fbs",
+ ":swerve_zeroing_fbs",
"//frc971/control_loops:control_loop",
+ "//frc971/control_loops:static_zeroing_single_dof_profiled_subsystem",
+ "//frc971/zeroing:continuous_absolute_encoder",
],
)
@@ -76,6 +88,7 @@
srcs = ["swerve_control_test.cc"],
data = [
":aos_config",
+ "//frc971/control_loops/swerve/test_module:rotation_json",
],
target_compatible_with = ["@platforms//os:linux"],
deps = [
@@ -140,12 +153,14 @@
"dynamics.cc",
"dynamics.h",
"dynamics.py",
+ "dynamics_constants.py",
],
args = [
"--output_base=$(BINDIR)/",
"--cc_output_path=$(location :dynamics.cc)",
"--h_output_path=$(location :dynamics.h)",
"--casadi_py_output_path=$(location :dynamics.py)",
+ "--constants_output_path=$(location :dynamics_constants.py)",
],
tool = ":generate_physics",
)
@@ -200,10 +215,10 @@
py_library(
name = "jax_dynamics",
srcs = [
+ "dynamics_constants.py",
"jax_dynamics.py",
],
deps = [
- ":dynamics",
"//frc971/control_loops/python:controls",
"@pip//jax",
],
@@ -214,17 +229,22 @@
srcs = [
"physics_test.py",
],
+ data = [":cpp_dynamics.so"],
env = {
"JAX_PLATFORMS": "cpu",
},
main = "physics_test.py",
target_compatible_with = ["@platforms//cpu:x86_64"],
deps = [
+ ":casadi_velocity_mpc_lib",
":dynamics",
":jax_dynamics",
":physics_test_utils",
+ "@pip//absl_py",
"@pip//casadi",
+ "@pip//matplotlib",
"@pip//numpy",
+ "@pip//pygobject",
"@pip//scipy",
],
)
@@ -234,18 +254,35 @@
srcs = [
"physics_test.py",
],
+ data = [":cpp_dynamics.so"],
env = {
"JAX_PLATFORMS": "cuda",
},
main = "physics_test.py",
target_compatible_with = ["@platforms//cpu:x86_64"],
deps = [
+ ":casadi_velocity_mpc_lib",
":dynamics",
":jax_dynamics",
":physics_test_utils",
+ "@pip//absl_py",
+ "@pip//casadi",
+ "@pip//matplotlib",
+ "@pip//numpy",
+ "@pip//pygobject",
+ "@pip//scipy",
+ ],
+)
+
+py_binary(
+ name = "casadi_velocity_mpc_lib",
+ srcs = [
+ "casadi_velocity_mpc_lib.py",
+ ],
+ deps = [
+ ":dynamics",
"@pip//casadi",
"@pip//numpy",
- "@pip//scipy",
],
)
@@ -255,9 +292,8 @@
"casadi_velocity_mpc.py",
],
deps = [
- ":dynamics",
+ ":casadi_velocity_mpc_lib",
"@pip//absl_py",
- "@pip//casadi",
"@pip//matplotlib",
"@pip//numpy",
"@pip//pygobject",
@@ -265,6 +301,33 @@
],
)
+py_binary(
+ name = "experience_collector",
+ srcs = [
+ "experience_collector.py",
+ ],
+ deps = [
+ ":casadi_velocity_mpc_lib",
+ ":jax_dynamics",
+ "//frc971/control_loops/swerve/velocity_controller:physics",
+ "@pip//absl_py",
+ "@pip//matplotlib",
+ "@pip//numpy",
+ "@pip//pygobject",
+ "@pip//scipy",
+ "@pip//tensorflow",
+ ],
+)
+
+py_binary(
+ name = "multi_experience_collector",
+ srcs = ["multi_experience_collector.py"],
+ data = [":experience_collector"],
+ deps = [
+ "@pip//absl_py",
+ ],
+)
+
py_library(
name = "physics_test_utils",
srcs = [
@@ -329,3 +392,107 @@
"@pip//pygobject",
],
)
+
+cc_binary(
+ name = "cpp_dynamics.so",
+ # Just use the python dynamics directly if you want them; this is just for testing.
+ testonly = True,
+ srcs = ["dynamics_python_bindings.cc"],
+ linkshared = True,
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ ":eigen_dynamics",
+ "//third_party/python",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
+ ],
+)
+
+cc_library(
+ name = "linearization_utils",
+ hdrs = ["linearization_utils.h"],
+)
+
+cc_library(
+ name = "linearized_controller",
+ hdrs = ["linearized_controller.h"],
+ deps = [
+ ":eigen_dynamics",
+ ":linearization_utils",
+ "//frc971/control_loops:c2d",
+ "//frc971/control_loops:dlqr",
+ "//frc971/control_loops:jacobian",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
+ ],
+)
+
+cc_test(
+ name = "linearized_controller_test",
+ srcs = ["linearized_controller_test.cc"],
+ deps = [
+ ":linearized_controller",
+ "//aos/testing:googletest",
+ ],
+)
+
+cc_library(
+ name = "auto_diff_jacobian",
+ hdrs = ["auto_diff_jacobian.h"],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ "@com_google_ceres_solver//:ceres",
+ ],
+)
+
+cc_test(
+ name = "auto_diff_jacobian_test",
+ srcs = ["auto_diff_jacobian_test.cc"],
+ deps = [
+ ":auto_diff_jacobian",
+ "//aos/testing:googletest",
+ ],
+)
+
+cc_library(
+ name = "simplified_dynamics",
+ hdrs = ["simplified_dynamics.h"],
+ deps = [
+ ":auto_diff_jacobian",
+ ":eigen_dynamics",
+ ":motors",
+ "//aos/util:math",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
+ ],
+)
+
+cc_test(
+ name = "simplified_dynamics_test",
+ srcs = ["simplified_dynamics_test.cc"],
+ deps = [
+ ":simplified_dynamics",
+ "//aos/testing:googletest",
+ "//aos/time",
+ "//frc971/control_loops:jacobian",
+ "@com_google_absl//absl/log",
+ ],
+)
+
+cc_library(
+ name = "inverse_kinematics",
+ hdrs = ["inverse_kinematics.h"],
+ deps = [
+ ":simplified_dynamics",
+ "//aos/util:math",
+ ],
+)
+
+cc_test(
+ name = "inverse_kinematics_test",
+ srcs = ["inverse_kinematics_test.cc"],
+ deps = [
+ ":inverse_kinematics",
+ "//aos/testing:googletest",
+ ],
+)
diff --git a/frc971/control_loops/swerve/auto_diff_jacobian.h b/frc971/control_loops/swerve/auto_diff_jacobian.h
new file mode 100644
index 0000000..2e7947a
--- /dev/null
+++ b/frc971/control_loops/swerve/auto_diff_jacobian.h
@@ -0,0 +1,62 @@
+#ifndef FRC971_CONTROL_LOOPS_SWERVE_AUTO_DIFF_JACOBIAN_H_
+#define FRC971_CONTROL_LOOPS_SWERVE_AUTO_DIFF_JACOBIAN_H_
+#include "include/ceres/tiny_solver.h"
+#include "include/ceres/tiny_solver_autodiff_function.h"
+
+namespace frc971::control_loops::swerve {
+// Class to conveniently scope a function that makes use of Ceres'
+// autodifferentiation methods to calculate the jacobian of the provided method.
+// Template parameters:
+// Scalar: scalar type to use (typically double or float; this is used for
+// allowing you to control what precision you use; you cannot use this
+// with ceres Jets because this has to use Jets internally).
+// Function: The type of the function itself. A Function f must be callable as
+// Eigen::Matrix<Scalar, kNumOutputs, 1> = f(Eigen::Matrix<Scalar,
+// kNumInputs, 1>{});
+template <typename Scalar, typename Function, size_t kNumInputs,
+ size_t kNumOutputs>
+class AutoDiffJacobian {
+ public:
+ // Calculates the jacobian of the provided method, function, at the provided
+ // input X.
+ static Eigen::Matrix<Scalar, kNumOutputs, kNumInputs> Jacobian(
+ const Function &function, const Eigen::Matrix<Scalar, kNumInputs, 1> &X) {
+ AutoDiffCeresFunctor ceres_functor(function);
+ TinySolverFunctor tiny_solver(ceres_functor);
+ // residual is unused, it's just a place to store the evaluated function at
+ // the current state/input.
+ Eigen::Matrix<Scalar, kNumOutputs, 1> residual;
+ Eigen::Matrix<Scalar, kNumOutputs, kNumInputs> jacobian;
+ tiny_solver(X.data(), residual.data(), jacobian.data());
+ return jacobian;
+ }
+
+ private:
+ // Borrow the TinySolver's auto-differentiation execution for use here to
+ // calculate the linearized dynamics. We aren't actually doing any solving,
+ // just letting it do the jacobian calculation for us.
+ // As such, construct a "residual" function whose residuals are just the
+ // derivative of the state and whose parameters are the stacked state + input.
+ class AutoDiffCeresFunctor {
+ public:
+ AutoDiffCeresFunctor(const Function &function) : function_(function) {}
+ template <typename ScalarT>
+ bool operator()(const ScalarT *const parameters,
+ ScalarT *const residuals) const {
+ const Eigen::Map<const Eigen::Matrix<ScalarT, kNumInputs, 1>>
+ eigen_parameters(parameters);
+ Eigen::Map<Eigen::Matrix<ScalarT, kNumOutputs, 1>> eigen_residuals(
+ residuals);
+ eigen_residuals = function_(eigen_parameters);
+ return true;
+ }
+
+ private:
+ const Function &function_;
+ };
+ typedef ceres::TinySolverAutoDiffFunction<AutoDiffCeresFunctor, kNumOutputs,
+ kNumInputs, Scalar>
+ TinySolverFunctor;
+};
+} // namespace frc971::control_loops::swerve
+#endif // FRC971_CONTROL_LOOPS_SWERVE_AUTO_DIFF_JACOBIAN_H_
diff --git a/frc971/control_loops/swerve/auto_diff_jacobian_test.cc b/frc971/control_loops/swerve/auto_diff_jacobian_test.cc
new file mode 100644
index 0000000..d04726c
--- /dev/null
+++ b/frc971/control_loops/swerve/auto_diff_jacobian_test.cc
@@ -0,0 +1,23 @@
+#include "frc971/control_loops/swerve/auto_diff_jacobian.h"
+
+#include <functional>
+
+#include "absl/log/log.h"
+#include "gtest/gtest.h"
+
+namespace frc971::control_loops::swerve::testing {
+struct TestFunction {
+ template <typename Scalar>
+ Eigen::Matrix<Scalar, 3, 1> operator()(
+ const Eigen::Map<const Eigen::Matrix<Scalar, 2, 1>> X) const {
+ return Eigen::Matrix<double, 3, 2>{{1, 2}, {3, 4}, {5, 6}} * X;
+ }
+};
+
+TEST(AutoDiffJacobianTest, EvaluatesJacobian) {
+ EXPECT_EQ((AutoDiffJacobian<double, TestFunction, 2, 3>::Jacobian(
+ TestFunction{}, Eigen::Vector2d::Zero())),
+ (Eigen::Matrix<double, 3, 2>{{1, 2}, {3, 4}, {5, 6}}));
+}
+
+} // namespace frc971::control_loops::swerve::testing
diff --git a/frc971/control_loops/swerve/casadi_velocity_mpc.py b/frc971/control_loops/swerve/casadi_velocity_mpc.py
index 239f49a..54e33f1 100644
--- a/frc971/control_loops/swerve/casadi_velocity_mpc.py
+++ b/frc971/control_loops/swerve/casadi_velocity_mpc.py
@@ -1,6 +1,7 @@
#!/usr/bin/env python3
from frc971.control_loops.swerve import dynamics
+from frc971.control_loops.swerve.casadi_velocity_mpc_lib import MPC
import pickle
import matplotlib.pyplot as pyplot
import matplotlib
@@ -23,252 +24,6 @@
flags.DEFINE_bool('pickle', False, 'Write optimization results.')
flags.DEFINE_string('outputdir', None, 'Directory to write problem results to')
-matplotlib.use("GTK3Agg")
-
-# Full print level on ipopt. Piping to a file and using a filter or search method is suggested
-# grad_x prints out the gradient at each iteration in the following sequence: U0, X1, U1, etc.
-full_debug = False
-
-
-class MPC(object):
-
- def __init__(self, solver='fatrop'):
- self.fdot = dynamics.swerve_full_dynamics(
- casadi.SX.sym("X", dynamics.NUM_STATES, 1),
- casadi.SX.sym("U", 8, 1))
- self.velocity_fdot = dynamics.velocity_swerve_physics(
- casadi.SX.sym("X", dynamics.NUM_VELOCITY_STATES, 1),
- casadi.SX.sym("U", 8, 1))
-
- self.wrapped_swerve_physics = lambda X, U: numpy.array(self.fdot(X, U))
-
- self.dt = 0.005
-
- # TODO(austin): Do we need a disturbance torque per module to account for friction?
- # Do it only in the observer/post?
-
- self.next_X = self.make_physics()
- self.cost = self.make_cost()
- self.force = [
- dynamics.F(i, casadi.SX.sym("X", 25, 1), casadi.SX.sym("U", 8, 1))
- for i in range(4)
- ]
- self.slip_angle = [
- dynamics.slip_angle(i, casadi.SX.sym("X", 25, 1),
- casadi.SX.sym("U", 8, 1)) for i in range(4)
- ]
-
- self.N = 200
-
- # Start with an empty nonlinear program.
- self.w = []
- self.lbw = []
- self.ubw = []
- J = 0
- self.g = []
- self.lbg = []
- self.ubg = []
-
- self.X0 = casadi.MX.sym('X0', dynamics.NUM_VELOCITY_STATES)
-
- # We care about the linear and angular velocities only.
- self.R = casadi.MX.sym('R', 3)
-
- # Make Xn and U for each step. fatrop wants us to interleave the control variables and
- # states so that it can produce a banded/structured problem which it can solve a lot
- # faster.
- Xn_variables = []
- U_variables = []
- for i in range(self.N):
- U_variables.append(casadi.MX.sym(f'U{i}', 8))
-
- if i == 0:
- continue
-
- Xn_variables.append(
- casadi.MX.sym(f'X{i}', dynamics.NUM_VELOCITY_STATES))
-
- Xn = casadi.horzcat(*Xn_variables)
- U = casadi.horzcat(*U_variables)
-
- # printme(number) is the debug.
- Xk_begin = casadi.horzcat(self.X0, Xn)
- Xk_end = self.next_X.map(self.N, "thread")(Xk_begin, U)
- J = casadi.sum2(self.cost.map(self.N, "thread")(Xk_end, U, self.R))
-
- # Put U and Xn interleaved into w to go fast.
- for i in range(self.N):
- self.w += [U_variables[i]]
- self.ubw += [100] * 8
- self.lbw += [-100] * 8
-
- if i == self.N - 1:
- continue
-
- self.w += [Xn_variables[i]]
- self.ubw += [casadi.inf] * dynamics.NUM_VELOCITY_STATES
- self.lbw += [-casadi.inf] * dynamics.NUM_VELOCITY_STATES
-
- self.g += [
- casadi.reshape(Xn - Xk_end[:, 0:(self.N - 1)],
- dynamics.NUM_VELOCITY_STATES * (self.N - 1), 1)
- ]
-
- self.lbg += [0] * dynamics.NUM_VELOCITY_STATES * (self.N - 1)
- self.ubg += [0] * dynamics.NUM_VELOCITY_STATES * (self.N - 1)
-
- prob = {
- 'f': J,
- # lbx <= x <= ubx
- 'x': casadi.vertcat(*self.w),
- # lbg <= g(x, p) <= ubg
- 'g': casadi.vertcat(*self.g),
- # Input parameters (initial position + goal)
- 'p': casadi.vertcat(self.X0, self.R),
- }
-
- compiler = "ccache clang"
- flags = ["-O3"]
- jit_options = {
- "flags": flags,
- "verbose": False,
- "compiler": compiler,
- "temp_suffix": False,
- }
-
- if solver == 'fatrop':
- equality = [
- True
- for _ in range(dynamics.NUM_VELOCITY_STATES * (self.N - 1))
- ]
- options = {
- "jit": True,
- "jit_cleanup": False,
- "jit_temp_suffix": False,
- "compiler": "shell",
- "jit_options": jit_options,
- "structure_detection": "auto",
- "fatrop": {
- "tol": 1e-7
- },
- "debug": True,
- "equality": equality,
- }
- else:
- options = {
- "jit": True,
- "jit_cleanup": False,
- "jit_temp_suffix": False,
- "compiler": "shell",
- "jit_options": jit_options,
- }
- if full_debug:
- options["jit"] = False
- options["ipopt"] = {
- "print_level": 12,
- }
-
- self.solver = casadi.nlpsol('solver', solver, prob, options)
-
- # TODO(austin): Vary the number of sub steps to be more short term and fewer long term?
- def make_physics(self):
- X0 = casadi.MX.sym('X0', dynamics.NUM_VELOCITY_STATES)
- U = casadi.MX.sym('U', 8)
-
- X = X0
- M = 2 # RK4 steps per interval
- DT = self.dt / M
-
- for j in range(M):
- k1 = self.velocity_fdot(X, U)
- k2 = self.velocity_fdot(X + DT / 2 * k1, U)
- k3 = self.velocity_fdot(X + DT / 2 * k2, U)
- k4 = self.velocity_fdot(X + DT * k3, U)
- X = X + DT / 6 * (k1 + 2 * k2 + 2 * k3 + k4)
-
- return casadi.Function("next_X", [X0, U], [X])
-
- def make_cost(self):
- # TODO(austin): tune cost fn?
- # Do we want to penalize slipping tires?
- # Do we want to penalize powers unevenly applied across the motors?
- # Need to do some simulations to see what works well.
-
- X = casadi.MX.sym('X', dynamics.NUM_VELOCITY_STATES)
- U = casadi.MX.sym('U', 8)
- R = casadi.MX.sym('R', 3)
-
- J = 0
- vnorm = casadi.sqrt(R[0]**2.0 + R[1]**2.0)
-
- vnormx = casadi.if_else(vnorm > 0.0001, R[0] / vnorm, 1.0)
- vnormy = casadi.if_else(vnorm > 0.0001, R[1] / vnorm, 0.0)
-
- vperpx = casadi.if_else(vnorm > 0.0001, -vnormy, 0.0)
- vperpy = casadi.if_else(vnorm > 0.0001, vnormx, 1.0)
-
- # TODO(austin): Do we want to do something more special for 0?
-
- J += 75 * ((R[0] - X[dynamics.VELOCITY_STATE_VX]) * vnormx +
- (R[1] - X[dynamics.VELOCITY_STATE_VY]) * vnormy)**2.0
-
- J += 1500 * ((R[0] - X[dynamics.VELOCITY_STATE_VX]) * vperpx +
- (R[1] - X[dynamics.VELOCITY_STATE_VY]) * vperpy)**2.0
-
- J += 1000 * (R[2] - X[dynamics.VELOCITY_STATE_OMEGA])**2.0
-
- kSteerPositionGain = 0
- kSteerVelocityGain = 0.10
- J += kSteerPositionGain * (X[dynamics.VELOCITY_STATE_THETAS0])**2.0
- J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS0])**2.0
-
- J += kSteerPositionGain * (X[dynamics.VELOCITY_STATE_THETAS1])**2.0
- J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS1])**2.0
-
- J += kSteerPositionGain * (X[dynamics.VELOCITY_STATE_THETAS2])**2.0
- J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS2])**2.0
-
- J += kSteerPositionGain * (X[dynamics.VELOCITY_STATE_THETAS3])**2.0
- J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS3])**2.0
-
- # TODO(austin): Don't penalize torque steering current.
- for i in range(4):
- Is = U[2 * i + 0]
- Id = U[2 * i + 1]
- # Steer
- J += ((Is + dynamics.STEER_CURRENT_COUPLING_FACTOR * Id)**
- 2.0) / 100000.0
- # Drive
- J += Id * Id / 1000.0
-
- return casadi.Function("Jn", [X, U, R], [J])
-
- def solve(self, p, seed=None):
- if seed is None:
- seed = []
-
- for i in range(self.N):
- seed += [0, 0] * 4
- if i < self.N - 1:
- seed += list(p[:dynamics.NUM_VELOCITY_STATES, 0])
-
- return self.solver(x0=seed,
- lbx=self.lbw,
- ubx=self.ubw,
- lbg=self.lbg,
- ubg=self.ubg,
- p=casadi.DM(p))
-
- def unpack_u(self, sol, i):
- return sol['x'].full().flatten()[
- (8 + dynamics.NUM_VELOCITY_STATES) *
- i:((8 + dynamics.NUM_VELOCITY_STATES) * i + 8)]
-
- def unpack_x(self, sol, i):
- return sol['x'].full().flatten(
- )[8 + (8 + dynamics.NUM_VELOCITY_STATES) *
- (i - 1):(8 + dynamics.NUM_VELOCITY_STATES) * i]
-
class Solver(object):
@@ -334,6 +89,9 @@
self.X_plot[dynamics.STATE_VX, 0:i + 1],
label="vx")
axs0[0].plot(self.t,
+ self.X_plot[dynamics.STATE_OMEGA, 0:i + 1],
+ label="omega")
+ axs0[0].plot(self.t,
self.X_plot[dynamics.STATE_VY, 0:i + 1],
label="vy")
axs0[0].legend()
@@ -375,10 +133,12 @@
last_time = time.time()
- print(f"Tool {overall_time} seconds overall to solve.")
+ print(f"Took {overall_time} seconds overall to solve.")
def main(argv):
+ matplotlib.use("GTK3Agg")
+
if FLAGS.outputdir:
os.chdir(FLAGS.outputdir)
@@ -409,7 +169,7 @@
R_goal[1, 0] = FLAGS.vy
R_goal[2, 0] = FLAGS.omega
- mpc = MPC(solver='fatrop') if not full_debug else MPC(solver='ipopt')
+ mpc = MPC(solver='fatrop') if not FLAGS.full_debug else MPC(solver='ipopt')
solver = Solver()
if not FLAGS.compileonly:
results = solver.solve(mpc=mpc,
diff --git a/frc971/control_loops/swerve/casadi_velocity_mpc_lib.py b/frc971/control_loops/swerve/casadi_velocity_mpc_lib.py
new file mode 100644
index 0000000..e358422
--- /dev/null
+++ b/frc971/control_loops/swerve/casadi_velocity_mpc_lib.py
@@ -0,0 +1,288 @@
+#!/usr/bin/env python3
+
+from frc971.control_loops.swerve import dynamics
+import casadi
+import numpy
+from absl import flags
+
+FLAGS = flags.FLAGS
+
+# Full print level on ipopt. Piping to a file and using a filter or search method is suggested
+# grad_x prints out the gradient at each iteration in the following sequence: U0, X1, U1, etc.
+flags.DEFINE_bool('full_debug', False,
+ 'If true, turn on all the debugging in the solver.')
+
+
+class MPC(object):
+
+ def __init__(self, solver='fatrop', jit=True, N=200):
+ self.fdot = dynamics.swerve_full_dynamics(
+ casadi.SX.sym("X", dynamics.NUM_STATES, 1),
+ casadi.SX.sym("U", 8, 1))
+ self.velocity_fdot = dynamics.velocity_swerve_physics(
+ casadi.SX.sym("X", dynamics.NUM_VELOCITY_STATES, 1),
+ casadi.SX.sym("U", 8, 1))
+
+ self.wrapped_swerve_physics = lambda X, U: numpy.array(self.fdot(X, U))
+
+ self.dt = 0.005
+
+ # TODO(austin): Do we need a disturbance torque per module to account for friction?
+ # Do it only in the observer/post?
+
+ self.force = [
+ dynamics.F(i, casadi.SX.sym("X", 25, 1), casadi.SX.sym("U", 8, 1))
+ for i in range(4)
+ ]
+ self.force_vel = [
+ dynamics.F_vel(i,
+ casadi.SX.sym("X", dynamics.NUM_VELOCITY_STATES, 1),
+ casadi.SX.sym("U", 8, 1)) for i in range(4)
+ ]
+ self.slip_angle = [
+ dynamics.slip_angle(i, casadi.SX.sym("X", 25, 1),
+ casadi.SX.sym("U", 8, 1)) for i in range(4)
+ ]
+ self.rotated_mounting_location = [
+ dynamics.rotated_mounting_location(
+ i, casadi.SX.sym("X", dynamics.NUM_VELOCITY_STATES, 1),
+ casadi.SX.sym("U", 8, 1)) for i in range(4)
+ ]
+ self.torque_cross = self.torque_cross_func(casadi.SX.sym("r", 2, 1),
+ casadi.SX.sym("F", 2, 1))
+ self.force_cross = self.force_cross_func(casadi.SX.sym("Tau", 1, 1),
+ casadi.SX.sym("r", 2, 1))
+ self.next_X = self.make_physics()
+ self.cost = self.make_cost()
+
+ self.N = N
+
+ # Start with an empty nonlinear program.
+ self.w = []
+ self.lbw = []
+ self.ubw = []
+ J = 0
+ self.g = []
+ self.lbg = []
+ self.ubg = []
+
+ self.X0 = casadi.MX.sym('X0', dynamics.NUM_VELOCITY_STATES)
+
+ # We care about the linear and angular velocities only.
+ self.R = casadi.MX.sym('R', 3)
+
+ # Make Xn and U for each step. fatrop wants us to interleave the control variables and
+ # states so that it can produce a banded/structured problem which it can solve a lot
+ # faster.
+ Xn_variables = []
+ U_variables = []
+ for i in range(self.N):
+ U_variables.append(casadi.MX.sym(f'U{i}', 8))
+
+ if i == 0:
+ continue
+
+ Xn_variables.append(
+ casadi.MX.sym(f'X{i}', dynamics.NUM_VELOCITY_STATES))
+
+ Xn = casadi.horzcat(*Xn_variables)
+ U = casadi.horzcat(*U_variables)
+
+ # printme(number) is the debug.
+ Xk_begin = casadi.horzcat(self.X0, Xn)
+ Xk_end = self.next_X.map(self.N, "thread")(Xk_begin, U)
+ J = casadi.sum2(self.cost.map(self.N, "thread")(Xk_end, U, self.R))
+
+ # Put U and Xn interleaved into w to go fast.
+ for i in range(self.N):
+ self.w += [U_variables[i]]
+ self.ubw += [100] * 8
+ self.lbw += [-100] * 8
+
+ if i == self.N - 1:
+ continue
+
+ self.w += [Xn_variables[i]]
+ self.ubw += [casadi.inf] * dynamics.NUM_VELOCITY_STATES
+ self.lbw += [-casadi.inf] * dynamics.NUM_VELOCITY_STATES
+
+ self.g += [
+ casadi.reshape(Xn - Xk_end[:, 0:(self.N - 1)],
+ dynamics.NUM_VELOCITY_STATES * (self.N - 1), 1)
+ ]
+
+ self.lbg += [0] * dynamics.NUM_VELOCITY_STATES * (self.N - 1)
+ self.ubg += [0] * dynamics.NUM_VELOCITY_STATES * (self.N - 1)
+
+ prob = {
+ 'f': J,
+ # lbx <= x <= ubx
+ 'x': casadi.vertcat(*self.w),
+ # lbg <= g(x, p) <= ubg
+ 'g': casadi.vertcat(*self.g),
+ # Input parameters (initial position + goal)
+ 'p': casadi.vertcat(self.X0, self.R),
+ }
+
+ compiler = "ccache clang"
+ flags = ["-O3"]
+ jit_options = {
+ "flags": flags,
+ "verbose": True,
+ "compiler": compiler,
+ "temp_suffix": False,
+ }
+
+ if solver == 'fatrop':
+ equality = [
+ True
+ for _ in range(dynamics.NUM_VELOCITY_STATES * (self.N - 1))
+ ]
+ options = {
+ "jit": jit,
+ "jit_cleanup": False,
+ "jit_temp_suffix": False,
+ "compiler": "shell",
+ "jit_options": jit_options,
+ "structure_detection": "auto",
+ "fatrop": {
+ "tol": 1e-7
+ },
+ "debug": True,
+ "equality": equality,
+ }
+ else:
+ options = {
+ "jit": jit,
+ "jit_cleanup": False,
+ "jit_temp_suffix": False,
+ "compiler": "shell",
+ "jit_options": jit_options,
+ }
+ if FLAGS.full_debug:
+ options["jit"] = False
+ options["ipopt"] = {
+ "print_level": 12,
+ }
+
+ self.solver = casadi.nlpsol('solver', solver, prob, options)
+
+ # TODO(austin): Vary the number of sub steps to be more short term and fewer long term?
+ def make_physics(self):
+ X0 = casadi.MX.sym('X0', dynamics.NUM_VELOCITY_STATES)
+ U = casadi.MX.sym('U', 8)
+
+ X = X0
+ M = 2 # RK4 steps per interval
+ DT = self.dt / M
+
+ for j in range(M):
+ k1 = self.velocity_fdot(X, U)
+ k2 = self.velocity_fdot(X + DT / 2 * k1, U)
+ k3 = self.velocity_fdot(X + DT / 2 * k2, U)
+ k4 = self.velocity_fdot(X + DT * k3, U)
+ X = X + DT / 6 * (k1 + 2 * k2 + 2 * k3 + k4)
+
+ return casadi.Function("next_X", [X0, U], [X])
+
+ def make_cost(self):
+ # TODO(austin): tune cost fn?
+ # Need to do some simulations to see what works well.
+
+ X = casadi.MX.sym('X', dynamics.NUM_VELOCITY_STATES)
+ U = casadi.MX.sym('U', 8)
+ R = casadi.MX.sym('R', 3)
+
+ J = 0
+ vnorm = casadi.sqrt(R[0]**2.0 + R[1]**2.0)
+
+ vnormx = casadi.if_else(vnorm > 0.0001, R[0] / vnorm, 1.0)
+ vnormy = casadi.if_else(vnorm > 0.0001, R[1] / vnorm, 0.0)
+
+ vperpx = casadi.if_else(vnorm > 0.0001, -vnormy, 0.0)
+ vperpy = casadi.if_else(vnorm > 0.0001, vnormx, 1.0)
+
+ # TODO(austin): Do we want to do something more special for 0?
+
+ # cost velocity a lot more in the perpendicular direction to allow tire to spin up
+ # we also only want to get moving in the correct direction as fast as possible
+ J += 75 * ((R[0] - X[dynamics.VELOCITY_STATE_VX]) * vnormx +
+ (R[1] - X[dynamics.VELOCITY_STATE_VY]) * vnormy)**2.0
+
+ J += 1500 * ((R[0] - X[dynamics.VELOCITY_STATE_VX]) * vperpx +
+ (R[1] - X[dynamics.VELOCITY_STATE_VY]) * vperpy)**2.0
+
+ J += 1000 * (R[2] - X[dynamics.VELOCITY_STATE_OMEGA])**2.0
+
+ kSteerVelocityGain = 0.10
+ J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS0])**2.0
+ J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS1])**2.0
+ J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS2])**2.0
+ J += kSteerVelocityGain * (X[dynamics.VELOCITY_STATE_OMEGAS3])**2.0
+
+ # cost variance of the force by a tire and the expected average force and torque on it
+ total_force = self.force_vel[0](X, U)
+ total_torque = self.torque_cross(
+ self.rotated_mounting_location[0](X, U), self.force_vel[0](X, U))
+ for i in range(3):
+ total_force += self.force_vel[i + 1](X, U)
+ total_torque += self.torque_cross(
+ self.rotated_mounting_location[i + 1](X, U),
+ self.force_vel[i + 1](X, U))
+
+ total_force /= 4
+ total_torque /= 4
+ for i in range(4):
+ f_diff = (total_force + self.force_cross(
+ total_torque, self.rotated_mounting_location[i]
+ (X, U))) - self.force_vel[i](X, U)
+ J += 0.01 * (f_diff[0, 0]**2.0 + f_diff[1, 0]**2.0)
+
+ # TODO(austin): Don't penalize torque steering current.
+ for i in range(4):
+ Is = U[2 * i + 0]
+ Id = U[2 * i + 1]
+ # Steer, cost it a lot less than drive to be more agressive in steering
+ J += ((Is + dynamics.STEER_CURRENT_COUPLING_FACTOR * Id)**
+ 2.0) / 100000.0
+ # Drive
+ J += Id * Id / 1000.0
+
+ return casadi.Function("Jn", [X, U, R], [J])
+
+ def torque_cross_func(self, r, F):
+ result = casadi.SX.sym('Tau', 1, 1)
+ result[0, 0] = r[0, 0] * F[1, 0] - r[1, 0] * F[0, 0]
+ return casadi.Function('Tau', [r, F], [result])
+
+ def force_cross_func(self, Tau, r):
+ result = casadi.SX.sym('F', 2, 1)
+ result[0, 0] = -r[1, 0] * Tau[0, 0] / casadi.norm_2(r)**2.0
+ result[1, 0] = r[0, 0] * Tau[0, 0] / casadi.norm_2(r)**2.0
+ return casadi.Function('F', [Tau, r], [result])
+
+ def solve(self, p, seed=None):
+ if seed is None:
+ seed = []
+
+ for i in range(self.N):
+ seed += [0, 0] * 4
+ if i < self.N - 1:
+ seed += list(p[:dynamics.NUM_VELOCITY_STATES, 0])
+
+ return self.solver(x0=seed,
+ lbx=self.lbw,
+ ubx=self.ubw,
+ lbg=self.lbg,
+ ubg=self.ubg,
+ p=casadi.DM(p))
+
+ def unpack_u(self, sol, i):
+ return sol['x'].full().flatten()[
+ (8 + dynamics.NUM_VELOCITY_STATES) *
+ i:((8 + dynamics.NUM_VELOCITY_STATES) * i + 8)]
+
+ def unpack_x(self, sol, i):
+ return sol['x'].full().flatten(
+ )[8 + (8 + dynamics.NUM_VELOCITY_STATES) *
+ (i - 1):(8 + dynamics.NUM_VELOCITY_STATES) * i]
diff --git a/frc971/control_loops/swerve/dynamics_python_bindings.cc b/frc971/control_loops/swerve/dynamics_python_bindings.cc
new file mode 100644
index 0000000..e1fbe19
--- /dev/null
+++ b/frc971/control_loops/swerve/dynamics_python_bindings.cc
@@ -0,0 +1,103 @@
+#define PY_SSIZE_T_CLEAN
+// Note that Python.h needs to be included before anything else.
+#include <Python.h>
+
+#include <iostream>
+#include <optional>
+
+#include "frc971/control_loops/swerve/dynamics.h"
+
+namespace frc971::control_loops::swerve {
+namespace {
+template <int N>
+std::optional<Eigen::Matrix<double, N, 1>> ToEigen(PyObject *list) {
+ Eigen::Matrix<double, N, 1> result;
+ for (size_t index = 0; index < N; ++index) {
+ PyObject *element = PyList_GetItem(list, index);
+ if (!PyFloat_Check(element)) {
+ PyErr_SetString(PyExc_ValueError,
+ "Input lists should be lists of floats.");
+ return std::nullopt;
+ }
+ result(index) = PyFloat_AsDouble(element);
+ }
+ return result;
+}
+PyObject *swerve_dynamics(PyObject * /*self*/, PyObject *args) {
+ PyObject *X;
+ PyObject *U;
+ if (!PyArg_ParseTuple(args, "OO", &X, &U)) {
+ PyErr_SetString(PyExc_ValueError, "Input arguments should be two lists.");
+ return nullptr;
+ }
+
+ if (!PyList_Check(X)) {
+ PyErr_SetString(PyExc_ValueError, "X should be a list.");
+ return nullptr;
+ }
+ if (!PyList_Check(U)) {
+ PyErr_SetString(PyExc_ValueError, "U should be a list.");
+ return nullptr;
+ }
+
+ if (PyList_Size(X) != kNumFullDynamicsStates) {
+ PyErr_SetString(PyExc_ValueError,
+ "X should have kNumFullDynamicsStates elements.");
+ return nullptr;
+ }
+
+ if (PyList_Size(U) != kNumInputs) {
+ PyErr_SetString(PyExc_ValueError, "U should have kNumInputs elements.");
+ return nullptr;
+ }
+
+ std::optional<Eigen::Matrix<double, kNumFullDynamicsStates, 1>> X_eig =
+ ToEigen<kNumFullDynamicsStates>(X);
+
+ if (!X_eig.has_value()) {
+ return nullptr;
+ }
+
+ std::optional<Eigen::Matrix<double, kNumInputs, 1>> U_eig =
+ ToEigen<kNumInputs>(X);
+
+ if (!U_eig.has_value()) {
+ return nullptr;
+ }
+
+ Eigen::Matrix<double, kNumFullDynamicsStates, 1> Xdot =
+ SwervePhysics(X_eig.value(), U_eig.value());
+
+ PyObject *result = PyList_New(kNumFullDynamicsStates);
+ for (size_t index = 0; index < kNumFullDynamicsStates; ++index) {
+ if (PyList_SetItem(result, index, PyFloat_FromDouble(Xdot(index))) != 0) {
+ return nullptr;
+ }
+ }
+
+ return result;
+}
+
+static PyMethodDef methods[] = {
+ {"swerve_dynamics", swerve_dynamics, METH_VARARGS,
+ "Xdot = swerve_dynamics(X, U), all types are lists."},
+ {NULL, NULL, 0, NULL} // Sentinel
+};
+
+static PyModuleDef cpp_dynamics_module = {
+ .m_base = PyModuleDef_HEAD_INIT,
+ .m_name = "cpp_dynamics",
+ .m_doc =
+ "Wraps the generated C++ dynamics in order to support convenient "
+ "testing.",
+ .m_size = -1,
+ .m_methods = methods,
+};
+
+PyObject *InitModule() { return PyModule_Create(&cpp_dynamics_module); }
+} // namespace
+} // namespace frc971::control_loops::swerve
+
+PyMODINIT_FUNC PyInit_cpp_dynamics(void) {
+ return frc971::control_loops::swerve::InitModule();
+}
diff --git a/frc971/control_loops/swerve/experience_collector.py b/frc971/control_loops/swerve/experience_collector.py
new file mode 100644
index 0000000..b4c17fb
--- /dev/null
+++ b/frc971/control_loops/swerve/experience_collector.py
@@ -0,0 +1,201 @@
+#!/usr/bin/env python3
+import os, sys
+
+# Setup XLA first.
+os.environ['XLA_FLAGS'] = ' '.join([
+ # Teach it where to find CUDA
+ '--xla_gpu_cuda_data_dir=/usr/lib/cuda',
+ # Use up to 20 cores
+ #'--xla_force_host_platform_device_count=6',
+ # Dump XLA to /tmp/foo to aid debugging
+ #'--xla_dump_to=/tmp/foo',
+ #'--xla_gpu_enable_command_buffer='
+ # Dump sharding
+ #"--xla_dump_to=/tmp/foo",
+ #"--xla_dump_hlo_pass_re=spmd|propagation"
+])
+os.environ['JAX_PLATFORMS'] = 'cpu'
+os.environ['XLA_PYTHON_CLIENT_PREALLOCATE'] = 'false'
+os.environ['XLA_PYTHON_CLIENT_MEM_FRACTION'] = '.50'
+
+from absl import flags
+from absl import app
+from absl import logging
+import pickle
+import numpy
+from frc971.control_loops.swerve import dynamics
+from frc971.control_loops.swerve.casadi_velocity_mpc_lib import MPC
+import jax
+import tensorflow as tf
+from frc971.control_loops.swerve.velocity_controller.physics import SwerveProblem
+from frc971.control_loops.swerve import jax_dynamics
+
+FLAGS = flags.FLAGS
+
+flags.DEFINE_bool('compileonly', False,
+ 'If true, load casadi, don\'t compile it')
+
+flags.DEFINE_float('vx', 1.0, 'Goal velocity in m/s in x')
+flags.DEFINE_float('vy', 0.0, 'Goal velocity in m/s in y')
+flags.DEFINE_float('omega', 0.0, 'Goal velocity in m/s in omega')
+flags.DEFINE_integer('seed', 0, 'Seed for random initial state.')
+
+flags.DEFINE_bool('save_plots', True,
+ 'If true, save plots for each run as well.')
+flags.DEFINE_string('outputdir', None, 'Directory to write problem results to')
+flags.DEFINE_bool('quiet', False, 'If true, print a lot less')
+
+flags.DEFINE_integer('num_solutions', 100,
+ 'Number of random problems to solve.')
+flags.DEFINE_integer('horizon', 200, 'Horizon to solve for')
+
+try:
+ from matplotlib import pylab
+except ModuleNotFoundError:
+ pass
+
+
+def collect_experience(problem, mpc, rng):
+ X_initial = numpy.array(problem.random_states(rng,
+ dimensions=1)).transpose()
+
+ R_goal = numpy.zeros((3, 1))
+ R_goal[0, 0] = FLAGS.vx
+ R_goal[1, 0] = FLAGS.vy
+ R_goal[2, 0] = FLAGS.omega
+
+ solution = mpc.solve(p=numpy.vstack((X_initial, R_goal)))
+ sys.stderr.flush()
+ sys.stdout.flush()
+
+ # Solver doesn't solve for the last state. So we get N-1 states back.
+ experience = {
+ 'observations1': numpy.zeros((mpc.N - 1, problem.num_states)),
+ 'observations2': numpy.zeros((mpc.N - 1, problem.num_states)),
+ 'actions': numpy.zeros((mpc.N - 1, problem.num_outputs)),
+ 'rewards': numpy.zeros((mpc.N - 1, 1)),
+ 'goals': numpy.zeros((mpc.N - 1, problem.num_goals)),
+ }
+
+ if not FLAGS.quiet:
+ print('x(0):', X_initial.transpose())
+
+ logging.info('Finished solving')
+ X_prior = X_initial.squeeze()
+ for j in range(mpc.N - 1):
+ if not FLAGS.quiet:
+ print(f'u({j}): ', mpc.unpack_u(solution, j))
+ print(f'x({j+1}): ', mpc.unpack_x(solution, j + 1))
+ experience['observations1'][j, :] = X_prior
+ X_prior = mpc.unpack_x(solution, j + 1)
+ experience['observations2'][j, :] = X_prior
+ experience['actions'][j, :] = mpc.unpack_u(solution, j)
+ experience['goals'][j, :] = R_goal[:, 0]
+
+ logging.info('Finished all but reward')
+ for j in range(mpc.N - 1):
+ experience['rewards'][j, :] = problem.reward(
+ X=X_prior,
+ U=mpc.unpack_u(solution, j),
+ goal=R_goal[:, 0],
+ )
+ sys.stderr.flush()
+ sys.stdout.flush()
+
+ return experience
+
+
+def save_experience(problem, mpc, experience, experience_number):
+ with open(f'experience_{experience_number}.pkl', 'wb') as f:
+ pickle.dump(experience, f)
+
+ if not FLAGS.save_plots:
+ return
+
+ fig0, axs0 = pylab.subplots(3)
+ fig1, axs1 = pylab.subplots(2)
+
+ axs0[0].clear()
+ axs0[1].clear()
+ axs0[2].clear()
+
+ t = problem.dt * numpy.array(list(range(mpc.N - 1)))
+
+ X_plot = experience['observations1']
+ U_plot = experience['actions']
+
+ axs0[0].plot(t, X_plot[:, dynamics.VELOCITY_STATE_VX], label="vx")
+ axs0[0].plot(t, X_plot[:, dynamics.VELOCITY_STATE_VY], label="vy")
+ axs0[0].plot(t, X_plot[:, dynamics.VELOCITY_STATE_OMEGA], label="omega")
+ axs0[0].legend()
+
+ axs0[1].plot(t, U_plot[:, 0], label="Is0")
+ axs0[1].plot(t, U_plot[:, 2], label="Is1")
+ axs0[1].plot(t, U_plot[:, 4], label="Is2")
+ axs0[1].plot(t, U_plot[:, 6], label="Is3")
+ axs0[1].legend()
+
+ axs0[2].plot(t, U_plot[:, 1], label="Id0")
+ axs0[2].plot(t, U_plot[:, 3], label="Id1")
+ axs0[2].plot(t, U_plot[:, 5], label="Id2")
+ axs0[2].plot(t, U_plot[:, 7], label="Id3")
+ axs0[2].legend()
+
+ axs1[0].clear()
+ axs1[1].clear()
+
+ axs1[0].plot(t, X_plot[:, dynamics.VELOCITY_STATE_THETAS0], label='steer0')
+ axs1[0].plot(t, X_plot[:, dynamics.VELOCITY_STATE_THETAS1], label='steer1')
+ axs1[0].plot(t, X_plot[:, dynamics.VELOCITY_STATE_THETAS2], label='steer2')
+ axs1[0].plot(t, X_plot[:, dynamics.VELOCITY_STATE_THETAS3], label='steer3')
+ axs1[0].legend()
+ axs1[1].plot(t,
+ X_plot[:, dynamics.VELOCITY_STATE_OMEGAS0],
+ label='steer_velocity0')
+ axs1[1].plot(t,
+ X_plot[:, dynamics.VELOCITY_STATE_OMEGAS1],
+ label='steer_velocity1')
+ axs1[1].plot(t,
+ X_plot[:, dynamics.VELOCITY_STATE_OMEGAS2],
+ label='steer_velocity2')
+ axs1[1].plot(t,
+ X_plot[:, dynamics.VELOCITY_STATE_OMEGAS3],
+ label='steer_velocity3')
+ axs1[1].legend()
+
+ fig0.savefig(f'state_{experience_number}.svg')
+ fig1.savefig(f'steer_{experience_number}.svg')
+
+ # Free the memory associated with the figures.
+ fig0.clf()
+ fig1.clf()
+ pylab.close(fig0)
+ pylab.close(fig1)
+
+
+def main(argv):
+ if FLAGS.outputdir:
+ os.chdir(FLAGS.outputdir)
+
+ # Hide any GPUs from TensorFlow. Otherwise it might reserve memory.
+ tf.config.experimental.set_visible_devices([], 'GPU')
+ rng = jax.random.key(FLAGS.seed)
+
+ physics_constants = jax_dynamics.Coefficients()
+ problem = SwerveProblem(physics_constants)
+ mpc = MPC(solver='ipopt', N=(FLAGS.horizon + 1))
+
+ if FLAGS.compileonly:
+ return
+
+ for i in range(FLAGS.num_solutions):
+ rng, rng_init = jax.random.split(rng)
+ experience = collect_experience(problem, mpc, rng_init)
+ logging.info('Solved problem %d', i)
+
+ save_experience(problem, mpc, experience, i)
+ logging.info('Wrote problem %d', i)
+
+
+if __name__ == '__main__':
+ app.run(main)
diff --git a/frc971/control_loops/swerve/generate_physics.cc b/frc971/control_loops/swerve/generate_physics.cc
index e796ec6..8a7fe16 100644
--- a/frc971/control_loops/swerve/generate_physics.cc
+++ b/frc971/control_loops/swerve/generate_physics.cc
@@ -32,6 +32,8 @@
"Path to write generated header code to");
ABSL_FLAG(std::string, casadi_py_output_path, "",
"Path to write casadi generated py code to");
+ABSL_FLAG(std::string, constants_output_path, "",
+ "Path to write constants python code to");
ABSL_FLAG(double, caster, 0.01, "Caster in meters for the module.");
ABSL_FLAG(bool, symbolic, false, "If true, write everything out symbolically.");
@@ -68,6 +70,7 @@
// State per module.
struct Module {
DenseMatrix mounting_location;
+ DenseMatrix rotated_mounting_location;
RCP<const Symbol> Is;
@@ -283,18 +286,84 @@
result_h.emplace_back("");
result_h.emplace_back("namespace frc971::control_loops::swerve {");
result_h.emplace_back("");
+ result_h.emplace_back("struct FullDynamicsStates {");
+ result_h.emplace_back("enum States {");
+ result_h.emplace_back(" kThetas0 = 0,");
+ result_h.emplace_back(" kThetad0 = 1,");
+ result_h.emplace_back(" kOmegas0 = 2,");
+ result_h.emplace_back(" kOmegad0 = 3,");
+ result_h.emplace_back(" kThetas1 = 4,");
+ result_h.emplace_back(" kThetad1 = 5,");
+ result_h.emplace_back(" kOmegas1 = 6,");
+ result_h.emplace_back(" kOmegad1 = 7,");
+ result_h.emplace_back(" kThetas2 = 8,");
+ result_h.emplace_back(" kThetad2 = 9,");
+ result_h.emplace_back(" kOmegas2 = 10,");
+ result_h.emplace_back(" kOmegad2 = 11,");
+ result_h.emplace_back(" kThetas3 = 12,");
+ result_h.emplace_back(" kThetad3 = 13,");
+ result_h.emplace_back(" kOmegas3 = 14,");
+ result_h.emplace_back(" kOmegad3 = 15,");
+ result_h.emplace_back(" kX = 16,");
+ result_h.emplace_back(" kY = 17,");
+ result_h.emplace_back(" kTheta = 18,");
+ result_h.emplace_back(" kVx = 19,");
+ result_h.emplace_back(" kVy = 20,");
+ result_h.emplace_back(" kOmega = 21,");
+ result_h.emplace_back(" kFx = 22,");
+ result_h.emplace_back(" kFy = 23,");
+ result_h.emplace_back(" kMoment = 24,");
+ result_h.emplace_back(" kNumStates");
+ result_h.emplace_back("};");
+ result_h.emplace_back("};");
+ result_h.emplace_back(
+ "inline constexpr size_t kNumFullDynamicsStates = "
+ "static_cast<size_t>(FullDynamicsStates::kNumStates);");
+ result_h.emplace_back("struct VelocityStates {");
+ result_h.emplace_back("enum States {");
+ result_h.emplace_back(" kThetas0 = 0,");
+ result_h.emplace_back(" kOmegas0 = 1,");
+ result_h.emplace_back(" kThetas1 = 2,");
+ result_h.emplace_back(" kOmegas1 = 3,");
+ result_h.emplace_back(" kThetas2 = 4,");
+ result_h.emplace_back(" kOmegas2 = 5,");
+ result_h.emplace_back(" kThetas3 = 6,");
+ result_h.emplace_back(" kOmegas3 = 7,");
+ result_h.emplace_back(" kTheta = 8,");
+ result_h.emplace_back(" kVx = 9,");
+ result_h.emplace_back(" kVy = 10,");
+ result_h.emplace_back(" kOmega = 11,");
+ result_h.emplace_back(" kNumStates");
+ result_h.emplace_back("};");
+ result_h.emplace_back("};");
+ result_h.emplace_back(
+ "inline constexpr size_t kNumVelocityStates = "
+ "static_cast<size_t>(VelocityStates::kNumStates);");
+ result_h.emplace_back("struct InputStates {");
+ result_h.emplace_back("enum States {");
+ result_h.emplace_back(" kIs0 = 0,");
+ result_h.emplace_back(" kId0 = 1,");
+ result_h.emplace_back(" kIs1 = 2,");
+ result_h.emplace_back(" kId1 = 3,");
+ result_h.emplace_back(" kIs2 = 4,");
+ result_h.emplace_back(" kId2 = 5,");
+ result_h.emplace_back(" kIs3 = 6,");
+ result_h.emplace_back(" kId3 = 7,");
+ result_h.emplace_back(" kNumInputs = 8");
+ result_h.emplace_back("};");
+ result_h.emplace_back("};");
+ result_h.emplace_back(
+ "inline constexpr size_t kNumInputs = "
+ "static_cast<size_t>(InputStates::kNumInputs);");
+ result_h.emplace_back("");
result_h.emplace_back("// Returns the derivative of our state vector");
- result_h.emplace_back("// [thetas0, thetad0, omegas0, omegad0,");
- result_h.emplace_back("// thetas1, thetad1, omegas1, omegad1,");
- result_h.emplace_back("// thetas2, thetad2, omegas2, omegad2,");
- result_h.emplace_back("// thetas3, thetad3, omegas3, omegad3,");
- result_h.emplace_back("// x, y, theta, vx, vy, omega,");
- result_h.emplace_back("// Fx, Fy, Moment]");
- result_h.emplace_back("Eigen::Matrix<double, 25, 1> SwervePhysics(");
result_h.emplace_back(
- " Eigen::Map<const Eigen::Matrix<double, 25, 1>> X,");
+ "Eigen::Matrix<double, kNumFullDynamicsStates, 1> SwervePhysics(");
result_h.emplace_back(
- " Eigen::Map<const Eigen::Matrix<double, 8, 1>> U);");
+ " Eigen::Ref<const Eigen::Matrix<double, kNumFullDynamicsStates, "
+ "1>> X,");
+ result_h.emplace_back(
+ " Eigen::Ref<const Eigen::Matrix<double, kNumInputs, 1>> U);");
result_h.emplace_back("");
result_h.emplace_back("} // namespace frc971::control_loops::swerve");
result_h.emplace_back("");
@@ -308,12 +377,15 @@
result_cc.emplace_back("");
result_cc.emplace_back("namespace frc971::control_loops::swerve {");
result_cc.emplace_back("");
- result_cc.emplace_back("Eigen::Matrix<double, 25, 1> SwervePhysics(");
result_cc.emplace_back(
- " Eigen::Map<const Eigen::Matrix<double, 25, 1>> X,");
+ "Eigen::Matrix<double, kNumFullDynamicsStates, 1> SwervePhysics(");
result_cc.emplace_back(
- " Eigen::Map<const Eigen::Matrix<double, 8, 1>> U) {");
- result_cc.emplace_back(" Eigen::Matrix<double, 25, 1> result;");
+ " Eigen::Ref<const Eigen::Matrix<double, kNumFullDynamicsStates, "
+ "1>> X,");
+ result_cc.emplace_back(
+ " Eigen::Ref<const Eigen::Matrix<double, kNumInputs, 1>> U) {");
+ result_cc.emplace_back(
+ " Eigen::Matrix<double, kNumFullDynamicsStates, 1> result;");
// Start by writing out variables matching each of the symbol names we use
// so we don't have to modify the computed equations too much.
@@ -499,6 +571,80 @@
}
}
+ void WriteConstantsFile(std::string_view path) {
+ std::vector<std::string> result_py;
+
+ // Write out the header.
+ result_py.emplace_back("#!/usr/bin/env python3");
+ result_py.emplace_back("");
+
+ WriteConstants(&result_py);
+
+ aos::util::WriteStringToFileOrDie(path, absl::StrJoin(result_py, "\n"));
+ }
+
+ void WriteConstants(std::vector<std::string> *result_py) {
+ result_py->emplace_back(absl::Substitute("WHEEL_RADIUS = $0", ccode(*rw_)));
+ result_py->emplace_back(
+ absl::Substitute("ROBOT_WIDTH = $0", ccode(*robot_width_)));
+ result_py->emplace_back(absl::Substitute("CASTER = $0", ccode(*caster_)));
+ result_py->emplace_back("STATE_THETAS0 = 0");
+ result_py->emplace_back("STATE_THETAD0 = 1");
+ result_py->emplace_back("STATE_OMEGAS0 = 2");
+ result_py->emplace_back("STATE_OMEGAD0 = 3");
+ result_py->emplace_back("STATE_THETAS1 = 4");
+ result_py->emplace_back("STATE_THETAD1 = 5");
+ result_py->emplace_back("STATE_OMEGAS1 = 6");
+ result_py->emplace_back("STATE_OMEGAD1 = 7");
+ result_py->emplace_back("STATE_THETAS2 = 8");
+ result_py->emplace_back("STATE_THETAD2 = 9");
+ result_py->emplace_back("STATE_OMEGAS2 = 10");
+ result_py->emplace_back("STATE_OMEGAD2 = 11");
+ result_py->emplace_back("STATE_THETAS3 = 12");
+ result_py->emplace_back("STATE_THETAD3 = 13");
+ result_py->emplace_back("STATE_OMEGAS3 = 14");
+ result_py->emplace_back("STATE_OMEGAD3 = 15");
+ result_py->emplace_back("STATE_X = 16");
+ result_py->emplace_back("STATE_Y = 17");
+ result_py->emplace_back("STATE_THETA = 18");
+ result_py->emplace_back("STATE_VX = 19");
+ result_py->emplace_back("STATE_VY = 20");
+ result_py->emplace_back("STATE_OMEGA = 21");
+ result_py->emplace_back("STATE_FX = 22");
+ result_py->emplace_back("STATE_FY = 23");
+ result_py->emplace_back("STATE_MOMENT = 24");
+ result_py->emplace_back("NUM_STATES = 25");
+ result_py->emplace_back("");
+ result_py->emplace_back("VELOCITY_STATE_THETAS0 = 0");
+ result_py->emplace_back("VELOCITY_STATE_OMEGAS0 = 1");
+ result_py->emplace_back("VELOCITY_STATE_THETAS1 = 2");
+ result_py->emplace_back("VELOCITY_STATE_OMEGAS1 = 3");
+ result_py->emplace_back("VELOCITY_STATE_THETAS2 = 4");
+ result_py->emplace_back("VELOCITY_STATE_OMEGAS2 = 5");
+ result_py->emplace_back("VELOCITY_STATE_THETAS3 = 6");
+ result_py->emplace_back("VELOCITY_STATE_OMEGAS3 = 7");
+ result_py->emplace_back("VELOCITY_STATE_THETA = 8");
+ result_py->emplace_back("VELOCITY_STATE_VX = 9");
+ result_py->emplace_back("VELOCITY_STATE_VY = 10");
+ result_py->emplace_back("VELOCITY_STATE_OMEGA = 11");
+ // result_py->emplace_back("VELOCITY_STATE_FX = 16");
+ // result_py->emplace_back("VELOCITY_STATE_FY = 17");
+ // result_py->emplace_back("VELOCITY_STATE_MOMENT = 18");
+ result_py->emplace_back("NUM_VELOCITY_STATES = 12");
+ result_py->emplace_back("");
+ result_py->emplace_back("");
+ result_py->emplace_back("# Is = STEER_CURRENT_COUPLING_FACTOR * Id");
+ result_py->emplace_back(absl::Substitute(
+ "STEER_CURRENT_COUPLING_FACTOR = $0",
+ ccode(*(neg(
+ mul(div(Gs_, Kts_),
+ mul(div(Ktd_, mul(Gd_, rw_)),
+ neg(mul(add(neg(wb_), mul(add(rs_, rp_),
+ sub(integer(1), div(rb1_, rp_)))),
+ div(rw_, rb2_))))))))));
+ result_py->emplace_back("");
+ }
+
// Writes the physics out to the provided .cc and .h path.
void WriteCasadi(std::string_view py_path) {
std::vector<std::string> result_py;
@@ -508,54 +654,9 @@
result_py.emplace_back("");
result_py.emplace_back("import casadi, numpy");
result_py.emplace_back("");
- result_py.emplace_back(absl::Substitute("WHEEL_RADIUS = $0", ccode(*rw_)));
- result_py.emplace_back(
- absl::Substitute("ROBOT_WIDTH = $0", ccode(*robot_width_)));
- result_py.emplace_back(absl::Substitute("CASTER = $0", ccode(*caster_)));
- result_py.emplace_back("STATE_THETAS0 = 0");
- result_py.emplace_back("STATE_THETAD0 = 1");
- result_py.emplace_back("STATE_OMEGAS0 = 2");
- result_py.emplace_back("STATE_OMEGAD0 = 3");
- result_py.emplace_back("STATE_THETAS1 = 4");
- result_py.emplace_back("STATE_THETAD1 = 5");
- result_py.emplace_back("STATE_OMEGAS1 = 6");
- result_py.emplace_back("STATE_OMEGAD1 = 7");
- result_py.emplace_back("STATE_THETAS2 = 8");
- result_py.emplace_back("STATE_THETAD2 = 9");
- result_py.emplace_back("STATE_OMEGAS2 = 10");
- result_py.emplace_back("STATE_OMEGAD2 = 11");
- result_py.emplace_back("STATE_THETAS3 = 12");
- result_py.emplace_back("STATE_THETAD3 = 13");
- result_py.emplace_back("STATE_OMEGAS3 = 14");
- result_py.emplace_back("STATE_OMEGAD3 = 15");
- result_py.emplace_back("STATE_X = 16");
- result_py.emplace_back("STATE_Y = 17");
- result_py.emplace_back("STATE_THETA = 18");
- result_py.emplace_back("STATE_VX = 19");
- result_py.emplace_back("STATE_VY = 20");
- result_py.emplace_back("STATE_OMEGA = 21");
- result_py.emplace_back("STATE_FX = 22");
- result_py.emplace_back("STATE_FY = 23");
- result_py.emplace_back("STATE_MOMENT = 24");
- result_py.emplace_back("NUM_STATES = 25");
- result_py.emplace_back("");
- result_py.emplace_back("VELOCITY_STATE_THETAS0 = 0");
- result_py.emplace_back("VELOCITY_STATE_OMEGAS0 = 1");
- result_py.emplace_back("VELOCITY_STATE_THETAS1 = 2");
- result_py.emplace_back("VELOCITY_STATE_OMEGAS1 = 3");
- result_py.emplace_back("VELOCITY_STATE_THETAS2 = 4");
- result_py.emplace_back("VELOCITY_STATE_OMEGAS2 = 5");
- result_py.emplace_back("VELOCITY_STATE_THETAS3 = 6");
- result_py.emplace_back("VELOCITY_STATE_OMEGAS3 = 7");
- result_py.emplace_back("VELOCITY_STATE_THETA = 8");
- result_py.emplace_back("VELOCITY_STATE_VX = 9");
- result_py.emplace_back("VELOCITY_STATE_VY = 10");
- result_py.emplace_back("VELOCITY_STATE_OMEGA = 11");
- // result_py.emplace_back("VELOCITY_STATE_FX = 16");
- // result_py.emplace_back("VELOCITY_STATE_FY = 17");
- // result_py.emplace_back("VELOCITY_STATE_MOMENT = 18");
- result_py.emplace_back("NUM_VELOCITY_STATES = 12");
- result_py.emplace_back("");
+
+ WriteConstants(&result_py);
+
result_py.emplace_back("def to_velocity_state(X):");
result_py.emplace_back(" return numpy.array([");
result_py.emplace_back(" [X[STATE_THETAS0, 0]],");
@@ -606,27 +707,6 @@
"casadi.exp($1.0 * x))) * $0.0]))) / $0.0)",
kLogGain, kAbsGain));
}
- result_py.emplace_back("");
- result_py.emplace_back("# Is = STEER_CURRENT_COUPLING_FACTOR * Id");
- result_py.emplace_back(absl::Substitute(
- "STEER_CURRENT_COUPLING_FACTOR = $0",
- ccode(*(neg(
- mul(div(Gs_, Kts_),
- mul(div(Ktd_, mul(Gd_, rw_)),
- neg(mul(add(neg(wb_), mul(add(rs_, rp_),
- sub(integer(1), div(rb1_, rp_)))),
- div(rw_, rb2_))))))))));
- result_py.emplace_back("");
- result_py.emplace_back("# Is = STEER_CURRENT_COUPLING_FACTOR * Id");
- result_py.emplace_back(absl::Substitute(
- "STEER_CURRENT_COUPLING_FACTOR = $0",
- ccode(*(neg(
- mul(div(Gs_, Kts_),
- mul(div(Ktd_, mul(Gd_, rw_)),
- neg(mul(add(neg(wb_), mul(add(rs_, rp_),
- sub(integer(1), div(rb1_, rp_)))),
- div(rw_, rb2_))))))))));
- result_py.emplace_back("");
result_py.emplace_back("# Returns the derivative of our state vector");
result_py.emplace_back("# [thetas0, thetad0, omegas0, omegad0,");
@@ -785,7 +865,16 @@
},
&result_py);
- DefineVector2dFunction(
+ DefineVector2dVelocityFunction(
+ "F_vel",
+ "Returns the force on the wheel in absolute coordinates based on the "
+ "velocity controller",
+ [](const Module &m, int dimension) {
+ return ccode(*m.direct.F.get(dimension, 0));
+ },
+ &result_py);
+
+ DefineVector2dVelocityFunction(
"mounting_location",
"Returns the mounting location of wheel in robot coordinates",
[](const Module &m, int dimension) {
@@ -793,6 +882,14 @@
},
&result_py);
+ DefineVector2dVelocityFunction(
+ "rotated_mounting_location",
+ "Returns the mounting location of wheel in field aligned coordinates",
+ [](const Module &m, int dimension) {
+ return ccode(*m.rotated_mounting_location.get(dimension, 0));
+ },
+ &result_py);
+
DefineScalarFunction(
"Ms", "Returns the self aligning moment of the ith wheel",
[this](const Module &m) {
@@ -852,6 +949,34 @@
" return casadi.Function('$0', [X, U], [result])", name));
}
+ void DefineVector2dVelocityFunction(
+ std::string_view name, std::string_view documentation,
+ std::function<std::string(const Module &, int)> scalar_fn,
+ std::vector<std::string> *result_py) {
+ result_py->emplace_back("");
+ result_py->emplace_back(absl::Substitute("# $0.", documentation));
+ result_py->emplace_back(absl::Substitute("def $0(i, X, U):", name));
+ WriteCasadiVelocityVariables(result_py);
+ result_py->emplace_back(
+ absl::Substitute(" result = casadi.SX.sym('$0', 2, 1)", name));
+ for (size_t m = 0; m < kNumModules; ++m) {
+ if (m == 0) {
+ result_py->emplace_back(" if i == 0:");
+ } else {
+ result_py->emplace_back(absl::Substitute(" elif i == $0:", m));
+ }
+ for (int j = 0; j < 2; ++j) {
+ result_py->emplace_back(absl::Substitute(" result[$0, 0] = $1",
+ j, scalar_fn(modules_[m], j)));
+ }
+ }
+ result_py->emplace_back(" else:");
+ result_py->emplace_back(
+ " raise ValueError(\"Invalid module number\")");
+ result_py->emplace_back(absl::Substitute(
+ " return casadi.Function('$0', [X, U], [result])", name));
+ }
+
private:
static constexpr uint8_t kNumModules = 4;
@@ -1015,14 +1140,19 @@
mul_dense_dense(R(add(theta_, result.thetas)),
DenseMatrix(2, 1, {result.full.Fwx, result.Fwy}),
result.full.F);
- result.full.torque = force_cross(result.mounting_location, result.full.F);
+
+ result.rotated_mounting_location = DenseMatrix(2, 1);
+ mul_dense_dense(R(theta_), result.mounting_location,
+ result.rotated_mounting_location);
+ result.full.torque =
+ force_cross(result.rotated_mounting_location, result.full.F);
result.direct.F = DenseMatrix(2, 1);
mul_dense_dense(R(add(theta_, result.thetas)),
DenseMatrix(2, 1, {result.direct.Fwx, result.Fwy}),
result.direct.F);
result.direct.torque =
- force_cross(result.mounting_location, result.direct.F);
+ force_cross(result.rotated_mounting_location, result.direct.F);
VLOG(1);
VLOG(1) << "full torque = " << result.full.torque->__str__();
@@ -1117,5 +1247,9 @@
sim.WriteCasadi(absl::GetFlag(FLAGS_casadi_py_output_path));
}
+ if (!absl::GetFlag(FLAGS_constants_output_path).empty()) {
+ sim.WriteConstantsFile(absl::GetFlag(FLAGS_constants_output_path));
+ }
+
return 0;
}
diff --git a/frc971/control_loops/swerve/inverse_kinematics.h b/frc971/control_loops/swerve/inverse_kinematics.h
new file mode 100644
index 0000000..a4e43e1
--- /dev/null
+++ b/frc971/control_loops/swerve/inverse_kinematics.h
@@ -0,0 +1,86 @@
+#ifndef FRC971_CONTROL_LOOPS_SWERVE_INVERSE_KINEMATICS_H_
+#define FRC971_CONTROL_LOOPS_SWERVE_INVERSE_KINEMATICS_H_
+#include "aos/util/math.h"
+#include "frc971/control_loops/swerve/simplified_dynamics.h"
+namespace frc971::control_loops::swerve {
+// Class to do straightforwards inverse kinematics of a swerve drivebase. This
+// is meant largely as a sanity-check/initializer for more sophisticated
+// methods. This calculates which directions the modules must be pointed to
+// cause them to be pointed directly along the direction of motion of the
+// drivebase. Accounting for slip angles and the such must be done as part of
+// more sophisticated inverse dynamics.
+template <typename Scalar>
+class InverseKinematics {
+ public:
+ using ModuleParams = SimplifiedDynamics<Scalar>::ModuleParams;
+ using Parameters = SimplifiedDynamics<Scalar>::Parameters;
+ using States = SimplifiedDynamics<Scalar>::States;
+ using State = SimplifiedDynamics<Scalar>::template VelocityState<Scalar>;
+ InverseKinematics(const Parameters ¶ms) : params_(params) {}
+
+ // Uses kVx, kVy, kTheta, and kOmega from the input goal state for the
+ // absolute kinematics. Also uses the specified theta values to bias theta
+ // output values towards the current state (i.e., if the module 0 theta is
+ // currently 0 and we are asked to drive straight backwards, this will prefer
+ // a theta of zero rather than a theta of pi).
+ State Solve(const State &goal) {
+ State result = goal;
+ for (size_t module_index = 0; module_index < params_.modules.size();
+ ++module_index) {
+ SolveModule(goal, params_.modules[module_index].position,
+ &result(States::kThetas0 + 2 * module_index),
+ &result(States::kOmegas0 + 2 * module_index));
+ }
+ return result;
+ }
+
+ void SolveModule(const State &goal,
+ const Eigen::Matrix<Scalar, 2, 1> &module_position,
+ Scalar *module_theta, Scalar *module_omega) {
+ const Scalar vx = goal(States::kVx);
+ const Scalar vy = goal(States::kVy);
+ const Scalar omega = goal(States::kOmega);
+ // module_velocity_in_robot_frame = R(-theta) * robot_vel +
+ // omega.cross(module_position);
+ // module_vel_x = (cos(-theta) * vx - sin(-theta) * vy) - omega * module_y
+ // module_vel_y = (sin(-theta) * vx + cos(-theta) * vy) + omega * module_x
+ // module_theta = atan2(module_vel_y, module_vel_x)
+ // module_omega = datan2(module_vel_y, module_vel_x) / dt
+ // datan2(y, x) / dt = (x * dy/dt - y * dx / dt) / (x^2 + y^2)
+ // robot accelerations are assumed to be zero.
+ // dmodule_vel_x / dt = (sin(-theta) * vx + cos(-theta) * vy) * omega
+ // dmodule_vel_y / dt = (-cos(-theta) * vx + sin(-theta) * vy) * omega
+ const Scalar ctheta = std::cos(-goal(States::kTheta));
+ const Scalar stheta = std::sin(-goal(States::kTheta));
+ const Scalar module_vel_x =
+ (ctheta * vx - stheta * vy) - omega * module_position.y();
+ const Scalar module_vel_y =
+ (stheta * vx + ctheta * vy) + omega * module_position.x();
+ const Scalar nominal_module_theta = atan2(module_vel_y, module_vel_x);
+ // If the current module theta is more than 90 deg from the desired theta,
+ // flip the desired theta by 180 deg.
+ if (std::abs(aos::math::DiffAngle(nominal_module_theta, *module_theta)) >
+ M_PI_2) {
+ *module_theta = aos::math::NormalizeAngle(nominal_module_theta + M_PI);
+ } else {
+ *module_theta = nominal_module_theta;
+ }
+ const Scalar module_accel_x = (stheta * vx + ctheta * vy) * omega;
+ const Scalar module_accel_y = (-ctheta * vx + stheta * vy) * omega;
+ const Scalar module_vel_norm_squared =
+ (module_vel_x * module_vel_x + module_vel_y * module_vel_y);
+ if (module_vel_norm_squared < 1e-5) {
+ // Prevent poor conditioning of module velocities at near-zero speeds.
+ *module_omega = 0.0;
+ } else {
+ *module_omega =
+ (module_vel_x * module_accel_y - module_vel_y * module_accel_x) /
+ module_vel_norm_squared;
+ }
+ }
+
+ private:
+ Parameters params_;
+};
+} // namespace frc971::control_loops::swerve
+#endif // FRC971_CONTROL_LOOPS_SWERVE_INVERSE_KINEMATICS_H_
diff --git a/frc971/control_loops/swerve/inverse_kinematics_test.cc b/frc971/control_loops/swerve/inverse_kinematics_test.cc
new file mode 100644
index 0000000..407d540
--- /dev/null
+++ b/frc971/control_loops/swerve/inverse_kinematics_test.cc
@@ -0,0 +1,150 @@
+#include "frc971/control_loops/swerve/inverse_kinematics.h"
+
+#include "gtest/gtest.h"
+
+namespace frc971::control_loops::swerve::testing {
+class InverseKinematicsTest : public ::testing::Test {
+ protected:
+ typedef double Scalar;
+ using State = InverseKinematics<Scalar>::State;
+ using States = InverseKinematics<Scalar>::States;
+ using ModuleParams = InverseKinematics<Scalar>::ModuleParams;
+ using Parameters = InverseKinematics<Scalar>::Parameters;
+ static ModuleParams MakeModule(const Eigen::Matrix<Scalar, 2, 1> &position) {
+ return ModuleParams{.position = position,
+ .slip_angle_coefficient = 0.0,
+ .slip_angle_alignment_coefficient = 0.0,
+ .steer_motor = KrakenFOC(),
+ .drive_motor = KrakenFOC(),
+ .steer_ratio = 1.0,
+ .drive_ratio = 1.0};
+ }
+ static Parameters MakeParams() {
+ return {.mass = 1.0,
+ .moment_of_inertia = 1.0,
+ .modules = {
+ MakeModule({1.0, 1.0}),
+ MakeModule({-1.0, 1.0}),
+ MakeModule({-1.0, -1.0}),
+ MakeModule({1.0, -1.0}),
+ }};
+ }
+
+ InverseKinematicsTest() : inverse_kinematics_(MakeParams()) {}
+
+ struct Goal {
+ Scalar vx;
+ Scalar vy;
+ Scalar omega;
+ Scalar theta;
+ };
+
+ void CheckState(
+ const Goal &goal, const std::array<Scalar, 4> &expected_thetas,
+ const std::optional<Eigen::Vector4d> &expected_omegas = std::nullopt) {
+ State goal_state = State::Zero();
+ goal_state(States::kVx) = goal.vx;
+ goal_state(States::kVy) = goal.vy;
+ goal_state(States::kOmega) = goal.omega;
+ goal_state(States::kTheta) = goal.theta;
+ SCOPED_TRACE(goal_state.bottomRows<4>().transpose());
+ const State nominal_state = inverse_kinematics_.Solve(goal_state);
+ // Now, calculate the numerical derivative of the state and validate that it
+ // matches expectations.
+ const Scalar kDt = 1e-5;
+ const Scalar dtheta = kDt * goal.omega;
+ goal_state(States::kTheta) += dtheta / 2.0;
+ const State state_eps_pos = inverse_kinematics_.Solve(goal_state);
+ goal_state(States::kTheta) -= dtheta;
+ const State state_eps_neg = inverse_kinematics_.Solve(goal_state);
+ const State state_derivative = (state_eps_pos - state_eps_neg) / kDt;
+ for (size_t module_index = 0; module_index < 4; ++module_index) {
+ SCOPED_TRACE(module_index);
+ const int omega_idx = States::kOmegas0 + 2 * module_index;
+ const int theta_idx = States::kThetas0 + 2 * module_index;
+ EXPECT_NEAR(nominal_state(omega_idx), state_derivative(theta_idx), 1e-10);
+ EXPECT_NEAR(nominal_state(theta_idx), expected_thetas[module_index],
+ 1e-10);
+ if (expected_omegas.has_value()) {
+ EXPECT_NEAR(nominal_state(omega_idx),
+ expected_omegas.value()(module_index), 1e-10);
+ }
+ }
+ }
+
+ InverseKinematics<Scalar> inverse_kinematics_;
+};
+
+// Tests that if we are driving straight with no yaw that we get sane
+// kinematics.
+TEST_F(InverseKinematicsTest, StraightDrivingNoYaw) {
+ // Sanity-check zero-speed operation.
+ CheckState({.vx = 0.0, .vy = 0.0, .omega = 0.0, .theta = 0.0},
+ {0.0, 0.0, 0.0, 0.0}, Eigen::Vector4d::Zero());
+
+ CheckState({.vx = 1.0, .vy = 0.0, .omega = 0.0, .theta = 0.0},
+ {0.0, 0.0, 0.0, 0.0}, Eigen::Vector4d::Zero());
+ // Reverse should prefer to bias the modules towards [-pi/2, pi/2] due to
+ // hysteresis from starting the modules at thetas of 0.
+ CheckState({.vx = -1.0, .vy = 0.0, .omega = 0.0, .theta = 0.0},
+ {0.0, 0.0, 0.0, 0.0}, Eigen::Vector4d::Zero());
+
+ CheckState({.vx = 0.0, .vy = 1.0, .omega = 0.0, .theta = 0.0},
+ {M_PI_2, M_PI_2, M_PI_2, M_PI_2}, Eigen::Vector4d::Zero());
+ // For module hysteresis, this is a corner case where we are exactly 90 deg
+ // from the current value; the exact result is unimportant.
+ CheckState({.vx = 0.0, .vy = -1.0, .omega = 0.0, .theta = 0.0},
+ {-M_PI_2, -M_PI_2, -M_PI_2, -M_PI_2}, Eigen::Vector4d::Zero());
+
+ CheckState({.vx = 1.0, .vy = 1.0, .omega = 0.0, .theta = 0.0},
+ {M_PI_4, M_PI_4, M_PI_4, M_PI_4}, Eigen::Vector4d::Zero());
+ // Reverse should prefer to bias the modules towards [-pi/2, pi/2] due to
+ // hysteresis from starting the modules at thetas of 0.
+ CheckState({.vx = -1.0, .vy = -1.0, .omega = 0.0, .theta = 0.0},
+ {M_PI_4, M_PI_4, M_PI_4, M_PI_4}, Eigen::Vector4d::Zero());
+}
+
+// Tests that if we are driving straight with non-zero yaw that we get sane
+// kinematics.
+TEST_F(InverseKinematicsTest, StraightDrivingYawed) {
+ CheckState({.vx = 1.0, .vy = 0.0, .omega = 0.0, .theta = 0.1},
+ {-0.1, -0.1, -0.1, -0.1}, Eigen::Vector4d::Zero());
+
+ CheckState({.vx = 1.0, .vy = 0.0, .omega = 0.0, .theta = M_PI_2},
+ {-M_PI_2, -M_PI_2, -M_PI_2, -M_PI_2}, Eigen::Vector4d::Zero());
+ CheckState({.vx = 1.0, .vy = 0.0, .omega = 0.0, .theta = M_PI},
+ {0.0, 0.0, 0.0, 0.0}, Eigen::Vector4d::Zero());
+
+ CheckState({.vx = 0.0, .vy = 1.0, .omega = 0.0, .theta = M_PI_2},
+ {0.0, 0.0, 0.0, 0.0}, Eigen::Vector4d::Zero());
+ // Reverse should prefer to bias the modules towards [-pi/2, pi/2] due to
+ // hysteresis from starting the modules at thetas of 0.
+ CheckState({.vx = 0.0, .vy = -1.0, .omega = 0.0, .theta = M_PI_2},
+ {0.0, 0.0, 0.0, 0.0}, Eigen::Vector4d::Zero());
+}
+
+// Tests that we can spin in place.
+TEST_F(InverseKinematicsTest, SpinInPlace) {
+ CheckState({.vx = 0.0, .vy = 0.0, .omega = 1.0, .theta = 0.0},
+ {-M_PI_4, M_PI_4, -M_PI_4, M_PI_4}, Eigen::Vector4d::Zero());
+ // And changing the current theta should not matter.
+ CheckState({.vx = 0.0, .vy = 0.0, .omega = 1.0, .theta = 1.0},
+ {-M_PI_4, M_PI_4, -M_PI_4, M_PI_4}, Eigen::Vector4d::Zero());
+}
+
+// Tests that if we are spinning while moving that we correctly calculate module
+// yaw rates.
+TEST_F(InverseKinematicsTest, SpinWhileMoving) {
+ // Set up a situation where we are driving straight forwards, with a
+ // yaw rate of 1 rad / sec.
+ // The modules are all at radii of sqrt(2), so the contribution from both
+ // the translational and rotational velocities should be equal; in this case
+ // each module will have an angle that is an equal combination of straight
+ // forwards (0 deg) and some 45 deg offset.
+ CheckState({.vx = std::sqrt(static_cast<Scalar>(2)),
+ .vy = 0.0,
+ .omega = 1.0,
+ .theta = 0.0},
+ {3 * M_PI_4 / 2, -3 * M_PI_4 / 2, -M_PI_4 / 2, M_PI_4 / 2});
+}
+} // namespace frc971::control_loops::swerve::testing
diff --git a/frc971/control_loops/swerve/jax_dynamics.py b/frc971/control_loops/swerve/jax_dynamics.py
index 8b05ef4..58d5fcf 100644
--- a/frc971/control_loops/swerve/jax_dynamics.py
+++ b/frc971/control_loops/swerve/jax_dynamics.py
@@ -4,8 +4,8 @@
from collections import namedtuple
import jax
-from frc971.control_loops.swerve import dynamics
from frc971.control_loops.python.control_loop import KrakenFOC
+from frc971.control_loops.swerve.dynamics_constants import *
# Note: this physics needs to match the symengine code. We have tests that
# confirm they match in all the cases we care about.
@@ -115,14 +115,14 @@
def softsign(x, gain):
- return -2 / (1 + jax.numpy.exp(gain * x)) + 1
+ return 1 - 2.0 * jax.nn.sigmoid(-gain * x)
def soft_atan2(y, x):
kMaxLogGain = 1.0 / 0.05
kAbsLogGain = 1.0 / 0.01
- softabs_x = x * (1.0 - 2.0 / (1 + jax.numpy.exp(kAbsLogGain * x)))
+ softabs_x = x * softsign(x, kAbsLogGain)
return jax.numpy.arctan2(
y,
@@ -130,36 +130,35 @@
jax.numpy.array([1.0, softabs_x * kMaxLogGain])) / kMaxLogGain)
-def full_module_physics(coefficients: dict, Rtheta, module_index: int,
- mounting_location, X, U):
+def full_module_physics(coefficients: CoefficientsType, Rtheta,
+ module_index: int, mounting_location, X, U):
X_module = X[module_index * 4:(module_index + 1) * 4]
Is = U[2 * module_index + 0]
Id = U[2 * module_index + 1]
- Rthetaplusthetas = R(X[dynamics.STATE_THETA] +
- X_module[dynamics.STATE_THETAS0])
+ Rthetaplusthetas = R(X[STATE_THETA] + X_module[STATE_THETAS0])
caster_vector = jax.numpy.array([-coefficients.caster, 0.0])
- robot_velocity = X[dynamics.STATE_VX:dynamics.STATE_VY + 1]
+ robot_velocity = X[STATE_VX:STATE_VY + 1]
contact_patch_velocity = (
- angle_cross(Rtheta @ mounting_location, X[dynamics.STATE_OMEGA]) +
- robot_velocity + angle_cross(
- Rthetaplusthetas @ caster_vector,
- (X[dynamics.STATE_OMEGA] + X_module[dynamics.STATE_OMEGAS0])))
+ angle_cross(Rtheta @ mounting_location, X[STATE_OMEGA]) +
+ robot_velocity +
+ angle_cross(Rthetaplusthetas @ caster_vector,
+ (X[STATE_OMEGA] + X_module[STATE_OMEGAS0])))
wheel_ground_velocity = Rthetaplusthetas.T @ contact_patch_velocity
wheel_velocity = jax.numpy.array(
- [coefficients.rw * X_module[dynamics.STATE_OMEGAD0], 0.0])
+ [coefficients.rw * X_module[STATE_OMEGAD0], 0.0])
wheel_slip_velocity = wheel_velocity - wheel_ground_velocity
slip_angle = jax.numpy.sin(
-soft_atan2(wheel_ground_velocity[1], wheel_ground_velocity[0]))
- slip_ratio = (coefficients.rw * X_module[dynamics.STATE_OMEGAD0] -
+ slip_ratio = (coefficients.rw * X_module[STATE_OMEGAD0] -
wheel_ground_velocity[0]) / jax.numpy.max(
jax.numpy.array(
[0.02, jax.numpy.abs(wheel_ground_velocity[0])]))
@@ -189,12 +188,12 @@
F = Rthetaplusthetas @ jax.numpy.array([Fwx, Fwy])
- torque = force_cross(mounting_location, F)
+ torque = force_cross(Rtheta @ mounting_location, F)
X_dot_contribution = jax.numpy.hstack((jax.numpy.zeros(
(4, )), ) * (module_index) + (jax.numpy.array([
- X_module[dynamics.STATE_OMEGAS0],
- X_module[dynamics.STATE_OMEGAD0],
+ X_module[STATE_OMEGAS0],
+ X_module[STATE_OMEGAD0],
alphas,
alphad,
]), ) + (jax.numpy.zeros((4, )), ) * (3 - module_index) + (
@@ -208,7 +207,7 @@
@partial(jax.jit, static_argnames=['coefficients'])
def full_dynamics(coefficients: CoefficientsType, X, U):
- Rtheta = R(X[dynamics.STATE_THETA])
+ Rtheta = R(X[STATE_THETA])
module0 = full_module_physics(
coefficients, Rtheta, 0,
@@ -233,37 +232,41 @@
X_dot = module0 + module1 + module2 + module3
- X_dot = X_dot.at[dynamics.STATE_X:dynamics.STATE_THETA + 1].set(
+ X_dot = X_dot.at[STATE_X:STATE_THETA + 1].set(
jax.numpy.array([
- X[dynamics.STATE_VX],
- X[dynamics.STATE_VY],
- X[dynamics.STATE_OMEGA],
+ X[STATE_VX],
+ X[STATE_VY],
+ X[STATE_OMEGA],
]))
return X_dot
-def velocity_module_physics(coefficients: dict, Rtheta, module_index: int,
- mounting_location, X, U):
+def velocity_module_physics(coefficients: CoefficientsType,
+ Rtheta: jax.typing.ArrayLike, module_index: int,
+ mounting_location: jax.typing.ArrayLike,
+ X: jax.typing.ArrayLike, U: jax.typing.ArrayLike):
X_module = X[module_index * 2:(module_index + 1) * 2]
Is = U[2 * module_index + 0]
Id = U[2 * module_index + 1]
- Rthetaplusthetas = R(X[dynamics.VELOCITY_STATE_THETA] +
- X_module[dynamics.VELOCITY_STATE_THETAS0])
+ rotated_mounting_location = Rtheta @ mounting_location
+
+ Rthetaplusthetas = R(X[VELOCITY_STATE_THETA] +
+ X_module[VELOCITY_STATE_THETAS0])
caster_vector = jax.numpy.array([-coefficients.caster, 0.0])
- robot_velocity = X[dynamics.VELOCITY_STATE_VX:dynamics.VELOCITY_STATE_VY +
- 1]
+ robot_velocity = X[VELOCITY_STATE_VX:VELOCITY_STATE_VY + 1]
contact_patch_velocity = (
- angle_cross(Rtheta @ mounting_location,
- X[dynamics.VELOCITY_STATE_OMEGA]) + robot_velocity +
- angle_cross(Rthetaplusthetas @ caster_vector,
- (X[dynamics.VELOCITY_STATE_OMEGA] +
- X_module[dynamics.VELOCITY_STATE_OMEGAS0])))
+ angle_cross(rotated_mounting_location, X[VELOCITY_STATE_OMEGA]) +
+ robot_velocity + angle_cross(
+ Rthetaplusthetas @ caster_vector,
+ (X[VELOCITY_STATE_OMEGA] + X_module[VELOCITY_STATE_OMEGAS0])))
+ # Velocity of the contact patch over the field projected into the direction
+ # of the wheel.
wheel_ground_velocity = Rthetaplusthetas.T @ contact_patch_velocity
slip_angle = jax.numpy.sin(
@@ -272,7 +275,7 @@
Fwx = (coefficients.Ktd / (coefficients.Gd * coefficients.rw)) * Id
Fwy = coefficients.Cy * slip_angle
- softsign_velocity = softsign(wheel_ground_velocity[0], 100)
+ softsign_velocity = softsign(wheel_ground_velocity[0], 100.0)
Ms = -Fwy * (
(softsign_velocity * coefficients.contact_patch_length / 3.0) +
@@ -288,11 +291,11 @@
F = Rthetaplusthetas @ jax.numpy.array([Fwx, Fwy])
- torque = force_cross(mounting_location, F)
+ torque = force_cross(rotated_mounting_location, F)
X_dot_contribution = jax.numpy.hstack((jax.numpy.zeros(
(2, )), ) * (module_index) + (jax.numpy.array([
- X_module[dynamics.VELOCITY_STATE_OMEGAS0],
+ X_module[VELOCITY_STATE_OMEGAS0],
alphas,
]), ) + (jax.numpy.zeros((2, )), ) * (3 - module_index) + (
jax.numpy.zeros((1, )),
@@ -300,29 +303,30 @@
jax.numpy.array([torque / coefficients.J]),
))
- return X_dot_contribution
+ return X_dot_contribution, F, torque
@partial(jax.jit, static_argnames=['coefficients'])
-def velocity_dynamics(coefficients: CoefficientsType, X, U):
- Rtheta = R(X[dynamics.VELOCITY_STATE_THETA])
+def velocity_dynamics(coefficients: CoefficientsType, X: jax.typing.ArrayLike,
+ U: jax.typing.ArrayLike):
+ Rtheta = R(X[VELOCITY_STATE_THETA])
- module0 = velocity_module_physics(
+ module0, _, _ = velocity_module_physics(
coefficients, Rtheta, 0,
jax.numpy.array(
[coefficients.robot_width / 2.0, coefficients.robot_width / 2.0]),
X, U)
- module1 = velocity_module_physics(
+ module1, _, _ = velocity_module_physics(
coefficients, Rtheta, 1,
jax.numpy.array(
[-coefficients.robot_width / 2.0, coefficients.robot_width / 2.0]),
X, U)
- module2 = velocity_module_physics(
+ module2, _, _ = velocity_module_physics(
coefficients, Rtheta, 2,
jax.numpy.array(
[-coefficients.robot_width / 2.0,
-coefficients.robot_width / 2.0]), X, U)
- module3 = velocity_module_physics(
+ module3, _, _ = velocity_module_physics(
coefficients, Rtheta, 3,
jax.numpy.array(
[coefficients.robot_width / 2.0, -coefficients.robot_width / 2.0]),
@@ -330,5 +334,92 @@
X_dot = module0 + module1 + module2 + module3
- return X_dot.at[dynamics.VELOCITY_STATE_THETA].set(
- X[dynamics.VELOCITY_STATE_OMEGA])
+ return X_dot.at[VELOCITY_STATE_THETA].set(X[VELOCITY_STATE_OMEGA])
+
+
+def to_velocity_state(X):
+ return jax.numpy.array([
+ X[STATE_THETAS0],
+ X[STATE_OMEGAS0],
+ X[STATE_THETAS1],
+ X[STATE_OMEGAS1],
+ X[STATE_THETAS2],
+ X[STATE_OMEGAS2],
+ X[STATE_THETAS3],
+ X[STATE_OMEGAS3],
+ X[STATE_THETA],
+ X[STATE_VX],
+ X[STATE_VY],
+ X[STATE_OMEGA],
+ ])
+
+
+@jax.jit
+def mpc_cost(coefficients: CoefficientsType, X, U, goal):
+ J = 0
+
+ rnorm = jax.numpy.linalg.norm(goal[0:2])
+
+ vnorm = jax.lax.select(rnorm > 0.0001, goal[0:2] / rnorm,
+ jax.numpy.array([1.0, 0.0]))
+ vperp = jax.lax.select(rnorm > 0.0001,
+ jax.numpy.array([-vnorm[1], vnorm[0]]),
+ jax.numpy.array([0.0, 1.0]))
+
+ velocity_error = goal[0:2] - X[VELOCITY_STATE_VX:VELOCITY_STATE_VY + 1]
+
+ # TODO(austin): Do we want to do something more special for 0?
+
+ J += 75 * (jax.numpy.dot(velocity_error, vnorm)**2.0)
+ J += 1500 * (jax.numpy.dot(velocity_error, vperp)**2.0)
+ J += 1000 * (goal[2] - X[VELOCITY_STATE_OMEGA])**2.0
+
+ kSteerVelocityGain = 0.10
+ J += kSteerVelocityGain * (X[VELOCITY_STATE_OMEGAS0])**2.0
+ J += kSteerVelocityGain * (X[VELOCITY_STATE_OMEGAS1])**2.0
+ J += kSteerVelocityGain * (X[VELOCITY_STATE_OMEGAS2])**2.0
+ J += kSteerVelocityGain * (X[VELOCITY_STATE_OMEGAS3])**2.0
+
+ mounting_locations = jax.numpy.array(
+ [[coefficients.robot_width / 2.0, coefficients.robot_width / 2.0],
+ [-coefficients.robot_width / 2.0, coefficients.robot_width / 2.0],
+ [-coefficients.robot_width / 2.0, -coefficients.robot_width / 2.0],
+ [coefficients.robot_width / 2.0, -coefficients.robot_width / 2.0]])
+
+ Rtheta = R(X[VELOCITY_STATE_THETA])
+ _, F0, torque0 = velocity_module_physics(coefficients, Rtheta, 0,
+ mounting_locations[0], X, U)
+ _, F1, torque1 = velocity_module_physics(coefficients, Rtheta, 1,
+ mounting_locations[1], X, U)
+ _, F2, torque2 = velocity_module_physics(coefficients, Rtheta, 2,
+ mounting_locations[2], X, U)
+ _, F3, torque3 = velocity_module_physics(coefficients, Rtheta, 3,
+ mounting_locations[3], X, U)
+
+ forces = [F0, F1, F2, F3]
+
+ F = (F0 + F1 + F2 + F3)
+ torque = (torque0 + torque1 + torque2 + torque3)
+
+ def force_cross(torque, r):
+ r_squared_norm = jax.numpy.inner(r, r)
+
+ return jax.numpy.array(
+ [-r[1] * torque / r_squared_norm, r[0] * torque / r_squared_norm])
+
+ # TODO(austin): Are these penalties reasonable? Do they give us a decent time constant?
+ for i in range(4):
+ desired_force = F / 4.0 + force_cross(
+ torque / 4.0, Rtheta @ mounting_locations[i, :])
+ force_error = desired_force - forces[i]
+ J += 0.01 * jax.numpy.inner(force_error, force_error)
+
+ for i in range(4):
+ Is = U[2 * i + 0]
+ Id = U[2 * i + 1]
+ # Steer
+ J += ((Is + STEER_CURRENT_COUPLING_FACTOR * Id)**2.0) / 100000.0
+ # Drive
+ J += (Id**2.0) / 1000.0
+
+ return J
diff --git a/frc971/control_loops/swerve/linearization_utils.h b/frc971/control_loops/swerve/linearization_utils.h
new file mode 100644
index 0000000..ee1275e
--- /dev/null
+++ b/frc971/control_loops/swerve/linearization_utils.h
@@ -0,0 +1,13 @@
+#ifndef FRC971_CONTROL_LOOPS_SWERVE_LINEARIZATION_UTILS_H_
+#define FRC971_CONTROL_LOOPS_SWERVE_LINEARIZATION_UTILS_H_
+
+namespace frc971::control_loops::swerve {
+template <typename State, typename Input>
+struct DynamicsInterface {
+ virtual ~DynamicsInterface() {}
+ // To be overridden by the implementation; returns the derivative of the state
+ // at the given state with the provided control input.
+ virtual State operator()(const State &X, const Input &U) const = 0;
+};
+} // namespace frc971::control_loops::swerve
+#endif // FRC971_CONTROL_LOOPS_SWERVE_LINEARIZATION_UTILS_H_
diff --git a/frc971/control_loops/swerve/linearized_controller.h b/frc971/control_loops/swerve/linearized_controller.h
new file mode 100644
index 0000000..1df9640
--- /dev/null
+++ b/frc971/control_loops/swerve/linearized_controller.h
@@ -0,0 +1,126 @@
+#include <memory>
+
+#include "absl/log/check.h"
+#include "absl/log/log.h"
+#include <Eigen/Dense>
+
+#include "frc971/control_loops/c2d.h"
+#include "frc971/control_loops/dlqr.h"
+#include "frc971/control_loops/jacobian.h"
+#include "frc971/control_loops/swerve/dynamics.h"
+#include "frc971/control_loops/swerve/linearization_utils.h"
+
+namespace frc971::control_loops::swerve {
+
+// Provides a simple LQR controller that takes a non-linear system, linearizes
+// the dynamics at each timepoint, recalculates the LQR gains for those
+// dynamics, and calculates the relevant feedback inputs to provide.
+template <int NStates, typename Scalar = double>
+class LinearizedController {
+ public:
+ typedef Eigen::Matrix<Scalar, NStates, 1> State;
+ typedef Eigen::Matrix<Scalar, NStates, NStates> StateSquare;
+ typedef Eigen::Matrix<Scalar, kNumInputs, 1> Input;
+ typedef Eigen::Matrix<Scalar, kNumInputs, kNumInputs> InputSquare;
+ typedef Eigen::Matrix<Scalar, NStates, kNumInputs> BMatrix;
+ typedef DynamicsInterface<State, Input> Dynamics;
+
+ struct Parameters {
+ // State cost matrix.
+ StateSquare Q;
+ // Input cost matrix.
+ InputSquare R;
+ // period at which the controller is called.
+ std::chrono::nanoseconds dt;
+ // The dynamics to use.
+ // TODO(james): I wrote this before creating the auto-differentiation
+ // functions; we should swap to the auto-differentiation, since the
+ // numerical linearization is one of the bigger timesinks in this controller
+ // right now.
+ std::unique_ptr<Dynamics> dynamics;
+ };
+
+ // Represents the linearized dynamics of the system.
+ struct LinearDynamics {
+ StateSquare A;
+ BMatrix B;
+ };
+
+ // Debug information for a given cycle of the controller.
+ struct ControllerDebug {
+ // Feedforward input which we provided.
+ Input U_ff;
+ // Calculated feedback input to provide.
+ Input U_feedback;
+ Eigen::Matrix<Scalar, kNumInputs, NStates> feedback_contributions;
+ };
+
+ struct ControllerResult {
+ // Control input to provide to the robot.
+ Input U;
+ ControllerDebug debug;
+ };
+
+ LinearizedController(Parameters params) : params_(std::move(params)) {}
+
+ // Runs the controller for a given iteration, relinearizing the dynamics about
+ // the provided current state X, attempting to control the robot to the
+ // desired goal state.
+ // The U_ff input will be added into the returned control input.
+ ControllerResult RunController(const State &X, const State &goal,
+ Input U_ff) {
+ auto start_time = aos::monotonic_clock::now();
+ // TODO(james): Swap this to the auto-diff methods; this is currently about
+ // a third of the total time spent in this method when run on the roborio.
+ const struct LinearDynamics continuous_dynamics =
+ LinearizeDynamics(X, U_ff);
+ auto linearization_time = aos::monotonic_clock::now();
+ struct LinearDynamics discrete_dynamics;
+ frc971::controls::C2D(continuous_dynamics.A, continuous_dynamics.B,
+ params_.dt, &discrete_dynamics.A,
+ &discrete_dynamics.B);
+ auto c2d_time = aos::monotonic_clock::now();
+ VLOG(2) << "Controllability of dynamics (ideally should be " << NStates
+ << "): "
+ << frc971::controls::Controllability(discrete_dynamics.A,
+ discrete_dynamics.B);
+ Eigen::Matrix<Scalar, kNumInputs, NStates> K;
+ Eigen::Matrix<Scalar, NStates, NStates> S;
+ // TODO(james): Swap this to a cheaper DARE solver; we should probably just
+ // do something like we do in Trajectory::CalculatePathGains for the tank
+ // spline controller where we approximate the infinite-horizon DARE solution
+ // by doing a finite-horizon LQR.
+ // Currently the dlqr call represents ~60% of the time spent in the
+ // RunController() method.
+ frc971::controls::dlqr(discrete_dynamics.A, discrete_dynamics.B, params_.Q,
+ params_.R, &K, &S);
+ auto dlqr_time = aos::monotonic_clock::now();
+ const Input U_feedback = K * (goal - X);
+ const Input U = U_ff + U_feedback;
+ Eigen::Matrix<Scalar, kNumInputs, NStates> feedback_contributions;
+ for (int state_idx = 0; state_idx < NStates; ++state_idx) {
+ feedback_contributions.col(state_idx) =
+ K.col(state_idx) * (goal - X)(state_idx);
+ }
+ VLOG(2) << "linearization time "
+ << aos::time::DurationInSeconds(linearization_time - start_time)
+ << " c2d time "
+ << aos::time::DurationInSeconds(c2d_time - linearization_time)
+ << " dlqr time "
+ << aos::time::DurationInSeconds(dlqr_time - c2d_time);
+ return {.U = U,
+ .debug = {.U_ff = U_ff,
+ .U_feedback = U_feedback,
+ .feedback_contributions = feedback_contributions}};
+ }
+
+ LinearDynamics LinearizeDynamics(const State &X, const Input &U) {
+ return {.A = NumericalJacobianX(*params_.dynamics, X, U),
+ .B = NumericalJacobianU(*params_.dynamics, X, U)};
+ }
+
+ private:
+ const Parameters params_;
+};
+
+} // namespace frc971::control_loops::swerve
diff --git a/frc971/control_loops/swerve/linearized_controller_test.cc b/frc971/control_loops/swerve/linearized_controller_test.cc
new file mode 100644
index 0000000..d5e7aee
--- /dev/null
+++ b/frc971/control_loops/swerve/linearized_controller_test.cc
@@ -0,0 +1,87 @@
+#include "frc971/control_loops/swerve/linearized_controller.h"
+
+#include "gtest/gtest.h"
+
+namespace frc971::control_loops::swerve::test {
+
+class LinearizedControllerTest : public ::testing::Test {
+ protected:
+ typedef LinearizedController<2> Controller;
+ typedef Controller::State State;
+ typedef Controller::Input Input;
+ struct LinearDynamics : public Controller::Dynamics {
+ Eigen::Vector2d operator()(
+ const Eigen::Vector2d &X,
+ const Eigen::Matrix<double, 8, 1> &U) const override {
+ return Eigen::Matrix2d{{0.0, 1.0}, {0.0, -0.01}} * X +
+ Eigen::Matrix<double, 2, 8>{
+ {0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0},
+ {1.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0}} *
+ U;
+ }
+ };
+ static Eigen::Matrix<double, kNumInputs, kNumInputs> MakeR() {
+ Eigen::Matrix<double, kNumInputs, kNumInputs> R;
+ R.setIdentity();
+ return R;
+ }
+ LinearizedControllerTest()
+ : controller_({.Q = Eigen::Matrix<double, 2, 2>{{1.0, 0.0}, {0.0, 1.0}},
+ .R = MakeR(),
+ .dt = std::chrono::milliseconds(10),
+ .dynamics = std::make_unique<LinearDynamics>()}) {}
+
+ Controller controller_;
+};
+
+// Sanity check that the dynamics linearization is working correctly.
+TEST_F(LinearizedControllerTest, LinearizedDynamics) {
+ auto dynamics = controller_.LinearizeDynamics(State::Zero(), Input::Zero());
+ EXPECT_EQ(0.0, dynamics.A(0, 0));
+ EXPECT_EQ(0.0, dynamics.A(1, 0));
+ EXPECT_EQ(1.0, dynamics.A(0, 1));
+ EXPECT_EQ(-0.01, dynamics.A(1, 1));
+ // All elements of B except for (1, 0) should be exactly 0.
+ EXPECT_EQ(1.0, dynamics.B(1, 0));
+ EXPECT_EQ(1.0, dynamics.B.norm());
+}
+
+// Confirm that the generated LQR controller is able to generate correct
+// inputs when state and goal are at zero.
+TEST_F(LinearizedControllerTest, ControllerResultAtZero) {
+ auto result =
+ controller_.RunController(State::Zero(), State::Zero(), Input::Zero());
+ EXPECT_EQ(0.0, result.U.norm());
+ EXPECT_EQ(0.0, result.debug.U_ff.norm());
+ EXPECT_EQ(0.0, result.debug.U_feedback.norm());
+}
+
+// Confirm that the generated LQR controller is able to generate correct
+// inputs when state is zero and the goal is non-zero.
+TEST_F(LinearizedControllerTest, ControlToZero) {
+ auto result = controller_.RunController(State::Zero(), State{{1.0}, {0.0}},
+ Input::Zero());
+ EXPECT_LT(0.0, result.U(0, 0));
+ // All other U inputs should be zero.
+ EXPECT_EQ(0.0, result.U.bottomRows<7>().norm());
+ EXPECT_EQ(0.0, result.debug.U_ff.norm());
+ EXPECT_EQ(0.0,
+ (result.U - (result.debug.U_ff + result.debug.U_feedback)).norm());
+}
+
+// Confirm that the generated LQR controller is able to pass through the
+// feedforwards when we have no difference between the goal and the current
+// state.
+TEST_F(LinearizedControllerTest, ControlToNonzeroState) {
+ const State state{{1.0}, {1.0}};
+ auto result = controller_.RunController(
+ state, state,
+ Input{{1.0}, {0.0}, {0.0}, {0.0}, {0.0}, {0.0}, {0.0}, {0.0}});
+ EXPECT_EQ(1.0, result.U(0, 0));
+ // All other U inputs should be zero.
+ EXPECT_EQ(0.0, result.U.bottomRows<7>().norm());
+ EXPECT_EQ(0.0, result.debug.U_feedback.norm());
+ EXPECT_EQ(0.0,
+ (result.U - (result.debug.U_ff + result.debug.U_feedback)).norm());
+}
+} // namespace frc971::control_loops::swerve::test
diff --git a/frc971/control_loops/swerve/multi_experience_collector.py b/frc971/control_loops/swerve/multi_experience_collector.py
new file mode 100644
index 0000000..d0551e1
--- /dev/null
+++ b/frc971/control_loops/swerve/multi_experience_collector.py
@@ -0,0 +1,54 @@
+#!/usr/bin/env python3
+from absl import app
+from absl import flags
+import sys
+from multiprocessing.pool import ThreadPool
+import pathlib
+import subprocess
+
+FLAGS = flags.FLAGS
+flags.DEFINE_string('outdir', '/tmp/swerve', "Directory to write results to.")
+flags.DEFINE_integer('num_actors', 20, 'Number of actors to run in parallel.')
+flags.DEFINE_integer('num_solutions', 100,
+ 'Number of random problems to solve.')
+
+
+def collect_experience(agent_number):
+ filename = f'{agent_number}'
+ if FLAGS.outdir:
+ subdir = pathlib.Path(FLAGS.outdir) / filename
+ else:
+ subdir = pathlib.Path(filename)
+ subdir.mkdir(parents=True, exist_ok=True)
+
+ with open(f'{subdir.resolve()}/log', 'w') as output:
+ subprocess.check_call(
+ args=[
+ sys.executable,
+ "frc971/control_loops/swerve/experience_collector",
+ f"--seed={agent_number}",
+ f"--outputdir={subdir.resolve()}",
+ "--quiet",
+ f"--num_solutions={FLAGS.num_solutions}",
+ ],
+ stdout=output,
+ stderr=output,
+ )
+
+
+def main(argv):
+ # Load a simple problem first so we compile with less system load. This
+ # makes it faster on a processor with frequency boosting.
+ subprocess.check_call(args=[
+ sys.executable,
+ "frc971/control_loops/swerve/experience_collector",
+ "--compileonly",
+ ])
+
+ # Try a bunch of goals now
+ with ThreadPool(FLAGS.num_actors) as pool:
+ pool.starmap(collect_experience, zip(range(FLAGS.num_actors), ))
+
+
+if __name__ == '__main__':
+ app.run(main)
diff --git a/frc971/control_loops/swerve/physics_debug.py b/frc971/control_loops/swerve/physics_debug.py
index db9ea85..04983d4 100644
--- a/frc971/control_loops/swerve/physics_debug.py
+++ b/frc971/control_loops/swerve/physics_debug.py
@@ -10,7 +10,7 @@
class PhysicsDebug(object):
def wrap(self, python_module):
- self.swerve_physics = utils.wrap(python_module.swerve_physics)
+ self.swerve_physics = utils.wrap(python_module.swerve_full_dynamics)
self.contact_patch_velocity = [
utils.wrap_module(python_module.contact_patch_velocity, i)
for i in range(4)
@@ -102,7 +102,7 @@
[40.0], [0.0]])
def calc_I(t, x):
- x_goal = numpy.zeros((16, 1))
+ x_goal = numpy.zeros(16)
Kp_steer = 15.0
Kp_drive = 0.0
@@ -182,12 +182,28 @@
print(result.t.shape)
xdot = numpy.zeros(result.y.shape)
print("shape", xdot.shape)
+
+ U_control = numpy.zeros((8, 1))
+
+ for i in range(numpy.shape(result.t)[0]):
+ U_control = numpy.hstack((
+ U_control,
+ numpy.reshape(
+ calc_I(result.t[i], result.y[:, i]),
+ (8, 1),
+ ),
+ ))
+
+ U_control = numpy.delete(U_control, 0, 1)
+
for i in range(xdot.shape[1]):
- xdot[:, i] = self.swerve_physics(result.y[:, i], self.I)[:, 0]
+ xdot[:, i] = self.swerve_physics(result.y[:, i],
+ U_control[:, i])[:, 0]
for i in range(2):
print(f"For t {i * 0.005}")
- self.print_state(self.swerve_physics, self.I, result.y[:, i])
+ self.print_state(self.swerve_physics, U_control[:, i], result.y[:,
+ i])
def ev(fn, Y):
return [fn(Y[:, i], self.I)[0, 0] for i in range(Y.shape[1])]
@@ -217,7 +233,7 @@
label=f'steering_accel{i}')
axs[i].legend()
- fig, axs = pylab.subplots(3)
+ fig, axs = pylab.subplots(4)
axs[0].plot(result.t, result.y[3, :], label="drive_velocity0")
axs[0].plot(result.t, result.y[7, :], label="drive_velocity1")
axs[0].plot(result.t, result.y[11, :], label="drive_velocity2")
@@ -226,6 +242,7 @@
axs[1].plot(result.t, result.y[20, :], label="vy")
axs[1].plot(result.t, result.y[21, :], label="omega")
+ axs[1].plot(result.t, result.y[18, :], label="theta")
axs[1].plot(result.t, xdot[20, :], label="ay")
axs[1].plot(result.t, xdot[21, :], label="alpha")
axs[1].legend()
@@ -239,24 +256,19 @@
axs[2].legend()
pylab.figure()
- U_control = numpy.zeros((8, 1))
-
- for i in range(numpy.shape(result.t)[0]):
- U_control = numpy.hstack((
- U_control,
- numpy.reshape(
- calc_I(result.t[i], numpy.reshape(result.y[:, i],
- (25, 1))),
- (8, 1),
- ),
- ))
-
- U_control = numpy.delete(U_control, 0, 1)
pylab.plot(result.t, U_control[0, :], label="Is0")
pylab.plot(result.t, U_control[1, :], label="Id0")
pylab.legend()
+ F_plot = numpy.array([
+ self.F[0](result.y[:, i], U_control[:, i])
+ for i in range(result.y[0, :].size)
+ ])
+ axs[3].plot(result.t, F_plot[:, 0], label="force_x0")
+ axs[3].plot(result.t, F_plot[:, 1], label="force_y0")
+ axs[3].legend()
+
pylab.show()
diff --git a/frc971/control_loops/swerve/physics_test.py b/frc971/control_loops/swerve/physics_test.py
index af3dc17..bc366fa 100644
--- a/frc971/control_loops/swerve/physics_test.py
+++ b/frc971/control_loops/swerve/physics_test.py
@@ -18,7 +18,9 @@
from frc971.control_loops.swerve import dynamics
from frc971.control_loops.swerve import nocaster_dynamics
from frc971.control_loops.swerve import physics_test_utils as utils
+from frc971.control_loops.swerve import casadi_velocity_mpc_lib
from frc971.control_loops.swerve import jax_dynamics
+from frc971.control_loops.swerve.cpp_dynamics import swerve_dynamics as cpp_dynamics
class TestSwervePhysics(unittest.TestCase):
@@ -59,6 +61,7 @@
Xdot = self.position_swerve_full_dynamics(X, U)
Xdot_jax = jax_dynamics.full_dynamics(self.coefficients, X[:, 0], U[:,
0])
+ self.assertEqual(Xdot.shape[0], Xdot_jax.shape[0])
self.assertLess(
numpy.linalg.norm(Xdot[:, 0] - Xdot_jax),
@@ -71,6 +74,9 @@
velocity_physics_jax = jax_dynamics.velocity_dynamics(
self.coefficients, X_velocity[:, 0], U[:, 0])
+ self.assertEqual(velocity_physics.shape[0],
+ velocity_physics_jax.shape[0])
+
self.assertLess(
numpy.linalg.norm(velocity_physics[:, 0] - velocity_physics_jax),
2e-8,
@@ -677,6 +683,105 @@
self.assertAlmostEqual(Xdot[dynamics.VELOCITY_STATE_OMEGAS2, 0], 0.0)
self.assertAlmostEqual(Xdot[dynamics.VELOCITY_STATE_OMEGAS3, 0], 0.0)
+ def test_constant_torque(self):
+ """Tests that the robot exerts the same amount of torque no matter the orientation"""
+ steer_I = numpy.reshape(numpy.array([(i % 2) * 20 for i in range(8)]),
+ (8, 1))
+
+ X = utils.state_vector(velocity=numpy.array([[0.0], [0.0]]),
+ omega=0.0,
+ module_angles=[
+ 3 * numpy.pi / 4.0, -3 * numpy.pi / 4.0,
+ -numpy.pi / 4.0, numpy.pi / 4.0
+ ],
+ drive_wheel_velocity=1.0)
+ Xdot = self.swerve_full_dynamics(X, steer_I, skip_compare=True)
+
+ X_rot = utils.state_vector(velocity=numpy.array([[0.0], [0.0]]),
+ omega=0.0,
+ theta=numpy.pi,
+ module_angles=[
+ 3 * numpy.pi / 4.0, -3 * numpy.pi / 4.0,
+ -numpy.pi / 4.0, numpy.pi / 4.0
+ ],
+ drive_wheel_velocity=1.0)
+ Xdot_rot = self.swerve_full_dynamics(X_rot, steer_I, skip_compare=True)
+
+ self.assertGreater(Xdot[dynamics.STATE_OMEGA, 0], 0.0)
+ self.assertAlmostEqual(Xdot[dynamics.STATE_OMEGA, 0],
+ Xdot_rot[dynamics.STATE_OMEGA, 0])
+
+ def test_cost_equality(self):
+ """Tests that the casadi and jax cost functions match."""
+ mpc = casadi_velocity_mpc_lib.MPC(jit=False)
+ cost = mpc.make_cost()
+
+ for i in range(10):
+ X = numpy.random.uniform(size=(dynamics.NUM_VELOCITY_STATES, ))
+ U = numpy.random.uniform(low=-10, high=10, size=(8, ))
+ R = numpy.random.uniform(low=-1, high=1, size=(3, ))
+
+ J = numpy.array(cost(X, U, R))[0, 0]
+ jax_J = jax_dynamics.mpc_cost(self.coefficients, X, U, R)
+
+ self.assertAlmostEqual(J, jax_J)
+
+ R = jax.numpy.array([0.0, 0.0, 1.0])
+
+ # Now try spinning in place and make sure the cost doesn't change.
+ # This tells us if we got our rotations right.
+ steer_I = numpy.array([(i % 2) * 20 for i in range(8)])
+
+ X = utils.state_vector(velocity=numpy.array([[0.0], [0.0]]),
+ omega=0.0,
+ module_angles=[
+ 3 * numpy.pi / 4.0, -3 * numpy.pi / 4.0,
+ -numpy.pi / 4.0, numpy.pi / 4.0
+ ],
+ drive_wheel_velocity=1.0)
+
+ jax_J_orig = jax_dynamics.mpc_cost(self.coefficients,
+ self.to_velocity_state(X)[:, 0],
+ steer_I, R)
+
+ X_rotated = utils.state_vector(velocity=numpy.array([[0.0], [0.0]]),
+ omega=0.0,
+ theta=numpy.pi,
+ module_angles=[
+ 3 * numpy.pi / 4.0,
+ -3 * numpy.pi / 4.0,
+ -numpy.pi / 4.0, numpy.pi / 4.0
+ ],
+ drive_wheel_velocity=1.0)
+ jax_J_rotated = jax_dynamics.mpc_cost(
+ self.coefficients,
+ self.to_velocity_state(X_rotated)[:, 0], steer_I, R)
+
+ self.assertAlmostEqual(jax_J_orig, jax_J_rotated)
+
+ def test_cpp_consistency(self):
+ """Tests that the C++ physics are consistent with the Python physics."""
+ # TODO(james): Currently the physics only match at X = 0 and U = 0.
+ # Fix this.
+ # Maybe due to different atan2 implementations?
+ # TODO(james): Fold this into the general comparisons for JAX versus
+ # casadi once the physics actually match.
+ for current in [0]:
+ print(f"Current: {current}")
+ steer_I = numpy.zeros((8, 1)) + current
+ for state_values in [0.0]:
+ print(f"States all set to: {state_values}")
+ X = numpy.zeros((dynamics.NUM_STATES, 1)) + state_values
+ Xdot_py = self.swerve_full_dynamics(X,
+ steer_I,
+ skip_compare=True)
+ Xdot_cpp = numpy.array(
+ cpp_dynamics(X.flatten().tolist(),
+ steer_I.flatten().tolist())).reshape((25, 1))
+ for index in range(dynamics.NUM_STATES):
+ self.assertAlmostEqual(Xdot_py[index, 0], Xdot_cpp[index,
+ 0])
+
if __name__ == "__main__":
unittest.main()
diff --git a/frc971/control_loops/swerve/simplified_dynamics.h b/frc971/control_loops/swerve/simplified_dynamics.h
new file mode 100644
index 0000000..9afe636
--- /dev/null
+++ b/frc971/control_loops/swerve/simplified_dynamics.h
@@ -0,0 +1,372 @@
+#ifndef FRC971_CONTROL_LOOPS_SWERVE_SIMPLIFIED_DYNAMICS_H_
+#define FRC971_CONTROL_LOOPS_SWERVE_SIMPLIFIED_DYNAMICS_H_
+#include "absl/log/check.h"
+#include "absl/log/log.h"
+
+#include "aos/util/math.h"
+#include "frc971/control_loops/swerve/auto_diff_jacobian.h"
+#include "frc971/control_loops/swerve/dynamics.h"
+#include "frc971/control_loops/swerve/motors.h"
+
+namespace frc971::control_loops::swerve {
+
+// Provides a simplified set of physics representing a swerve drivetrain.
+// Broadly speaking, these dynamics model:
+// * Standard motors on the drive and steer axes, with no coupling between
+// the motors.
+// * Assume that the steer direction of each module is only influenced by
+// the inertia of the motor rotor plus some small aligning force.
+// * Assume that torque from the drive motor is transferred directly to the
+// carpet.
+// * Assume that a lateral force on the wheel is generated proportional to the
+// slip angle of the wheel.
+//
+// This class is templated on a Scalar that is used to determine whether you
+// want to use double or single-precision floats for the calculations here.
+//
+// Several individual methods on this class are also templated on a LocalScalar
+// type. This is provided to allow those methods to be called with ceres Jets to
+// do autodifferentiation within various solvers/jacobian calculators.
+template <typename Scalar = double>
+class SimplifiedDynamics {
+ public:
+ struct ModuleParams {
+ // Module position relative to the center of mass of the robot.
+ Eigen::Matrix<Scalar, 2, 1> position;
+ // Coefficient dictating how much sideways force is generated at a given
+ // slip angle. Units are effectively Newtons / radian of slip.
+ Scalar slip_angle_coefficient;
+ // Coefficient dicating how much the steer wheel is forced into alignment
+ // by the motion of the wheel over the ground (i.e., we are assuming that
+ // if you push the robot along it will cause the wheels to eventually
+ // align with the direction of motion).
+ // In radians / sec^2 / radians of slip angle.
+ Scalar slip_angle_alignment_coefficient;
+ // Parameters for the steer and drive motors.
+ Motor steer_motor;
+ Motor drive_motor;
+ // radians of module steering = steer_ratio * radians of motor shaft
+ Scalar steer_ratio;
+ // meters of driving = drive_ratio * radians of motor shaft
+ Scalar drive_ratio;
+ };
+ struct Parameters {
+ // Mass of the robot, in kg.
+ Scalar mass;
+ // Moment of inertia of the robot about the yaw axis, in kg * m^2.
+ Scalar moment_of_inertia;
+ // Note: While this technically would support an arbitrary number of
+ // modules, the statically-sized state vectors do limit us to 4 modules
+ // currently, and it should not be counted on that other pieces of code will
+ // be able to support non-4-module swerves.
+ std::vector<ModuleParams> modules;
+ };
+ enum States {
+ // Thetas* and Omegas* are the yaw and yaw rate of the indicated modules.
+ // (note that we do not actually need to track drive speed per module,
+ // as with current control we have the ability to directly command torque
+ // to those motors; however, if we wished to account for the saturation
+ // limits on the motor, then we would need to have access to those states,
+ // although they can be fully derived from the robot vx, vy, theta, and
+ // omega).
+ kThetas0 = 0,
+ kOmegas0 = 1,
+ kThetas1 = 2,
+ kOmegas1 = 3,
+ kThetas2 = 4,
+ kOmegas2 = 5,
+ kThetas3 = 6,
+ kOmegas3 = 7,
+ // Robot yaw, in radians.
+ kTheta = 8,
+ // Robot speed in the global frame, in meters / sec.
+ kVx = 9,
+ kVy = 10,
+ // Robot yaw rate, in radians / sec.
+ kOmega = 11,
+ kNumVelocityStates = 12,
+ // Augmented states for doing position control.
+ // Robot X position in the global frame.
+ kX = 12,
+ // Robot Y position in the global frame.
+ kY = 13,
+ kNumPositionStates = 14,
+ };
+ using Inputs = InputStates::States;
+
+ template <typename ScalarT = Scalar>
+ using VelocityState = Eigen::Matrix<ScalarT, kNumVelocityStates, 1>;
+ template <typename ScalarT = Scalar>
+ using PositionState = Eigen::Matrix<ScalarT, kNumPositionStates, 1>;
+ template <typename ScalarT = Scalar>
+ using VelocityStateSquare =
+ Eigen::Matrix<ScalarT, kNumVelocityStates, kNumVelocityStates>;
+ template <typename ScalarT = Scalar>
+ using PositionStateSquare =
+ Eigen::Matrix<ScalarT, kNumPositionStates, kNumPositionStates>;
+ template <typename ScalarT = Scalar>
+ using PositionBMatrix =
+ Eigen::Matrix<ScalarT, kNumPositionStates, kNumInputs>;
+ template <typename ScalarT = Scalar>
+ using Input = Eigen::Matrix<ScalarT, kNumInputs, 1>;
+
+ SimplifiedDynamics(const Parameters ¶ms) : params_(params) {
+ for (size_t module_index = 0; module_index < params_.modules.size();
+ ++module_index) {
+ module_dynamics_.emplace_back(params_, module_index);
+ }
+ }
+
+ // Returns the derivative of state for the given state and input.
+ template <typename LocalScalar>
+ PositionState<LocalScalar> Dynamics(const PositionState<LocalScalar> &state,
+ const Input<LocalScalar> &input) const {
+ PositionState<LocalScalar> Xdot = PositionState<LocalScalar>::Zero();
+
+ for (const ModuleDynamics &module : module_dynamics_) {
+ Xdot += module.PartialDynamics(state, input);
+ }
+
+ // And finally catch the global states:
+ Xdot(kX) = state(kVx);
+ Xdot(kY) = state(kVy);
+ Xdot(kTheta) = state(kOmega);
+
+ return Xdot;
+ }
+
+ template <typename LocalScalar>
+ VelocityState<LocalScalar> VelocityDynamics(
+ const VelocityState<LocalScalar> &state,
+ const Input<LocalScalar> &input) const {
+ PositionState<LocalScalar> input_state = PositionState<LocalScalar>::Zero();
+ input_state.template topRows<kNumVelocityStates>() = state;
+ return Dynamics(input_state, input).template topRows<kNumVelocityStates>();
+ }
+
+ std::pair<PositionStateSquare<>, PositionBMatrix<>> LinearizedDynamics(
+ const PositionState<> &state, const Input<> &input) {
+ DynamicsFunctor functor(*this);
+ Eigen::Matrix<Scalar, kNumPositionStates + kNumInputs, 1> parameters;
+ parameters.template topRows<kNumPositionStates>() = state;
+ parameters.template bottomRows<kNumInputs>() = input;
+ const Eigen::Matrix<Scalar, kNumPositionStates,
+ kNumPositionStates + kNumInputs>
+ jacobian =
+ AutoDiffJacobian<Scalar, DynamicsFunctor,
+ kNumPositionStates + kNumInputs,
+ kNumPositionStates>::Jacobian(functor, parameters);
+ return {
+ jacobian.template block<kNumPositionStates, kNumPositionStates>(0, 0),
+ jacobian.template block<kNumPositionStates, kNumInputs>(
+ 0, kNumPositionStates)};
+ }
+
+ private:
+ // Wrapper to provide an operator() for the dynamisc class that allows it to
+ // be used by the auto-differentiation code.
+ class DynamicsFunctor {
+ public:
+ DynamicsFunctor(const SimplifiedDynamics &dynamics) : dynamics_(dynamics) {}
+
+ template <typename LocalScalar>
+ Eigen::Matrix<LocalScalar, kNumPositionStates, 1> operator()(
+ const Eigen::Map<const Eigen::Matrix<
+ LocalScalar, kNumPositionStates + kNumInputs, 1>>
+ input) const {
+ return dynamics_.Dynamics(
+ PositionState<LocalScalar>(
+ input.template topRows<kNumPositionStates>()),
+ Input<LocalScalar>(input.template bottomRows<kNumInputs>()));
+ }
+
+ private:
+ const SimplifiedDynamics &dynamics_;
+ };
+
+ // Represents the dynamics of an individual module.
+ class ModuleDynamics {
+ public:
+ ModuleDynamics(const Parameters &robot_params, const size_t module_index)
+ : robot_params_(robot_params), module_index_(module_index) {
+ CHECK_LT(module_index_, robot_params_.modules.size());
+ }
+
+ // This returns the portions of the derivative of state that are due to the
+ // individual module. The result from this function should be able to be
+ // naively summed with the dynamics for each other module plus some global
+ // dynamics (which take care of that e.g. xdot = vx) and give you the
+ // overall dynamics of the system.
+ template <typename LocalScalar>
+ PositionState<LocalScalar> PartialDynamics(
+ const PositionState<LocalScalar> &state,
+ const Input<LocalScalar> &input) const {
+ PositionState<LocalScalar> Xdot = PositionState<LocalScalar>::Zero();
+
+ Xdot(ThetasIdx()) = state(OmegasIdx());
+
+ // Steering dynamics for an individual module assume ~zero friction,
+ // and thus ~the only inertia is from the motor rotor itself.
+ // torque_motor = stall_torque / stall_current * current
+ // accel_motor = torque_motor / motor_inertia
+ // accel_steer = accel_motor * steer_ratio
+ const Motor &steer_motor = module_params().steer_motor;
+ const LocalScalar steer_motor_accel =
+ input(IsIdx()) *
+ static_cast<Scalar>(
+ module_params().steer_ratio * steer_motor.stall_torque /
+ (steer_motor.stall_current * steer_motor.motor_inertia));
+
+ // For the impacts of the modules on the overall robot
+ // dynamics (X, Y, and theta acceleration), we calculate the forces
+ // generated by the module and then apply them. These forces come from
+ // two effects in this model:
+ // 1. Slip angle of the module (dependent on the current robot velocity &
+ // module steer angle).
+ // 2. Drive torque from the module (dependent on the current drive
+ // current and module steer angle).
+ // We assume no torque is generated from e.g. the wheel resisting the
+ // steering motion.
+ //
+ // clang-format off
+ //
+ // For slip angle we have:
+ // wheel_velocity = R(-theta - theta_steer) * (
+ // robot_vel + omega.cross(R(theta) * module_position))
+ // slip_angle = -atan2(wheel_velocity)
+ // slip_force = slip_angle_coefficient * slip_angle
+ // slip_force_direction = theta + theta_steer + pi / 2
+ // force_x = slip_force * cos(slip_force_direction)
+ // force_y = slip_force * sin(slip_force_direction)
+ // accel_* = force_* / mass
+ // # And now calculate torque from slip angle.
+ // torque_vec = module_position.cross([slip_force * cos(theta_steer + pi / 2),
+ // slip_force * sin(theta_steer + pi / 2),
+ // 0.0])
+ // torque_vec = module_position.cross([slip_force * -sin(theta_steer),
+ // slip_force * cos(theta_steer),
+ // 0.0])
+ // robot_torque = torque_vec.z()
+ //
+ // For drive torque we have:
+ // drive_force = (drive_current * stall_torque / stall_current) / drive_ratio
+ // drive_force_direction = theta + theta_steer
+ // force_x = drive_force * cos(drive_force_direction)
+ // force_y = drive_force * sin(drive_force_direction)
+ // torque_vec = drive_force * module_position.cross([cos(theta_steer),
+ // sin(theta_steer),
+ // 0.0])
+ // torque = torque_vec.z()
+ //
+ // clang-format on
+
+ const Eigen::Matrix<Scalar, 3, 1> module_position{
+ {module_params().position.x()},
+ {module_params().position.y()},
+ {0.0}};
+ const LocalScalar theta = state(kTheta);
+ const LocalScalar theta_steer = state(ThetasIdx());
+ const Eigen::Matrix<LocalScalar, 3, 1> wheel_velocity_in_global_frame =
+ Eigen::Matrix<LocalScalar, 3, 1>(state(kVx), state(kVy),
+ static_cast<LocalScalar>(0.0)) +
+ (Eigen::Matrix<LocalScalar, 3, 1>(static_cast<LocalScalar>(0.0),
+ static_cast<LocalScalar>(0.0),
+ state(kOmega))
+ .cross(Eigen::AngleAxis<LocalScalar>(
+ theta, Eigen::Matrix<LocalScalar, 3, 1>::UnitZ()) *
+ module_position));
+ const Eigen::Matrix<LocalScalar, 3, 1> wheel_velocity_in_wheel_frame =
+ Eigen::AngleAxis<LocalScalar>(
+ -theta - theta_steer, Eigen::Matrix<LocalScalar, 3, 1>::UnitZ()) *
+ wheel_velocity_in_global_frame;
+ // The complicated dynamics use some obnoxious-looking functions to
+ // try to approximate how the slip angle behaves a low speeds to better
+ // condition the dynamics. Because I couldn't be bothered to copy those
+ // dynamics, instead just bias the slip angle to zero at low speeds.
+ const LocalScalar wheel_speed = wheel_velocity_in_wheel_frame.norm();
+ const Scalar start_speed = 0.1;
+ const LocalScalar heading_truth_proportion = -expm1(
+ /*arbitrary large number=*/static_cast<Scalar>(-100.0) *
+ (wheel_speed - start_speed));
+ const LocalScalar wheel_heading =
+ (wheel_speed < start_speed)
+ ? static_cast<LocalScalar>(0.0)
+ : heading_truth_proportion *
+ atan2(wheel_velocity_in_wheel_frame.y(),
+ wheel_velocity_in_wheel_frame.x());
+
+ // We wrap slip_angle with a sin() not because there is actually a sin()
+ // in the real math but rather because we need to smoothly and correctly
+ // handle slip angles between pi / 2 and 3 * pi / 2.
+ const LocalScalar slip_angle = sin(-wheel_heading);
+ const LocalScalar slip_force =
+ module_params().slip_angle_coefficient * slip_angle;
+ const LocalScalar slip_force_direction =
+ theta + theta_steer + static_cast<Scalar>(M_PI_2);
+ const Eigen::Matrix<LocalScalar, 3, 1> slip_force_vec =
+ slip_force * UnitYawVector<LocalScalar>(slip_force_direction);
+ const LocalScalar slip_torque =
+ module_position
+ .cross(slip_force *
+ UnitYawVector<LocalScalar>(theta_steer +
+ static_cast<Scalar>(M_PI_2)))
+ .z();
+
+ // drive torque calculations
+ const Motor &drive_motor = module_params().drive_motor;
+ const LocalScalar drive_force =
+ input(IdIdx()) * static_cast<Scalar>(drive_motor.stall_torque /
+ drive_motor.stall_current /
+ module_params().drive_ratio);
+ const Eigen::Matrix<LocalScalar, 3, 1> drive_force_vec =
+ drive_force * UnitYawVector<LocalScalar>(theta + theta_steer);
+ const LocalScalar drive_torque =
+ drive_force *
+ module_position.cross(UnitYawVector<LocalScalar>(theta_steer)).z();
+ // We add in an aligning force on the wheels primarily to help provide a
+ // bit of impetus to the controllers/solvers to discourage aggressive
+ // slip angles. If we do not include this, then the dynamics make it look
+ // like there are no losses to using extremely aggressive slip angles.
+ const LocalScalar wheel_alignment_accel =
+ -module_params().slip_angle_alignment_coefficient * slip_angle;
+
+ Xdot(OmegasIdx()) = steer_motor_accel + wheel_alignment_accel;
+ // Sum up all the forces.
+ Xdot(kVx) =
+ (slip_force_vec.x() + drive_force_vec.x()) / robot_params_.mass;
+ Xdot(kVy) =
+ (slip_force_vec.y() + drive_force_vec.y()) / robot_params_.mass;
+ Xdot(kOmega) =
+ (slip_torque + drive_torque) / robot_params_.moment_of_inertia;
+
+ return Xdot;
+ }
+
+ private:
+ template <typename LocalScalar>
+ Eigen::Matrix<LocalScalar, 3, 1> UnitYawVector(LocalScalar yaw) const {
+ return Eigen::Matrix<LocalScalar, 3, 1>{
+ {static_cast<LocalScalar>(cos(yaw))},
+ {static_cast<LocalScalar>(sin(yaw))},
+ {static_cast<LocalScalar>(0.0)}};
+ }
+ size_t ThetasIdx() const { return kThetas0 + 2 * module_index_; }
+ size_t OmegasIdx() const { return kOmegas0 + 2 * module_index_; }
+ size_t IsIdx() const { return Inputs::kIs0 + 2 * module_index_; }
+ size_t IdIdx() const { return Inputs::kId0 + 2 * module_index_; }
+
+ const ModuleParams &module_params() const {
+ return robot_params_.modules[module_index_];
+ }
+
+ const Parameters robot_params_;
+
+ const size_t module_index_;
+ };
+
+ Parameters params_;
+ std::vector<ModuleDynamics> module_dynamics_;
+};
+
+} // namespace frc971::control_loops::swerve
+#endif // FRC971_CONTROL_LOOPS_SWERVE_SIMPLIFIED_DYNAMICS_H_
diff --git a/frc971/control_loops/swerve/simplified_dynamics_test.cc b/frc971/control_loops/swerve/simplified_dynamics_test.cc
new file mode 100644
index 0000000..894a85b
--- /dev/null
+++ b/frc971/control_loops/swerve/simplified_dynamics_test.cc
@@ -0,0 +1,244 @@
+#include "frc971/control_loops/swerve/simplified_dynamics.h"
+
+#include <functional>
+
+#include "absl/log/log.h"
+#include "gtest/gtest.h"
+
+#include "aos/time/time.h"
+#include "frc971/control_loops/jacobian.h"
+
+namespace frc971::control_loops::swerve::testing {
+class SimplifiedDynamicsTest : public ::testing::Test {
+ protected:
+ using Dynamics = SimplifiedDynamics<double>;
+ using PositionState = Dynamics::PositionState<double>;
+ using States = Dynamics::States;
+ using Inputs = Dynamics::Inputs;
+ using Input = Dynamics::Input<double>;
+ using ModuleParams = Dynamics::ModuleParams;
+ using Parameters = Dynamics::Parameters;
+ static ModuleParams MakeModule(const Eigen::Vector2d &position,
+ bool wheel_alignment) {
+ return ModuleParams{
+ .position = position,
+ .slip_angle_coefficient = 200.0,
+ .slip_angle_alignment_coefficient = wheel_alignment ? 1.0 : 0.0,
+ .steer_motor = KrakenFOC(),
+ .drive_motor = KrakenFOC(),
+ .steer_ratio = 0.1,
+ .drive_ratio = 0.01};
+ }
+ static Parameters MakeParams(bool wheel_alignment) {
+ return {.mass = 60,
+ .moment_of_inertia = 2,
+ .modules = {
+ MakeModule({1.0, 1.0}, wheel_alignment),
+ MakeModule({-1.0, 1.0}, wheel_alignment),
+ MakeModule({-1.0, -1.0}, wheel_alignment),
+ MakeModule({1.0, -1.0}, wheel_alignment),
+ }};
+ }
+ SimplifiedDynamicsTest() : dynamics_(MakeParams(false)) {}
+
+ PositionState ValidateDynamics(const PositionState &state,
+ const Input &input) {
+ const PositionState Xdot = dynamics_.Dynamics(state, input);
+ // Sanity check simple invariants:
+ EXPECT_EQ(Xdot(Dynamics::kX), state(Dynamics::kVx));
+ EXPECT_EQ(Xdot(Dynamics::kY), state(Dynamics::kVy));
+ EXPECT_EQ(Xdot(Dynamics::kTheta), state(Dynamics::kOmega));
+
+ // Check that the dynamics linearization produces numbers that match numeric
+ // differentiation of the dynamics.
+ aos::monotonic_clock::time_point start_time = aos::monotonic_clock::now();
+ const auto linearized_dynamics = dynamics_.LinearizedDynamics(state, input);
+ const aos::monotonic_clock::duration auto_diff_time =
+ aos::monotonic_clock::now() - start_time;
+
+ start_time = aos::monotonic_clock::now();
+ auto numerical_A = NumericalJacobianX(
+ std::bind(&Dynamics::Dynamics<double>, &dynamics_,
+ std::placeholders::_1, std::placeholders::_2),
+ state, input);
+ auto numerical_B = NumericalJacobianU(
+ std::bind(&Dynamics::Dynamics<double>, &dynamics_,
+ std::placeholders::_1, std::placeholders::_2),
+ state, input);
+ const aos::monotonic_clock::duration numerical_time =
+ aos::monotonic_clock::now() - start_time;
+ VLOG(1) << "Autodifferentiation took " << auto_diff_time
+ << " while numerical differentiation took " << numerical_time;
+ EXPECT_LT((numerical_A - linearized_dynamics.first).norm(), 1e-6)
+ << "Numerical result:\n"
+ << numerical_A << "\nAuto-diff result:\n"
+ << linearized_dynamics.first;
+ EXPECT_LT((numerical_B - linearized_dynamics.second).norm(), 1e-6)
+ << "Numerical result:\n"
+ << numerical_B << "\nAuto-diff result:\n"
+ << linearized_dynamics.second;
+ return Xdot;
+ }
+
+ Dynamics dynamics_;
+};
+
+// Test that if all states and inputs are at zero that the robot won't move.
+TEST_F(SimplifiedDynamicsTest, ZeroIsZero) {
+ EXPECT_EQ(PositionState::Zero(),
+ ValidateDynamics(PositionState::Zero(), Input::Zero()));
+}
+
+// Test that if we are travelling straight forwards with zero inputs that we
+// just coast.
+TEST_F(SimplifiedDynamicsTest, CoastForwards) {
+ PositionState state = PositionState::Zero();
+ state(States::kVx) = 1.0;
+ PositionState expected = PositionState::Zero();
+ expected(States::kX) = 1.0;
+ EXPECT_EQ(expected, ValidateDynamics(state, Input::Zero()));
+}
+
+// Tests that we can accelerate the robot.
+TEST_F(SimplifiedDynamicsTest, AccelerateStraight) {
+ // Check that the drive currents behave as anticipated and accelerate the
+ // robot.
+ Input input{{0.0}, {1.0}, {0.0}, {1.0}, {0.0}, {1.0}, {0.0}, {1.0}};
+ PositionState state = PositionState::Zero();
+ state(States::kVx) = 0.0;
+ PositionState result = ValidateDynamics(state, input);
+ EXPECT_EQ(result.norm(), result(States::kVx));
+ EXPECT_LT(0.1, result(States::kVx));
+}
+
+// Test that if we are driving straight sideways (so our wheel are at 90
+// degrees) that we experience a force slowing us down.
+TEST_F(SimplifiedDynamicsTest, ForceWheelsSideways) {
+ PositionState state = PositionState::Zero();
+ state(States::kVy) = 1.0;
+ PositionState result = ValidateDynamics(state, Input::Zero());
+ EXPECT_LT(result.topRows<States::kVy>().norm(), 1e-10)
+ << ": All derivatives prior to the vy state should be ~zero.\n"
+ << result;
+ EXPECT_LT(result(States::kVy), -1.0)
+ << ": expected non-trivial deceleration.";
+ EXPECT_EQ(result(States::kOmega), 0.0);
+}
+
+// Tests that we can make the robot spin in place by orienting all the wheels
+TEST_F(SimplifiedDynamicsTest, SpinInPlaceNoSlip) {
+ PositionState state = PositionState::Zero();
+ state(States::kThetas0) = 3.0 * M_PI / 4.0;
+ state(States::kThetas1) = 5.0 * M_PI / 4.0;
+ state(States::kThetas2) = 7.0 * M_PI / 4.0;
+ state(States::kThetas3) = 1.0 * M_PI / 4.0;
+ state(States::kOmega) = 1.0;
+ PositionState result = ValidateDynamics(state, Input::Zero());
+ EXPECT_NEAR(result.norm(), 1.0, 1e-10)
+ << ": Only non-zero state should be kTheta, which should be exactly 1.0.";
+ EXPECT_EQ(result(States::kTheta), 1.0);
+
+ // Sanity check that when we then apply drive torque to the wheels that that
+ // apins the robot more.
+ Input input{{0.0}, {1.0}, {0.0}, {1.0}, {0.0}, {1.0}, {0.0}, {1.0}};
+ result = ValidateDynamics(state, input);
+ EXPECT_EQ(result(States::kTheta), 1.0);
+ EXPECT_LT(1.0, result(States::kOmega));
+ // Everything else should be ~zero.
+ result(States::kTheta) = 0.0;
+ result(States::kOmega) = 0.0;
+ EXPECT_LT(result.norm(), 1e-10);
+}
+
+// Tests that we can spin in place when skid-steering (i.e., all wheels stay
+// pointed straight, but we still attempt to spint he robot).
+TEST_F(SimplifiedDynamicsTest, SpinInPlaceSkidSteer) {
+ PositionState state = PositionState::Zero();
+ state(States::kThetas0) = -M_PI;
+ state(States::kThetas1) = -M_PI;
+ state(States::kThetas2) = 0.0;
+ state(States::kThetas3) = 0.0;
+ state(States::kOmega) = 1.0;
+ PositionState result = ValidateDynamics(state, Input::Zero());
+ EXPECT_EQ(result(States::kTheta), 1.0);
+ EXPECT_LT(result(States::kOmega), -1.0)
+ << "We should be aggressively decelerrating when slipping wheels.";
+ // Everything else should be ~zero.
+ result(States::kTheta) = 0.0;
+ result(States::kOmega) = 0.0;
+ EXPECT_LT(result.norm(), 1e-10);
+
+ // Sanity check that when we then apply drive torque to the wheels that that
+ // we can counteract the spin.
+ Input input{{0.0}, {100.0}, {0.0}, {100.0}, {0.0}, {100.0}, {0.0}, {100.0}};
+ result = ValidateDynamics(state, input);
+ EXPECT_EQ(result(States::kTheta), 1.0);
+ EXPECT_LT(1.0, result(States::kOmega));
+ // Everything else should be ~zero.
+ result(States::kTheta) = 0.0;
+ result(States::kOmega) = 0.0;
+ EXPECT_LT(result.norm(), 1e-10);
+}
+
+// Tests that we can spin in place when skid-steering backwards (ensures that
+// slip angle calculations and the such handle the sign changes correctly).
+TEST_F(SimplifiedDynamicsTest, SpinInPlaceSkidSteerBackwards) {
+ PositionState state = PositionState::Zero();
+ state(States::kThetas0) = 0.0;
+ state(States::kThetas1) = 0.0;
+ state(States::kThetas2) = M_PI;
+ state(States::kThetas3) = M_PI;
+ state(States::kOmega) = 1.0;
+ PositionState result = ValidateDynamics(state, Input::Zero());
+ EXPECT_EQ(result(States::kTheta), 1.0);
+ EXPECT_LT(result(States::kOmega), -1.0)
+ << "We should be aggressively decelerrating when slipping wheels.";
+ // Everything else should be ~zero.
+ result(States::kTheta) = 0.0;
+ result(States::kOmega) = 0.0;
+ EXPECT_LT(result.norm(), 1e-10);
+
+ // Sanity check that when we then apply drive torque to the wheels that that
+ // we can counteract the spin.
+ Input input{{0.0}, {-100.0}, {0.0}, {-100.0},
+ {0.0}, {-100.0}, {0.0}, {-100.0}};
+ result = ValidateDynamics(state, input);
+ EXPECT_EQ(result(States::kTheta), 1.0);
+ EXPECT_LT(1.0, result(States::kOmega));
+ // Everything else should be ~zero.
+ result(States::kTheta) = 0.0;
+ result(States::kOmega) = 0.0;
+ EXPECT_LT(result.norm(), 1e-10);
+}
+
+// Test that if we turn on the wheel alignment forces that it results in forces
+// that cause the wheels to align to straight over time.
+TEST_F(SimplifiedDynamicsTest, WheelAlignmentForces) {
+ dynamics_ = Dynamics(MakeParams(true));
+ PositionState state = PositionState::Zero();
+ state(States::kThetas0) = -0.1;
+ state(States::kThetas1) = -0.1;
+ state(States::kThetas2) = -0.1;
+ state(States::kThetas3) = -0.1;
+ state(States::kVx) = 1.0;
+ PositionState result = ValidateDynamics(state, Input::Zero());
+ EXPECT_LT(1e-2, result(States::kOmegas0));
+ EXPECT_LT(1e-2, result(States::kOmegas1));
+ EXPECT_LT(1e-2, result(States::kOmegas2));
+ EXPECT_LT(1e-2, result(States::kOmegas3));
+}
+
+// Do some fuzz testing of the jacobian calculations.
+TEST_F(SimplifiedDynamicsTest, Fuzz) {
+ for (size_t state_index = 0; state_index < States::kNumPositionStates;
+ ++state_index) {
+ SCOPED_TRACE(state_index);
+ PositionState state = PositionState::Zero();
+ for (const double value : {-1.0, 0.0, 1.0}) {
+ SCOPED_TRACE(value);
+ state(state_index) = value;
+ ValidateDynamics(state, Input::Zero());
+ }
+ }
+}
+} // namespace frc971::control_loops::swerve::testing
diff --git a/frc971/control_loops/swerve/swerve_control_loops.cc b/frc971/control_loops/swerve/swerve_control_loops.cc
index bd0d3bd..ec841c8 100644
--- a/frc971/control_loops/swerve/swerve_control_loops.cc
+++ b/frc971/control_loops/swerve/swerve_control_loops.cc
@@ -2,39 +2,114 @@
namespace frc971::control_loops::swerve {
-SwerveControlLoops::SwerveControlLoops(::aos::EventLoop *event_loop,
- const ::std::string &name)
+SwerveControlLoops::SwerveControlLoops(
+ ::aos::EventLoop *event_loop,
+ const frc971::control_loops::
+ StaticZeroingSingleDOFProfiledSubsystemCommonParams *rotation_params,
+ const SwerveZeroing *zeroing_params, const ::std::string &name)
: frc971::controls::ControlLoop<Goal, Position, StatusStatic, OutputStatic>(
- event_loop, name) {}
+ event_loop, name),
+ front_left_(rotation_params, zeroing_params->front_left()),
+ front_right_(rotation_params, zeroing_params->front_right()),
+ back_left_(rotation_params, zeroing_params->back_left()),
+ back_right_(rotation_params, zeroing_params->back_right()) {}
void SwerveControlLoops::RunIteration(
const Goal *goal, const Position *position,
aos::Sender<OutputStatic>::StaticBuilder *output_builder,
aos::Sender<StatusStatic>::StaticBuilder *status_builder) {
- (void)goal, (void)position;
+ if (WasReset()) {
+ front_left_.Reset();
+ front_right_.Reset();
+ back_left_.Reset();
+ back_right_.Reset();
+ }
+ aos::FlatbufferFixedAllocatorArray<
+ frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal, 512>
+ front_left_goal_buffer, front_right_goal_buffer, back_left_goal_buffer,
+ back_right_goal_buffer;
- if (output_builder != nullptr && goal != nullptr) {
+ front_left_goal_buffer.Finish(
+ frc971::control_loops::CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *front_left_goal_buffer.fbb(),
+ (goal != nullptr && goal->has_front_left_goal())
+ ? goal->front_left_goal()->rotation_angle()
+ : 0.0));
+ front_right_goal_buffer.Finish(
+ frc971::control_loops::CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *front_right_goal_buffer.fbb(),
+ (goal != nullptr && goal->has_front_right_goal())
+ ? goal->front_right_goal()->rotation_angle()
+ : 0.0));
+ back_left_goal_buffer.Finish(
+ frc971::control_loops::CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *back_left_goal_buffer.fbb(),
+ (goal != nullptr && goal->has_back_left_goal())
+ ? goal->back_left_goal()->rotation_angle()
+ : 0.0));
+ back_right_goal_buffer.Finish(
+ frc971::control_loops::CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *back_right_goal_buffer.fbb(),
+ (goal != nullptr && goal->has_back_right_goal())
+ ? goal->back_right_goal()->rotation_angle()
+ : 0.0));
+ const bool disabled = front_left_.Correct(
+ &front_left_goal_buffer.message(),
+ position->front_left()->rotation_position(), output_builder == nullptr);
+ front_right_.Correct(&front_right_goal_buffer.message(),
+ position->front_right()->rotation_position(),
+ output_builder == nullptr);
+ back_left_.Correct(&back_left_goal_buffer.message(),
+ position->back_left()->rotation_position(),
+ output_builder == nullptr);
+ back_right_.Correct(&back_right_goal_buffer.message(),
+ position->back_right()->rotation_position(),
+ output_builder == nullptr);
+
+ const double front_left_voltage = front_left_.UpdateController(disabled);
+ front_left_.UpdateObserver(front_left_voltage);
+ const double front_right_voltage = front_right_.UpdateController(disabled);
+ front_right_.UpdateObserver(front_right_voltage);
+ const double back_left_voltage = back_left_.UpdateController(disabled);
+ back_left_.UpdateObserver(back_left_voltage);
+ const double back_right_voltage = back_right_.UpdateController(disabled);
+ back_right_.UpdateObserver(back_right_voltage);
+ (void)goal, (void)position;
+ aos::FlatbufferFixedAllocatorArray<
+ frc971::control_loops::AbsoluteEncoderProfiledJointStatus, 512>
+ front_left_status_buffer, front_right_status_buffer,
+ back_left_status_buffer, back_right_status_buffer;
+ front_left_status_buffer.Finish(
+ front_left_.MakeStatus(front_left_status_buffer.fbb()));
+ front_right_status_buffer.Finish(
+ front_right_.MakeStatus(front_right_status_buffer.fbb()));
+ back_left_status_buffer.Finish(
+ back_left_.MakeStatus(back_left_status_buffer.fbb()));
+ back_right_status_buffer.Finish(
+ back_right_.MakeStatus(back_right_status_buffer.fbb()));
+
+ if (output_builder != nullptr) {
OutputStatic *output = output_builder->get();
auto front_left_output = output->add_front_left_output();
- front_left_output->set_rotation_current(0);
+ front_left_output->set_rotation_current(front_left_voltage);
front_left_output->set_translation_current(
- goal->front_left_goal()->translation_current());
+ goal ? goal->front_left_goal()->translation_current() : 0.0);
auto front_right_output = output->add_front_right_output();
- front_right_output->set_rotation_current(0);
+ front_right_output->set_rotation_current(front_right_voltage);
front_right_output->set_translation_current(
- goal->front_right_goal()->translation_current());
+ goal ? goal->front_right_goal()->translation_current() : 0.0);
auto back_left_output = output->add_back_left_output();
- back_left_output->set_rotation_current(0);
+ back_left_output->set_rotation_current(back_left_voltage);
back_left_output->set_translation_current(
- goal->back_left_goal()->translation_current());
+ goal ? goal->back_left_goal()->translation_current() : 0.0);
auto back_right_output = output->add_back_right_output();
- back_right_output->set_rotation_current(0);
+ back_right_output->set_rotation_current(back_right_voltage);
back_right_output->set_translation_current(
- goal->back_right_goal()->translation_current());
+ goal ? goal->back_right_goal()->translation_current() : 0.0);
// Ignore the return value of Send
output_builder->CheckOk(output_builder->Send());
@@ -44,16 +119,20 @@
StatusStatic *status = status_builder->get();
auto front_left_status = status->add_front_left_status();
- PopulateSwerveModuleRotation(front_left_status);
+ PopulateSwerveModuleRotation(front_left_status,
+ &front_left_status_buffer.message());
auto front_right_status = status->add_front_right_status();
- PopulateSwerveModuleRotation(front_right_status);
+ PopulateSwerveModuleRotation(front_right_status,
+ &front_right_status_buffer.message());
auto back_left_status = status->add_back_left_status();
- PopulateSwerveModuleRotation(back_left_status);
+ PopulateSwerveModuleRotation(back_left_status,
+ &back_left_status_buffer.message());
auto back_right_status = status->add_back_right_status();
- PopulateSwerveModuleRotation(back_right_status);
+ PopulateSwerveModuleRotation(back_right_status,
+ &back_right_status_buffer.message());
// Ignore the return value of Send
status_builder->CheckOk(status_builder->Send());
diff --git a/frc971/control_loops/swerve/swerve_control_loops.h b/frc971/control_loops/swerve/swerve_control_loops.h
index 78f6ba0..68016ab 100644
--- a/frc971/control_loops/swerve/swerve_control_loops.h
+++ b/frc971/control_loops/swerve/swerve_control_loops.h
@@ -4,19 +4,24 @@
#include "aos/time/time.h"
#include "frc971/control_loops/control_loop.h"
#include "frc971/control_loops/profiled_subsystem_generated.h"
+#include "frc971/control_loops/profiled_subsystem_static.h"
+#include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h"
#include "frc971/control_loops/swerve/swerve_drivetrain_can_position_generated.h"
#include "frc971/control_loops/swerve/swerve_drivetrain_goal_generated.h"
#include "frc971/control_loops/swerve/swerve_drivetrain_output_static.h"
#include "frc971/control_loops/swerve/swerve_drivetrain_position_generated.h"
#include "frc971/control_loops/swerve/swerve_drivetrain_status_static.h"
+#include "frc971/control_loops/swerve/swerve_zeroing_static.h"
+#include "frc971/zeroing/continuous_absolute_encoder.h"
namespace frc971::control_loops::swerve {
inline void PopulateSwerveModuleRotation(
- SwerveModuleStatusStatic *swerve_module_table) {
+ SwerveModuleStatusStatic *swerve_module_table,
+ const frc971::control_loops::AbsoluteEncoderProfiledJointStatus
+ *rotation_status) {
auto rotation = swerve_module_table->add_rotation();
- auto estimator_state = rotation->add_estimator_state();
- (void)estimator_state;
+ CHECK(rotation->FromFlatbuffer(rotation_status));
}
// Handles the translation and rotation current for each swerve module
@@ -24,14 +29,24 @@
: public ::frc971::controls::ControlLoop<Goal, Position, StatusStatic,
OutputStatic> {
public:
- explicit SwerveControlLoops(::aos::EventLoop *event_loop,
- const ::std::string &name = "/swerve");
+ using AbsoluteEncoderSubsystem =
+ ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystem<
+ ::frc971::zeroing::ContinuousAbsoluteEncoderZeroingEstimator,
+ ::frc971::control_loops::AbsoluteEncoderProfiledJointStatus>;
+
+ explicit SwerveControlLoops(
+ ::aos::EventLoop *event_loop,
+ const frc971::control_loops::
+ StaticZeroingSingleDOFProfiledSubsystemCommonParams *rotation_params,
+ const SwerveZeroing *zeroing_params,
+ const ::std::string &name = "/swerve");
protected:
void RunIteration(
const Goal *goal, const Position *position,
aos::Sender<OutputStatic>::StaticBuilder *output_builder,
aos::Sender<StatusStatic>::StaticBuilder *status_builder) override;
+ AbsoluteEncoderSubsystem front_left_, front_right_, back_left_, back_right_;
};
} // namespace frc971::control_loops::swerve
diff --git a/frc971/control_loops/swerve/swerve_control_test.cc b/frc971/control_loops/swerve/swerve_control_test.cc
index 9378f1c..051d1a7 100644
--- a/frc971/control_loops/swerve/swerve_control_test.cc
+++ b/frc971/control_loops/swerve/swerve_control_test.cc
@@ -4,15 +4,16 @@
#include <memory>
#include <vector>
+#include "absl/strings/str_format.h"
#include "gtest/gtest.h"
#include "aos/events/shm_event_loop.h"
#include "frc971/control_loops/control_loop_test.h"
#include "frc971/control_loops/swerve/swerve_control_loops.h"
-#include "frc971/control_loops/swerve/swerve_drivetrain_can_position_generated.h"
-#include "frc971/control_loops/swerve/swerve_drivetrain_goal_generated.h"
+#include "frc971/control_loops/swerve/swerve_drivetrain_can_position_static.h"
+#include "frc971/control_loops/swerve/swerve_drivetrain_goal_static.h"
#include "frc971/control_loops/swerve/swerve_drivetrain_output_generated.h"
-#include "frc971/control_loops/swerve/swerve_drivetrain_position_generated.h"
+#include "frc971/control_loops/swerve/swerve_drivetrain_position_static.h"
#include "frc971/control_loops/swerve/swerve_drivetrain_status_generated.h"
#include "frc971/control_loops/team_number_test_environment.h"
@@ -27,7 +28,7 @@
public:
SwerveControlSimulation(::aos::EventLoop *event_loop, chrono::nanoseconds dt)
: event_loop_(event_loop),
- position_sender_(event_loop_->MakeSender<Position>("/swerve")),
+ position_sender_(event_loop_->MakeSender<PositionStatic>("/swerve")),
can_position_sender_(event_loop_->MakeSender<CanPosition>("/swerve")),
goal_fetcher_(event_loop_->MakeFetcher<Goal>("/swerve")),
status_fetcher_(event_loop_->MakeFetcher<Status>("/swerve")),
@@ -45,12 +46,14 @@
// Sends a queue message with the position data.
void SendPositionMessage() {
- auto builder = position_sender_.MakeBuilder();
+ auto builder = position_sender_.MakeStaticBuilder();
- Position::Builder position_builder = builder.MakeBuilder<Position>();
+ builder->add_front_left()->add_rotation_position();
+ builder->add_front_right()->add_rotation_position();
+ builder->add_back_left()->add_rotation_position();
+ builder->add_back_right()->add_rotation_position();
- EXPECT_EQ(builder.Send(position_builder.Finish()),
- aos::RawSender::Error::kOk);
+ EXPECT_EQ(builder.Send(), aos::RawSender::Error::kOk);
}
void VerifyNearGoal() {
@@ -88,7 +91,7 @@
private:
::aos::EventLoop *event_loop_;
- ::aos::Sender<Position> position_sender_;
+ ::aos::Sender<PositionStatic> position_sender_;
::aos::Sender<CanPosition> can_position_sender_;
::aos::Sender<Goal> goal_sender_;
@@ -112,7 +115,57 @@
goal_sender_(swerve_test_event_loop_->MakeSender<Goal>("/swerve")),
swerve_control_event_loop_(MakeEventLoop("swerve_control")),
- swerve_control_loops_(swerve_control_event_loop_.get(), "/swerve"),
+ subsystem_params_(
+ aos::JsonToFlatbuffer<
+ frc971::control_loops::
+ StaticZeroingSingleDOFProfiledSubsystemCommonParams>(
+ absl::StrFormat(R"json({
+ "zeroing_voltage": 3.0,
+ "operating_voltage": 12.0,
+ "zeroing_profile_params": {
+ "max_velocity": 0.5,
+ "max_acceleration": 3.0
+ },
+ "default_profile_params":{
+ "max_velocity": 12.0,
+ "max_acceleration": 55.0
+ },
+ "range": {
+ "lower_hard": -inf,
+ "upper_hard": inf,
+ "lower": -inf,
+ "upper": inf
+ },
+ "loop": %s
+ })json",
+ aos::util::ReadFileToStringOrDie(
+ "frc971/control_loops/swerve/test_module/"
+ "integral_rotation_plant.json")))),
+ zeroing_params_(aos::JsonToFlatbuffer<SwerveZeroing>(R"json({
+ "front_left": {
+ "average_filter_size": 10,
+ "one_revolution_distance": 6,
+ "moving_buffer_size": 10
+ },
+ "front_right": {
+ "average_filter_size": 10,
+ "one_revolution_distance": 6,
+ "moving_buffer_size": 10
+ },
+ "back_left": {
+ "average_filter_size": 10,
+ "one_revolution_distance": 6,
+ "moving_buffer_size": 10
+ },
+ "back_right": {
+ "average_filter_size": 10,
+ "one_revolution_distance": 6,
+ "moving_buffer_size": 10
+ }
+ })json")),
+ swerve_control_loops_(swerve_control_event_loop_.get(),
+ &subsystem_params_.message(),
+ &zeroing_params_.message(), "/swerve"),
swerve_control_simulation_event_loop_(MakeEventLoop("simulation")),
swerve_control_simulation_(swerve_control_simulation_event_loop_.get(),
@@ -125,6 +178,11 @@
::aos::Sender<Goal> goal_sender_;
::std::unique_ptr<::aos::EventLoop> swerve_control_event_loop_;
+ aos::FlatbufferDetachedBuffer<
+ frc971::control_loops::
+ StaticZeroingSingleDOFProfiledSubsystemCommonParams>
+ subsystem_params_;
+ aos::FlatbufferDetachedBuffer<SwerveZeroing> zeroing_params_;
SwerveControlLoops swerve_control_loops_;
::std::unique_ptr<::aos::EventLoop> swerve_control_simulation_event_loop_;
@@ -158,4 +216,4 @@
swerve_control_simulation_.VerifyNearGoal();
}
-} // namespace frc971::control_loops::swerve::testing
\ No newline at end of file
+} // namespace frc971::control_loops::swerve::testing
diff --git a/frc971/control_loops/swerve/swerve_drivetrain_goal.fbs b/frc971/control_loops/swerve/swerve_drivetrain_goal.fbs
index eab0d0d..7cbb11c 100644
--- a/frc971/control_loops/swerve/swerve_drivetrain_goal.fbs
+++ b/frc971/control_loops/swerve/swerve_drivetrain_goal.fbs
@@ -1,3 +1,6 @@
+include "frc971/math/matrix.fbs";
+include "frc971/control_loops/swerve/swerve_drivetrain_joystick_goal.fbs";
+
namespace frc971.control_loops.swerve;
// States what translation control type goal we will care about
@@ -22,11 +25,20 @@
translation_speed:double (id: 3);
}
+attribute "static_length";
+
+table LinearVelocityGoal {
+ state:frc971.fbs.Matrix (id: 0);
+ input:frc971.fbs.Matrix (id: 1);
+}
+
table Goal {
front_left_goal:SwerveModuleGoal (id: 0);
front_right_goal:SwerveModuleGoal (id: 1);
back_left_goal:SwerveModuleGoal (id: 2);
back_right_goal:SwerveModuleGoal (id: 3);
+ linear_velocity_goal:LinearVelocityGoal (id: 4);
+ joystick_goal:JoystickGoal (id: 5);
}
root_type Goal;
diff --git a/frc971/control_loops/swerve/swerve_drivetrain_joystick_goal.fbs b/frc971/control_loops/swerve/swerve_drivetrain_joystick_goal.fbs
new file mode 100644
index 0000000..bf44cdd
--- /dev/null
+++ b/frc971/control_loops/swerve/swerve_drivetrain_joystick_goal.fbs
@@ -0,0 +1,9 @@
+namespace frc971.control_loops.swerve;
+
+table JoystickGoal {
+ vx:float (id: 0);
+ vy:float (id: 1);
+ omega:float (id: 2);
+}
+
+root_type JoystickGoal;
diff --git a/frc971/control_loops/swerve/swerve_notes.tex b/frc971/control_loops/swerve/swerve_notes.tex
index bf83dcc..380d6c8 100644
--- a/frc971/control_loops/swerve/swerve_notes.tex
+++ b/frc971/control_loops/swerve/swerve_notes.tex
@@ -376,7 +376,7 @@
\end{gather}
However, the angular velocity differential equation is more complicated as the torque added per module varies in sign
\begin{gather}
- \ddot{\theta} = \frac{\Sigma\left(\harpoon{r} \times \harpoon{F}_{mod}\right) + \tau_{d}}{J_{robot}}
+ \ddot{\theta} = \frac{\Sigma\left(R\left(\theta\right)\harpoon{r} \times \harpoon{F}_{mod}\right) + \tau_{d}}{J_{robot}}
\end{gather}
\subsection{Simplified longitudinal dynamics}
diff --git a/frc971/control_loops/swerve/test_module/BUILD b/frc971/control_loops/swerve/test_module/BUILD
new file mode 100644
index 0000000..972bddf
--- /dev/null
+++ b/frc971/control_loops/swerve/test_module/BUILD
@@ -0,0 +1,36 @@
+py_binary(
+ name = "rotation",
+ srcs = [
+ "rotation.py",
+ ],
+ target_compatible_with = ["@platforms//cpu:x86_64"],
+ deps = [
+ "//frc971/control_loops/python:angular_system_current",
+ "//frc971/control_loops/python:controls",
+ "@pip//glog",
+ "@pip//python_gflags",
+ ],
+)
+
+genrule(
+ name = "genrule_rotation",
+ outs = [
+ "rotation_plant.h",
+ "rotation_plant.cc",
+ "rotation_plant.json",
+ "integral_rotation_plant.h",
+ "integral_rotation_plant.cc",
+ "integral_rotation_plant.json",
+ ],
+ cmd = "$(location :rotation) $(OUTS)",
+ target_compatible_with = ["@platforms//os:linux"],
+ tools = [
+ ":rotation",
+ ],
+)
+
+filegroup(
+ name = "rotation_json",
+ srcs = ["integral_rotation_plant.json"],
+ visibility = ["//visibility:public"],
+)
diff --git a/frc971/control_loops/swerve/test_module/rotation.py b/frc971/control_loops/swerve/test_module/rotation.py
new file mode 100644
index 0000000..3f94e53
--- /dev/null
+++ b/frc971/control_loops/swerve/test_module/rotation.py
@@ -0,0 +1,57 @@
+#!/usr/bin/python3
+
+from aos.util.trapezoid_profile import TrapezoidProfile
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import angular_system_current
+from frc971.control_loops.python import controls
+import numpy
+import sys
+from matplotlib import pylab
+import gflags
+import glog
+import matplotlib
+
+FLAGS = gflags.FLAGS
+
+try:
+ gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+except gflags.DuplicateFlagError:
+ pass
+
+kRotation = angular_system_current.AngularSystemCurrentParams(
+ name='Rotation',
+ motor=control_loop.KrakenFOC(),
+ G=9.0 / 24.0 * 14.0 / 72.0,
+ J=3.1 / 1000.0,
+ q_pos=0.05,
+ q_vel=20.0,
+ kalman_q_pos=0.12,
+ kalman_q_vel=2.0,
+ kalman_q_voltage=4.0,
+ kalman_r_position=0.05,
+ radius=25 * 0.0254,
+ wrap_point=2.0 * numpy.pi)
+
+
+def main(argv):
+ if FLAGS.plot:
+ R = numpy.matrix([[numpy.pi / 2.0], [0.0]])
+ angular_system_current.PlotKick(kRotation, R)
+ angular_system_current.PlotMotion(kRotation, R)
+ return
+
+ # Write the generated constants out to a file.
+ if len(argv) != 7:
+ glog.fatal(
+ 'Expected .h file name and .cc file name for the wrist and integral wrist.'
+ )
+ else:
+ namespaces = ['frc971', 'control_loops', 'swerve', 'test_module']
+ angular_system_current.WriteAngularSystemCurrent(
+ kRotation, argv[1:4], argv[4:7], namespaces)
+
+
+if __name__ == '__main__':
+ argv = FLAGS(sys.argv)
+ glog.init()
+ sys.exit(main(argv))
diff --git a/frc971/control_loops/swerve/velocity_controller/BUILD b/frc971/control_loops/swerve/velocity_controller/BUILD
new file mode 100644
index 0000000..a0078b6
--- /dev/null
+++ b/frc971/control_loops/swerve/velocity_controller/BUILD
@@ -0,0 +1,107 @@
+package(default_visibility = ["//visibility:public"])
+
+py_library(
+ name = "experience_buffer",
+ srcs = [
+ "experience_buffer.py",
+ ],
+ deps = [
+ "@pip//flashbax",
+ "@pip//jax",
+ ],
+)
+
+py_test(
+ name = "experience_buffer_test",
+ srcs = [
+ "experience_buffer_test.py",
+ ],
+ deps = [
+ ":experience_buffer",
+ "@pip//flashbax",
+ "@pip//jax",
+ ],
+)
+
+py_binary(
+ name = "main",
+ srcs = [
+ "main.py",
+ "model.py",
+ "train.py",
+ ],
+ deps = [
+ ":experience_buffer",
+ ":physics",
+ "//frc971/control_loops/swerve:jax_dynamics",
+ "@pip//absl_py",
+ "@pip//aim",
+ "@pip//clu",
+ "@pip//flashbax",
+ "@pip//flax",
+ "@pip//jax",
+ "@pip//jaxtyping",
+ "@pip//matplotlib",
+ "@pip//numpy",
+ "@pip//tensorflow",
+ "@pip//tensorflow_probability",
+ "@pip//tf_keras",
+ ],
+)
+
+py_library(
+ name = "physics",
+ srcs = ["physics.py"],
+ deps = [
+ "//frc971/control_loops/swerve:jax_dynamics",
+ "@pip//flax",
+ "@pip//jax",
+ "@pip//jaxtyping",
+ ],
+)
+
+py_binary(
+ name = "plot",
+ srcs = [
+ "model.py",
+ "plot.py",
+ ],
+ deps = [
+ ":experience_buffer",
+ ":physics",
+ "//frc971/control_loops/swerve:jax_dynamics",
+ "@pip//absl_py",
+ "@pip//flashbax",
+ "@pip//flax",
+ "@pip//jax",
+ "@pip//jaxtyping",
+ "@pip//matplotlib",
+ "@pip//numpy",
+ "@pip//pygobject",
+ "@pip//tensorflow",
+ "@pip//tensorflow_probability",
+ "@pip//tf_keras",
+ ],
+)
+
+py_binary(
+ name = "lqr_plot",
+ srcs = [
+ "lqr_plot.py",
+ "model.py",
+ ],
+ deps = [
+ ":experience_buffer",
+ ":physics",
+ "//frc971/control_loops/swerve:jax_dynamics",
+ "@pip//absl_py",
+ "@pip//flashbax",
+ "@pip//flax",
+ "@pip//jax",
+ "@pip//jaxtyping",
+ "@pip//matplotlib",
+ "@pip//numpy",
+ "@pip//pygobject",
+ "@pip//tensorflow",
+ ],
+)
diff --git a/frc971/control_loops/swerve/velocity_controller/experience_buffer.py b/frc971/control_loops/swerve/velocity_controller/experience_buffer.py
new file mode 100644
index 0000000..1af3466
--- /dev/null
+++ b/frc971/control_loops/swerve/velocity_controller/experience_buffer.py
@@ -0,0 +1,85 @@
+import flashbax
+from flashbax.buffers.trajectory_buffer import TrajectoryBufferState, Experience, TrajectoryBufferSample
+import jax
+from jax.sharding import Mesh, PartitionSpec, NamedSharding
+from jax.experimental import mesh_utils
+from flax.typing import PRNGKey
+
+
+def make_experience_buffer(num_agents, sample_batch_size, length):
+ """Makes a random, sharded, fifo experience buffer."""
+ mesh = jax.sharding.Mesh(
+ devices=mesh_utils.create_device_mesh(len(jax.devices())),
+ axis_names=('batch', ),
+ )
+
+ # Shard all the data along the agents axis.
+ sharding = jax.sharding.NamedSharding(mesh, PartitionSpec('batch'))
+ replicated_sharding = jax.sharding.NamedSharding(mesh, PartitionSpec())
+
+ sample_batch_size = sample_batch_size // num_agents
+ trajectory_buffer = flashbax.make_trajectory_buffer(
+ max_length_time_axis=length // num_agents,
+ min_length_time_axis=1,
+ add_batch_size=num_agents,
+ sample_batch_size=sample_batch_size,
+ sample_sequence_length=1,
+ period=1,
+ )
+
+ def add_fn(state: TrajectoryBufferState,
+ batch: Experience) -> TrajectoryBufferState[Experience]:
+ # Squeeze the data to match the shape desired by flashbax.
+ batch_size, = flashbax.utils.get_tree_shape_prefix(batch, n_axes=1)
+ expanded_batch = jax.tree.map(
+ lambda x: x.reshape((batch_size, 1, *x.shape[1:])), batch)
+ return trajectory_buffer.add(state, expanded_batch)
+
+ def sample_fn(state: TrajectoryBufferState,
+ rng_key: PRNGKey) -> TrajectoryBufferSample[Experience]:
+ batch_size, = flashbax.utils.get_tree_shape_prefix(state.experience,
+ n_axes=1)
+
+ # Build up a RNG per actor so we can vmap the randomness.
+ sample_keys = jax.device_put(jax.random.split(rng_key, num=batch_size),
+ sharding)
+
+ # Now, randomly select the indices to sample for a single agent.
+ def single_item_indices(rng_key):
+ return jax.random.randint(
+ rng_key, (sample_batch_size, ), 0,
+ jax.lax.select(state.is_full, length // num_agents,
+ state.current_index))
+
+ # And do them all at once via vmap.
+ item_indices = jax.vmap(single_item_indices)(sample_keys)
+
+ # Actually sample them now, and vmap to do it for each agent.
+ vmap_sample_item_indices = jax.vmap(
+ lambda item_indices, x: x[item_indices])
+
+ # And apply it to the tree.
+ sampled_batch = jax.tree.map(
+ lambda x: vmap_sample_item_indices(item_indices, x),
+ state.experience)
+
+ return flashbax.buffers.trajectory_buffer.TrajectoryBufferSample(
+ experience=sampled_batch)
+
+ def init_fn(experience: Experience):
+ state = trajectory_buffer.init(experience)
+
+ # Push each element of the tree out across the devices to shard it.
+ sharded_experience = jax.tree_util.tree_map(
+ lambda x: jax.device_put(x, sharding), state.experience)
+
+ return flashbax.buffers.trajectory_buffer.TrajectoryBufferState(
+ experience=sharded_experience,
+ is_full=jax.device_put(state.is_full, replicated_sharding),
+ current_index=jax.device_put(state.current_index,
+ replicated_sharding),
+ )
+
+ return trajectory_buffer.replace(add=add_fn,
+ sample=sample_fn,
+ init=init_fn)
diff --git a/frc971/control_loops/swerve/velocity_controller/experience_buffer_test.py b/frc971/control_loops/swerve/velocity_controller/experience_buffer_test.py
new file mode 100644
index 0000000..016a56d
--- /dev/null
+++ b/frc971/control_loops/swerve/velocity_controller/experience_buffer_test.py
@@ -0,0 +1,126 @@
+import os
+
+os.environ['XLA_FLAGS'] = ' '.join([
+ # Teach it where to find CUDA
+ '--xla_gpu_cuda_data_dir=/usr/lib/cuda',
+ # Use up to 20 cores
+ '--xla_force_host_platform_device_count=2',
+ # Dump XLA to /tmp/foo to aid debugging
+ #'--xla_dump_to=/tmp/foo',
+ #'--xla_gpu_enable_command_buffer='
+])
+os.environ['JAX_PLATFORMS'] = 'cpu'
+#os.environ['XLA_PYTHON_CLIENT_PREALLOCATE'] = 'false'
+
+import experience_buffer
+import jax
+import numpy
+from jax.experimental import mesh_utils
+from jax.sharding import Mesh, PartitionSpec, NamedSharding
+import unittest
+
+
+class TestExperienceBuffer(unittest.TestCase):
+
+ def setUp(self):
+ self.mesh = jax.sharding.Mesh(
+ devices=mesh_utils.create_device_mesh(len(jax.devices())),
+ axis_names=('batch', ),
+ )
+
+ self.sharding = jax.sharding.NamedSharding(self.mesh,
+ PartitionSpec('batch'))
+ self.replicated_sharding = jax.sharding.NamedSharding(
+ self.mesh, PartitionSpec())
+
+ self.num_agents = 2
+ self.sample_batch_size = 10
+ self.length = 20
+
+ self.buffer = experience_buffer.make_experience_buffer(
+ self.num_agents, self.sample_batch_size, self.length)
+
+ def test_shape(self):
+ """Tests that the shapes coming out are right."""
+ buffer_state = self.buffer.init({
+ 'key': jax.numpy.zeros((2, )),
+ })
+
+ for i in range(self.sample_batch_size // self.num_agents):
+ buffer_state = self.buffer.add(
+ buffer_state, {
+ 'key':
+ jax.numpy.array(
+ [[i * 4, i * 4 + 1], [i * 4 + 2, i * 4 + 3]],
+ dtype=jax.numpy.float32)
+ })
+
+ rng = jax.random.key(0)
+
+ for i in range(2):
+ rng, sample_rng = jax.random.split(rng)
+ batch = self.buffer.sample(buffer_state, sample_rng)
+ self.assertEqual(batch.experience['key'].shape, (2, 5, 2))
+
+ def test_randomness(self):
+ """Tests that no sample is more or less likely."""
+ rng = jax.random.key(0)
+
+ # Adds an element to the buffer, and accumulates the sample.
+ def loop(i, val):
+ counts, buffer_state, rng = val
+
+ buffer_state = self.buffer.add(
+ buffer_state,
+ {'key': jax.numpy.array([[-i], [i]], dtype=jax.numpy.int32)})
+
+ rng, sample_rng = jax.random.split(rng)
+
+ def do_count(counts):
+ batch = self.buffer.sample(buffer_state, sample_rng)
+ for a in range(self.num_agents):
+ for s in range(5):
+ sampled_agent = jax.numpy.abs(batch.experience['key'][
+ a, s, 0]) % (self.length // self.num_agents)
+ prior = counts[a, sampled_agent]
+ counts = counts.at[a, sampled_agent].set(prior + 1)
+
+ return counts
+
+ # If we are full, start randomly picking and counting.
+ counts = jax.lax.cond(i >= self.length // self.num_agents,
+ do_count, lambda counts: counts, counts)
+
+ return counts, buffer_state, rng
+
+ @jax.jit
+ def doit(rng):
+ buffer_state = self.buffer.init({
+ 'key':
+ jax.numpy.zeros((1, ), dtype=jax.numpy.int32),
+ })
+
+ counts = numpy.zeros(
+ (self.num_agents, self.length // self.num_agents))
+
+ counts, buffer_state, rng = jax.lax.fori_loop(
+ 0,
+ 10000,
+ loop,
+ (jax.numpy.zeros(
+ (self.num_agents, self.length // self.num_agents)),
+ buffer_state, rng),
+ )
+ return counts
+
+ # Do this all in jax to make it fast. Many times speedup, including the JIT'ing.
+ counts = numpy.array(doit(rng), dtype=numpy.int32)
+ print(counts.min(), counts.max())
+
+ # Make sure things are decently balanced.
+ self.assertGreater(counts.min(), 4800)
+ self.assertLess(counts.max(), 5200)
+
+
+if __name__ == "__main__":
+ unittest.main()
diff --git a/frc971/control_loops/swerve/velocity_controller/lqr_plot.py b/frc971/control_loops/swerve/velocity_controller/lqr_plot.py
new file mode 100644
index 0000000..a63e100
--- /dev/null
+++ b/frc971/control_loops/swerve/velocity_controller/lqr_plot.py
@@ -0,0 +1,538 @@
+#!/usr/bin/env python3
+
+import os
+
+# Setup JAX to run on the CPU
+os.environ['XLA_FLAGS'] = ' '.join([
+ # Teach it where to find CUDA
+ '--xla_gpu_cuda_data_dir=/usr/lib/cuda',
+ # Use up to 20 cores
+ '--xla_force_host_platform_device_count=20',
+ # Dump XLA to /tmp/foo to aid debugging
+ '--xla_dump_to=/tmp/foo',
+ '--xla_gpu_enable_command_buffer='
+])
+
+os.environ['JAX_PLATFORMS'] = 'cpu'
+# Don't pre-allocate memory
+os.environ['XLA_PYTHON_CLIENT_PREALLOCATE'] = 'false'
+
+import absl
+from absl import logging
+from matplotlib.animation import FuncAnimation
+import matplotlib
+import numpy
+import scipy
+import time
+
+matplotlib.use("gtk3agg")
+
+from matplotlib import pylab
+from matplotlib import pyplot
+from flax.training import checkpoints
+from frc971.control_loops.python import controls
+import tensorflow as tf
+import threading
+import collections
+
+import jax
+
+jax._src.deprecations.accelerate('tracer-hash')
+jax.config.update("jax_compilation_cache_dir", "/tmp/jax_cache")
+jax.config.update("jax_persistent_cache_min_entry_size_bytes", -1)
+jax.config.update("jax_persistent_cache_min_compile_time_secs", 0)
+
+from frc971.control_loops.swerve.velocity_controller.model import *
+from frc971.control_loops.swerve.velocity_controller.physics import *
+
+# Container for the data.
+Data = collections.namedtuple('Data', [
+ 't',
+ 'X',
+ 'X_lqr',
+ 'U',
+ 'U_lqr',
+ 'cost',
+ 'cost_lqr',
+ 'q1_grid',
+ 'q2_grid',
+ 'q_grid',
+ 'target_q_grid',
+ 'lqr_grid',
+ 'pi_grid_U',
+ 'lqr_grid_U',
+ 'grid_X',
+ 'grid_Y',
+ 'reward',
+ 'reward_lqr',
+ 'step',
+ 'stdev',
+])
+
+FLAGS = absl.flags.FLAGS
+
+absl.flags.DEFINE_string('workdir', None, 'Directory to store model data.')
+
+absl.flags.DEFINE_integer(
+ 'horizon',
+ default=100,
+ help='Horizon to simulate',
+)
+
+absl.flags.DEFINE_float(
+ 'alpha',
+ default=0.2,
+ help='Entropy. If negative, automatically solve for it.',
+)
+
+numpy.set_printoptions(linewidth=200, )
+
+
+def restore_checkpoint(state: TrainState, workdir: str):
+ return checkpoints.restore_checkpoint(workdir, state)
+
+
+def generate_data(step=None):
+ grid_X = numpy.arange(-1, 1, 0.1)
+ grid_Y = numpy.arange(-10, 10, 0.1)
+ grid_X, grid_Y = numpy.meshgrid(grid_X, grid_Y)
+ grid_X = jax.numpy.array(grid_X)
+ grid_Y = jax.numpy.array(grid_Y)
+ # Load the training state.
+ problem = physics.TurretProblem()
+
+ rng = jax.random.key(0)
+ rng, init_rng = jax.random.split(rng)
+
+ state = create_train_state(
+ init_rng,
+ problem,
+ q_learning_rate=FLAGS.q_learning_rate,
+ pi_learning_rate=FLAGS.pi_learning_rate,
+ alpha_learning_rate=FLAGS.alpha_learning_rate,
+ )
+
+ state = restore_checkpoint(state, FLAGS.workdir)
+ if step is not None and state.step == step:
+ return None
+
+ X = jax.numpy.array([1.0, 0.0])
+ X_lqr = X.copy()
+ goal = jax.numpy.array([0.0, 0.0])
+
+ logging.info('X: %s', X)
+ logging.info('goal: %s', goal)
+ logging.debug('params: %s', state.params)
+
+ # Compute the various cost surfaces for plotting.
+ def compute_q1(X, Y):
+ return state.q1_apply(
+ state.params,
+ observation=state.problem.unwrap_angles(jax.numpy.array([X, Y])),
+ R=goal,
+ action=jax.numpy.array([0.]),
+ )[0]
+
+ def compute_q2(X, Y):
+ return state.q2_apply(
+ state.params,
+ observation=state.problem.unwrap_angles(jax.numpy.array([X, Y])),
+ R=goal,
+ action=jax.numpy.array([0.]),
+ )[0]
+
+ def lqr_cost(X, Y):
+ x = jax.numpy.array([X, Y]) - goal
+ return -x.T @ jax.numpy.array(problem.P) @ x
+
+ def compute_q(params, x, y):
+ X = state.problem.unwrap_angles(jax.numpy.array([x, y]))
+
+ return jax.numpy.minimum(
+ state.q1_apply(
+ params,
+ observation=X,
+ R=goal,
+ action=jax.numpy.array([0.]),
+ )[0],
+ state.q2_apply(
+ params,
+ observation=X,
+ R=goal,
+ action=jax.numpy.array([0.]),
+ )[0])
+
+ cost_grid1 = jax.vmap(jax.vmap(compute_q1))(grid_X, grid_Y)
+ cost_grid2 = jax.vmap(jax.vmap(compute_q2))(grid_X, grid_Y)
+ cost_grid = jax.vmap(jax.vmap(lambda x, y: compute_q(state.params, x, y)))(
+ grid_X, grid_Y)
+ target_cost_grid = jax.vmap(
+ jax.vmap(lambda x, y: compute_q(state.target_params, x, y)))(grid_X,
+ grid_Y)
+ lqr_cost_grid = jax.vmap(jax.vmap(lqr_cost))(grid_X, grid_Y)
+
+ # Now compute the two controller surfaces.
+ def compute_lqr_U(X, Y):
+ x = jax.numpy.array([X, Y])
+ return (-jax.numpy.array(problem.F.reshape((2, ))) @ x)[0]
+
+ def compute_pi_U(X, Y):
+ x = jax.numpy.array([X, Y])
+ U, _, _ = state.pi_apply(rng,
+ state.params,
+ observation=state.problem.unwrap_angles(x),
+ R=goal,
+ deterministic=True)
+ return U[0] * problem.action_limit
+
+ def compute_pi_stdev(X, Y):
+ x = jax.numpy.array([X, Y])
+ _, _, std = state.pi_apply(rng,
+ state.params,
+ observation=state.problem.unwrap_angles(x),
+ R=goal,
+ deterministic=True)
+ return std[0]
+
+ std_grid = jax.vmap(jax.vmap(compute_pi_stdev))(grid_X, grid_Y)
+
+ lqr_cost_U = jax.vmap(jax.vmap(compute_lqr_U))(grid_X, grid_Y)
+ pi_cost_U = jax.vmap(jax.vmap(compute_pi_U))(grid_X, grid_Y)
+
+ logging.info('Finished cost')
+
+ # Now simulate the robot, accumulating up things to plot.
+ def loop(i, val):
+ X, X_lqr, data, params = val
+ t = data.t.at[i].set(i * problem.dt)
+
+ normalized_U, _, _ = state.pi_apply(
+ rng,
+ params,
+ observation=state.problem.unwrap_angles(X),
+ R=goal,
+ deterministic=True)
+ U_lqr = problem.F @ (goal - X_lqr)
+
+ cost = jax.numpy.minimum(
+ state.q1_apply(params,
+ observation=state.problem.unwrap_angles(X),
+ R=goal,
+ action=normalized_U),
+ state.q2_apply(params,
+ observation=state.problem.unwrap_angles(X),
+ R=goal,
+ action=normalized_U))
+
+ U = normalized_U * problem.action_limit
+
+ U_plot = data.U.at[i, :].set(U)
+ U_lqr_plot = data.U_lqr.at[i, :].set(U_lqr)
+ X_plot = data.X.at[i, :].set(X)
+ X_lqr_plot = data.X_lqr.at[i, :].set(X_lqr)
+ cost_plot = data.cost.at[i, :].set(cost)
+ cost_lqr_plot = data.cost_lqr.at[i, :].set(lqr_cost(*X_lqr))
+
+ X = problem.A @ X + problem.B @ U
+ X_lqr = problem.A @ X_lqr + problem.B @ U_lqr
+
+ reward = data.reward + state.problem.reward(X, normalized_U, goal)
+ reward_lqr = data.reward_lqr + state.problem.reward(
+ X_lqr, U_lqr / problem.action_limit, goal)
+
+ return X, X_lqr, data._replace(
+ t=t,
+ U=U_plot,
+ U_lqr=U_lqr_plot,
+ X=X_plot,
+ X_lqr=X_lqr_plot,
+ cost=cost_plot,
+ cost_lqr=cost_lqr_plot,
+ reward=reward,
+ reward_lqr=reward_lqr,
+ ), params
+
+ # Do it.
+ @jax.jit
+ def integrate(data, X, X_lqr, params):
+ return jax.lax.fori_loop(0, FLAGS.horizon, loop,
+ (X, X_lqr, data, params))
+
+ X, X_lqr, data, params = integrate(
+ Data(
+ t=jax.numpy.zeros((FLAGS.horizon, )),
+ X=jax.numpy.zeros((FLAGS.horizon, state.problem.num_states)),
+ X_lqr=jax.numpy.zeros((FLAGS.horizon, state.problem.num_states)),
+ U=jax.numpy.zeros((FLAGS.horizon, state.problem.num_outputs)),
+ U_lqr=jax.numpy.zeros((FLAGS.horizon, state.problem.num_outputs)),
+ cost=jax.numpy.zeros((FLAGS.horizon, 1)),
+ cost_lqr=jax.numpy.zeros((FLAGS.horizon, 1)),
+ q1_grid=cost_grid1,
+ q2_grid=cost_grid2,
+ q_grid=cost_grid,
+ target_q_grid=target_cost_grid,
+ lqr_grid=lqr_cost_grid,
+ pi_grid_U=pi_cost_U,
+ lqr_grid_U=lqr_cost_U,
+ grid_X=grid_X,
+ grid_Y=grid_Y,
+ reward=0.0,
+ reward_lqr=0.0,
+ step=state.step,
+ stdev=std_grid,
+ ), X, X_lqr, state.params)
+
+ logging.info('Finished integrating, reward of %f, lqr reward of %f',
+ data.reward, data.reward_lqr)
+
+ # Convert back to numpy for plotting.
+ return Data(
+ t=numpy.array(data.t),
+ X=numpy.array(data.X),
+ X_lqr=numpy.array(data.X_lqr),
+ U=numpy.array(data.U),
+ U_lqr=numpy.array(data.U_lqr),
+ cost=numpy.array(data.cost),
+ cost_lqr=numpy.array(data.cost_lqr),
+ q1_grid=numpy.array(data.q1_grid),
+ q2_grid=numpy.array(data.q2_grid),
+ q_grid=numpy.array(data.q_grid),
+ target_q_grid=numpy.array(data.target_q_grid),
+ lqr_grid=numpy.array(data.lqr_grid),
+ pi_grid_U=numpy.array(data.pi_grid_U),
+ lqr_grid_U=numpy.array(data.lqr_grid_U),
+ grid_X=numpy.array(data.grid_X),
+ grid_Y=numpy.array(data.grid_Y),
+ stdev=numpy.array(data.stdev),
+ reward=float(data.reward),
+ reward_lqr=float(data.reward_lqr),
+ step=data.step,
+ )
+
+
+class Plotter(object):
+
+ def __init__(self, data):
+ # Make all the plots and axis.
+ self.fig0, self.axs0 = pylab.subplots(3)
+ self.fig0.supxlabel('Seconds')
+
+ self.axs_velocity = self.axs0[0].twinx()
+
+ self.x, = self.axs0[0].plot([], [], label="x")
+ self.x_lqr, = self.axs0[0].plot([], [], label="x_lqr")
+
+ self.axs0[0].set_ylabel('Position')
+ self.axs0[0].legend()
+ self.axs0[0].grid()
+
+ self.v, = self.axs_velocity.plot([], [], label="v", color='C2')
+ self.v_lqr, = self.axs_velocity.plot([], [], label="v_lqr", color='C3')
+ self.axs_velocity.set_ylabel('Velocity')
+ self.axs_velocity.legend()
+
+ self.uaxis, = self.axs0[1].plot([], [], label="U")
+ self.uaxis_lqr, = self.axs0[1].plot([], [], label="U_lqr")
+
+ self.axs0[1].set_ylabel('Amps')
+ self.axs0[1].legend()
+ self.axs0[1].grid()
+
+ self.costaxis, = self.axs0[2].plot([], [], label="cost")
+ self.costlqraxis, = self.axs0[2].plot([], [], label="cost lqr")
+ self.axs0[2].set_ylabel('Cost')
+ self.axs0[2].legend()
+ self.axs0[2].grid()
+
+ self.costfig = pyplot.figure(figsize=pyplot.figaspect(0.5))
+ self.cost3dax = [
+ self.costfig.add_subplot(2, 3, 1, projection='3d'),
+ self.costfig.add_subplot(2, 3, 2, projection='3d'),
+ self.costfig.add_subplot(2, 3, 3, projection='3d'),
+ self.costfig.add_subplot(2, 3, 4, projection='3d'),
+ self.costfig.add_subplot(2, 3, 5, projection='3d'),
+ self.costfig.add_subplot(2, 3, 6, projection='3d'),
+ ]
+
+ self.Ufig = pyplot.figure(figsize=pyplot.figaspect(0.5))
+ self.Uax = [
+ self.Ufig.add_subplot(2, 2, 1, projection='3d'),
+ self.Ufig.add_subplot(2, 2, 2, projection='3d'),
+ self.Ufig.add_subplot(2, 2, 3, projection='3d'),
+ self.Ufig.add_subplot(2, 2, 4, projection='3d'),
+ ]
+
+ self.last_trajectory_step = 0
+ self.last_cost_step = 0
+ self.last_U_step = 0
+
+ def update_trajectory_plot(self, data):
+ if data.step == self.last_trajectory_step:
+ return
+ self.last_trajectory_step = data.step
+ logging.info('Updating trajectory plots')
+ self.fig0.suptitle(f'Step {data.step}')
+
+ # Put data in the trajectory plots.
+ self.x.set_data(data.t, data.X[:, 0])
+ self.v.set_data(data.t, data.X[:, 1])
+ self.x_lqr.set_data(data.t, data.X_lqr[:, 0])
+ self.v_lqr.set_data(data.t, data.X_lqr[:, 1])
+
+ self.uaxis.set_data(data.t, data.U[:, 0])
+ self.uaxis_lqr.set_data(data.t, data.U_lqr[:, 0])
+ self.costaxis.set_data(data.t, data.cost[:, 0] - data.cost[-1, 0])
+ self.costlqraxis.set_data(data.t, data.cost_lqr[:, 0])
+
+ self.axs0[0].relim()
+ self.axs0[0].autoscale_view()
+
+ self.axs_velocity.relim()
+ self.axs_velocity.autoscale_view()
+
+ self.axs0[1].relim()
+ self.axs0[1].autoscale_view()
+
+ self.axs0[2].relim()
+ self.axs0[2].autoscale_view()
+
+ return self.x, self.v, self.uaxis, self.costaxis, self.costlqraxis
+
+ def update_cost_plot(self, data):
+ if data.step == self.last_cost_step:
+ return
+ logging.info('Updating cost plots')
+ self.last_cost_step = data.step
+ self.costfig.suptitle(f'Step {data.step}')
+ # Put data in the cost plots.
+ if hasattr(self, 'costsurf'):
+ for surf in self.costsurf:
+ surf.remove()
+
+ plots = [
+ (data.q1_grid, 'q1'),
+ (data.q2_grid, 'q2'),
+ (data.q_grid, 'q'),
+ (data.target_q_grid, 'target q'),
+ (data.lqr_grid, 'lqr'),
+ (data.q_grid - data.q_grid.max() - data.lqr_grid, 'error'),
+ ]
+
+ self.costsurf = [
+ self.cost3dax[i].plot_surface(
+ data.grid_X,
+ data.grid_Y,
+ Z,
+ cmap="magma",
+ label=label,
+ ) for i, (Z, label) in enumerate(plots)
+ ]
+
+ for axis in self.cost3dax:
+ axis.legend()
+ axis.relim()
+ axis.autoscale_view()
+
+ return self.costsurf
+
+ def update_U_plot(self, data):
+ if data.step == self.last_U_step:
+ return
+ self.last_U_step = data.step
+ logging.info('Updating U plots')
+ self.Ufig.suptitle(f'Step {data.step}')
+ # Put data in the controller plots.
+ if hasattr(self, 'Usurf'):
+ for surf in self.Usurf:
+ surf.remove()
+
+ plots = [
+ (data.lqr_grid_U, 'lqr'),
+ (data.pi_grid_U, 'pi'),
+ ((data.lqr_grid_U - data.pi_grid_U), 'error'),
+ (data.stdev, 'stdev'),
+ ]
+
+ self.Usurf = [
+ self.Uax[i].plot_surface(
+ data.grid_X,
+ data.grid_Y,
+ Z,
+ cmap="magma",
+ label=label,
+ ) for i, (Z, label) in enumerate(plots)
+ ]
+
+ for axis in self.Uax:
+ axis.legend()
+ axis.relim()
+ axis.autoscale_view()
+
+ return self.Usurf
+
+
+def main(argv):
+ if len(argv) > 1:
+ raise absl.app.UsageError('Too many command-line arguments.')
+
+ tf.config.experimental.set_visible_devices([], 'GPU')
+
+ lock = threading.Lock()
+
+ # Load data.
+ data = generate_data()
+
+ plotter = Plotter(data)
+
+ # Event for shutting down the thread.
+ shutdown = threading.Event()
+
+ # Thread to grab new data periodically.
+ def do_update():
+ while True:
+ nonlocal data
+
+ my_data = generate_data(data.step)
+
+ if my_data is not None:
+ with lock:
+ data = my_data
+
+ if shutdown.wait(timeout=3):
+ return
+
+ update_thread = threading.Thread(target=do_update)
+ update_thread.start()
+
+ # Now, update each of the plots every second with the new data.
+ def update0(frame):
+ with lock:
+ my_data = data
+
+ return plotter.update_trajectory_plot(my_data)
+
+ def update1(frame):
+ with lock:
+ my_data = data
+
+ return plotter.update_cost_plot(my_data)
+
+ def update2(frame):
+ with lock:
+ my_data = data
+
+ return plotter.update_U_plot(my_data)
+
+ animation0 = FuncAnimation(plotter.fig0, update0, interval=1000)
+ animation1 = FuncAnimation(plotter.costfig, update1, interval=1000)
+ animation2 = FuncAnimation(plotter.Ufig, update2, interval=1000)
+
+ pyplot.show()
+
+ shutdown.set()
+ update_thread.join()
+
+
+if __name__ == '__main__':
+ absl.flags.mark_flags_as_required(['workdir'])
+ absl.app.run(main)
diff --git a/frc971/control_loops/swerve/velocity_controller/main.py b/frc971/control_loops/swerve/velocity_controller/main.py
new file mode 100644
index 0000000..391b0fe
--- /dev/null
+++ b/frc971/control_loops/swerve/velocity_controller/main.py
@@ -0,0 +1,81 @@
+import os
+
+# Setup XLA first.
+os.environ['XLA_FLAGS'] = ' '.join([
+ # Teach it where to find CUDA
+ '--xla_gpu_cuda_data_dir=/usr/lib/cuda',
+ # Use up to 20 cores
+ #'--xla_force_host_platform_device_count=6',
+ # Dump XLA to /tmp/foo to aid debugging
+ #'--xla_dump_to=/tmp/foo',
+ #'--xla_gpu_enable_command_buffer='
+ # Dump sharding
+ #"--xla_dump_to=/tmp/foo",
+ #"--xla_dump_hlo_pass_re=spmd|propagation"
+])
+os.environ['JAX_PLATFORMS'] = 'cuda,cpu'
+os.environ['XLA_PYTHON_CLIENT_PREALLOCATE'] = 'true'
+os.environ['XLA_PYTHON_CLIENT_MEM_FRACTION'] = '.50'
+
+from absl import app
+from absl import flags
+from absl import logging
+from clu import platform
+import jax
+import tensorflow as tf
+from frc971.control_loops.swerve import jax_dynamics
+from frc971.control_loops.swerve.velocity_controller import physics
+
+jax._src.deprecations.accelerate('tracer-hash')
+# Enable the compilation cache
+jax.config.update("jax_compilation_cache_dir", "/tmp/jax_cache")
+jax.config.update("jax_persistent_cache_min_entry_size_bytes", -1)
+jax.config.update("jax_persistent_cache_min_compile_time_secs", 0)
+jax.config.update('jax_threefry_partitionable', True)
+
+import train
+
+FLAGS = flags.FLAGS
+
+flags.DEFINE_string('workdir', None, 'Directory to store model data.')
+
+flags.DEFINE_bool('swerve', True,
+ 'If true, train the swerve model, otherwise do the turret.')
+
+
+def main(argv):
+ if len(argv) > 1:
+ raise app.UsageError('Too many command-line arguments.')
+
+ # Hide any GPUs from TensorFlow. Otherwise it might reserve memory.
+ tf.config.experimental.set_visible_devices([], 'GPU')
+
+ logging.info('JAX process: %d / %d', jax.process_index(),
+ jax.process_count())
+ logging.info('JAX local devices: %r', jax.local_devices())
+
+ # Add a note so that we can tell which task is which JAX host.
+ # (Depending on the platform task 0 is not guaranteed to be host 0)
+ platform.work_unit().set_task_status(
+ f'process_index: {jax.process_index()}, '
+ f'process_count: {jax.process_count()}')
+ platform.work_unit().create_artifact(platform.ArtifactType.DIRECTORY,
+ FLAGS.workdir, 'workdir')
+
+ logging.info(
+ 'Visualize results with: bazel run -c opt @pip_deps_tensorboard//:rules_python_wheel_entry_point_tensorboard -- --logdir %s',
+ FLAGS.workdir,
+ )
+
+ if FLAGS.swerve:
+ physics_constants = jax_dynamics.Coefficients()
+ problem = physics.SwerveProblem(physics_constants)
+ else:
+ problem = physics.TurretProblem()
+
+ state = train.train(FLAGS.workdir, problem)
+
+
+if __name__ == '__main__':
+ flags.mark_flags_as_required(['workdir'])
+ app.run(main)
diff --git a/frc971/control_loops/swerve/velocity_controller/model.py b/frc971/control_loops/swerve/velocity_controller/model.py
new file mode 100644
index 0000000..7f01eef
--- /dev/null
+++ b/frc971/control_loops/swerve/velocity_controller/model.py
@@ -0,0 +1,595 @@
+from __future__ import annotations
+import flax
+import flashbax
+from typing import Any
+import dataclasses
+import absl
+from absl import logging
+import numpy
+import jax
+from flax import linen as nn
+from jaxtyping import Array, ArrayLike
+import optax
+from flax.training import train_state
+from jax.experimental import mesh_utils
+from jax.sharding import Mesh, PartitionSpec, NamedSharding
+from frc971.control_loops.swerve import jax_dynamics
+from frc971.control_loops.swerve.velocity_controller import physics
+from frc971.control_loops.swerve.velocity_controller import experience_buffer
+from tensorflow_probability.substrates import jax as tfp
+
+tfd = tfp.distributions
+tfb = tfp.bijectors
+
+from flax.typing import PRNGKey
+
+FLAGS = absl.flags.FLAGS
+
+absl.flags.DEFINE_integer(
+ 'num_agents',
+ default=10,
+ help='Training batch size.',
+)
+
+absl.flags.DEFINE_float(
+ 'alpha_learning_rate',
+ default=0.004,
+ help='Training learning rate for entropy.',
+)
+
+absl.flags.DEFINE_float(
+ 'q_learning_rate',
+ default=0.002,
+ help='Training learning rate.',
+)
+
+absl.flags.DEFINE_float(
+ 'final_q_learning_rate',
+ default=0.001,
+ help='Fraction of --q_learning_rate to reduce by by the end.',
+)
+
+absl.flags.DEFINE_float(
+ 'pi_learning_rate',
+ default=0.002,
+ help='Training learning rate.',
+)
+
+absl.flags.DEFINE_float(
+ 'final_pi_learning_rate',
+ default=0.001,
+ help='Fraction of --pi_learning_rate to reduce by by the end.',
+)
+
+absl.flags.DEFINE_float(
+ 'target_entropy_scalar',
+ default=1.0,
+ help=
+ 'Target entropy scalar for use when using automatic temperature adjustment.',
+)
+
+absl.flags.DEFINE_integer(
+ 'replay_size',
+ default=2000000,
+ help='Number of steps to save in our replay buffer',
+)
+
+absl.flags.DEFINE_integer(
+ 'batch_size',
+ default=10000,
+ help='Batch size for learning Q and pi',
+)
+
+absl.flags.DEFINE_boolean(
+ 'skip_layer',
+ default=False,
+ help='If true, add skip layer connections to the Q network.',
+)
+
+absl.flags.DEFINE_boolean(
+ 'rmsnorm',
+ default=False,
+ help='If true, use rmsnorm instead of layer norm.',
+)
+
+absl.flags.DEFINE_boolean(
+ 'dreamer_solver',
+ default=False,
+ help='If true, use the solver from dreamer v3 instead of adam.',
+)
+
+absl.flags.DEFINE_float(
+ 'initial_logalpha',
+ default=0.0,
+ help='The initial value to set logalpha to.',
+)
+
+HIDDEN_WEIGHTS = 256
+
+LOG_STD_MIN = -20
+LOG_STD_MAX = 2
+
+
+def gaussian_likelihood(noise: ArrayLike, log_std: ArrayLike):
+ pre_sum = -0.5 * (noise**2 + 2 * log_std + jax.numpy.log(2 * jax.numpy.pi))
+
+ if len(pre_sum.shape) > 1:
+ return jax.numpy.sum(pre_sum, keepdims=True, axis=1)
+ else:
+ return jax.numpy.sum(pre_sum, keepdims=True)
+
+
+class SquashedGaussianMLPActor(nn.Module):
+ """Actor model."""
+
+ # Number of dimensions in the action space
+ action_space: int = 8
+
+ hidden_sizes: list[int] = dataclasses.field(
+ default_factory=lambda: [HIDDEN_WEIGHTS, HIDDEN_WEIGHTS])
+
+ # Activation function
+ activation: Callable = nn.activation.relu
+
+ # Max action we can apply
+ action_limit: float = 1
+
+ @nn.compact
+ def __call__(self,
+ observation: ArrayLike,
+ R: ArrayLike,
+ deterministic: bool = False,
+ rng: PRNGKey | None = None):
+ x = jax.numpy.hstack((observation, R))
+ # Apply the dense layers
+ for i, hidden_size in enumerate(self.hidden_sizes):
+ x = nn.Dense(
+ name=f'denselayer{i}',
+ features=hidden_size,
+ )(x)
+ x = self.activation(x)
+
+ # Average policy is a dense function of the space.
+ mu = nn.Dense(
+ features=self.action_space,
+ name='mu',
+ )(x)
+
+ log_std_layer = nn.Dense(features=self.action_space,
+ name='log_std_layer')(x)
+
+ # Clip the log of the standard deviation in a soft manner.
+ log_std = LOG_STD_MIN + 0.5 * (LOG_STD_MAX - LOG_STD_MIN) * (
+ flax.linen.activation.tanh(log_std_layer) + 1)
+
+ std = jax.numpy.exp(log_std)
+
+ if rng is None:
+ rng = self.make_rng('pi')
+
+ pi_distribution = tfd.TransformedDistribution(
+ distribution=tfd.Normal(loc=mu, scale=std),
+ bijector=tfb.Tanh(),
+ )
+
+ if deterministic:
+ # We are testing the optimal policy, just use the mean.
+ pi_action = flax.linen.activation.tanh(mu)
+ else:
+ pi_action = pi_distribution.sample(shape=(1, ), seed=rng)
+
+ logp_pi = pi_distribution.log_prob(pi_action)
+
+ if len(logp_pi.shape) > 1:
+ logp_pi = jax.numpy.sum(logp_pi, keepdims=True, axis=1)
+ else:
+ logp_pi = jax.numpy.sum(logp_pi, keepdims=True)
+
+ return pi_action, logp_pi, self.action_limit * std
+
+
+class MLPQFunction(nn.Module):
+
+ # Number and size of the hidden layers.
+ hidden_sizes: list[int] = dataclasses.field(
+ default_factory=lambda: [HIDDEN_WEIGHTS, HIDDEN_WEIGHTS])
+
+ activation: Callable = nn.activation.tanh
+
+ @nn.compact
+ def __call__(self, observation: ArrayLike, R: ArrayLike,
+ action: ArrayLike):
+ # Estimate Q with a simple multi layer dense network.
+ x = jax.numpy.hstack((observation, R, action))
+ for i, hidden_size in enumerate(self.hidden_sizes):
+ # Add d2rl skip layer connections if requested.
+ # Idea from D2RL: https://arxiv.org/pdf/2010.09163.
+ if FLAGS.skip_layer and i != 0:
+ x = jax.numpy.hstack((x, observation, R, action))
+
+ x = nn.Dense(
+ name=f'denselayer{i}',
+ features=hidden_size,
+ )(x)
+
+ if FLAGS.rmsnorm:
+ # Idea from Dreamerv3: https://arxiv.org/pdf/2301.04104v2.
+ x = nn.RMSNorm(name=f'rmsnorm{i}')(x)
+ else:
+ # Layernorm also improves stability.
+ # Idea from RLPD: https://arxiv.org/pdf/2302.02948.
+ x = nn.LayerNorm(name=f'layernorm{i}')(x)
+ x = self.activation(x)
+
+ x = nn.Dense(
+ name=f'q',
+ features=1,
+ )(x)
+
+ return x
+
+
+class TrainState(flax.struct.PyTreeNode):
+ problem: Problem = flax.struct.field(pytree_node=False)
+
+ step: int | jax.Array = flax.struct.field(pytree_node=True)
+ substep: int | jax.Array = flax.struct.field(pytree_node=True)
+
+ params: flax.core.FrozenDict[str, typing.Any] = flax.struct.field(
+ pytree_node=True)
+
+ target_params: flax.core.FrozenDict[str, typing.Any] = flax.struct.field(
+ pytree_node=True)
+
+ pi_apply_fn: Callable = flax.struct.field(pytree_node=False)
+ q1_apply_fn: Callable = flax.struct.field(pytree_node=False)
+ q2_apply_fn: Callable = flax.struct.field(pytree_node=False)
+
+ pi_tx: optax.GradientTransformation = flax.struct.field(pytree_node=False)
+ pi_opt_state: optax.OptState = flax.struct.field(pytree_node=True)
+ q_tx: optax.GradientTransformation = flax.struct.field(pytree_node=False)
+ q_opt_state: optax.OptState = flax.struct.field(pytree_node=True)
+
+ alpha_tx: optax.GradientTransformation = flax.struct.field(
+ pytree_node=False)
+ alpha_opt_state: optax.OptState = flax.struct.field(pytree_node=True)
+
+ target_entropy: float = flax.struct.field(pytree_node=True)
+
+ mesh: Mesh = flax.struct.field(pytree_node=False)
+ sharding: NamedSharding = flax.struct.field(pytree_node=False)
+ replicated_sharding: NamedSharding = flax.struct.field(pytree_node=False)
+
+ replay_buffer: flashbax.buffers.trajectory_buffer.TrajectoryBuffer = flax.struct.field(
+ pytree_node=False)
+
+ def pi_apply(self,
+ rng: PRNGKey,
+ params: flax.core.FrozenDict[str, typing.Any],
+ observation: ArrayLike,
+ R: ArrayLike,
+ deterministic: bool = False):
+ return self.pi_apply_fn(
+ {'params': params['pi']},
+ observation=self.problem.unwrap_angles(observation),
+ R=R,
+ deterministic=deterministic,
+ rngs={'pi': rng})
+
+ def q1_apply(self, params: flax.core.FrozenDict[str, typing.Any],
+ observation: ArrayLike, R: ArrayLike, action: ArrayLike):
+ return self.q1_apply_fn(
+ {'params': params['q1']},
+ observation=self.problem.unwrap_angles(observation),
+ R=R,
+ action=action)
+
+ def q2_apply(self, params: flax.core.FrozenDict[str, typing.Any],
+ observation: ArrayLike, R: ArrayLike, action: ArrayLike):
+ return self.q2_apply_fn(
+ {'params': params['q2']},
+ observation=self.problem.unwrap_angles(observation),
+ R=R,
+ action=action)
+
+ def pi_apply_gradients(self, step: int, grads):
+ updates, new_pi_opt_state = self.pi_tx.update(grads, self.pi_opt_state,
+ self.params)
+ new_params = optax.apply_updates(self.params, updates)
+
+ return self.replace(
+ step=step,
+ substep=jax.lax.select(step != self.step, 0, self.substep + 1),
+ params=new_params,
+ pi_opt_state=new_pi_opt_state,
+ )
+
+ def q_apply_gradients(self, step: int, grads):
+ updates, new_q_opt_state = self.q_tx.update(grads, self.q_opt_state,
+ self.params)
+ new_params = optax.apply_updates(self.params, updates)
+
+ return self.replace(
+ step=step,
+ substep=jax.lax.select(step != self.step, 0, self.substep + 1),
+ params=new_params,
+ q_opt_state=new_q_opt_state,
+ )
+
+ def target_apply_gradients(self, step):
+ new_target_params = optax.incremental_update(self.params,
+ self.target_params,
+ 1 - FLAGS.polyak)
+
+ return self.replace(
+ step=step,
+ substep=jax.lax.select(step != self.step, 0, self.substep + 1),
+ target_params=new_target_params,
+ )
+
+ def alpha_apply_gradients(self, step, grads):
+ updates, new_alpha_opt_state = self.alpha_tx.update(
+ grads, self.alpha_opt_state, self.params)
+ new_params = optax.apply_updates(self.params, updates)
+
+ return self.replace(
+ step=step,
+ substep=jax.lax.select(step != self.step, 0, self.substep + 1),
+ params=new_params,
+ alpha_opt_state=new_alpha_opt_state,
+ )
+
+ def update_step(self, step):
+ return self.replace(
+ step=step,
+ substep=jax.lax.select(step != self.step, 0, self.substep + 1),
+ )
+
+ @classmethod
+ def create(cls, *, problem: Problem, params, pi_tx, q_tx, alpha_tx,
+ pi_apply_fn, q1_apply_fn, q2_apply_fn, **kwargs):
+ """Creates a new instance with ``step=0`` and initialized ``opt_state``."""
+
+ pi_tx = optax.multi_transform(
+ {
+ 'train': pi_tx,
+ 'freeze': optax.set_to_zero()
+ },
+ param_labels=flax.traverse_util.path_aware_map(
+ lambda path, x: 'train'
+ if path[0] == 'pi' else 'freeze', params),
+ )
+ pi_opt_state = pi_tx.init(params)
+
+ q_tx = optax.multi_transform(
+ {
+ 'train': q_tx,
+ 'freeze': optax.set_to_zero()
+ },
+ param_labels=flax.traverse_util.path_aware_map(
+ lambda path, x: 'train'
+ if path[0] == 'q1' or path[0] == 'q2' else 'freeze', params),
+ )
+ q_opt_state = q_tx.init(params)
+
+ alpha_tx = optax.multi_transform(
+ {
+ 'train': alpha_tx,
+ 'freeze': optax.set_to_zero()
+ },
+ param_labels=flax.traverse_util.path_aware_map(
+ lambda path, x: 'train'
+ if path[0] == 'logalpha' else 'freeze', params),
+ )
+ alpha_opt_state = alpha_tx.init(params)
+
+ mesh = Mesh(
+ devices=mesh_utils.create_device_mesh(len(jax.devices())),
+ axis_names=('batch', ),
+ )
+ print('Devices:', jax.devices())
+ sharding = NamedSharding(mesh, PartitionSpec('batch'))
+ replicated_sharding = NamedSharding(mesh, PartitionSpec())
+
+ replay_buffer = experience_buffer.make_experience_buffer(
+ num_agents=FLAGS.num_agents,
+ sample_batch_size=FLAGS.batch_size,
+ length=FLAGS.replay_size)
+
+ result = cls(
+ problem=problem,
+ step=0,
+ substep=0,
+ params=params,
+ target_params=params,
+ q1_apply_fn=q1_apply_fn,
+ q2_apply_fn=q2_apply_fn,
+ pi_apply_fn=pi_apply_fn,
+ pi_tx=pi_tx,
+ pi_opt_state=pi_opt_state,
+ q_tx=q_tx,
+ q_opt_state=q_opt_state,
+ alpha_tx=alpha_tx,
+ alpha_opt_state=alpha_opt_state,
+ target_entropy=-problem.num_outputs * FLAGS.target_entropy_scalar,
+ mesh=mesh,
+ sharding=sharding,
+ replicated_sharding=replicated_sharding,
+ replay_buffer=replay_buffer,
+ )
+
+ return jax.device_put(result, replicated_sharding)
+
+
+def create_train_state(rng: PRNGKey, problem: Problem, q_learning_rate,
+ pi_learning_rate, alpha_learning_rate):
+ """Creates initial `TrainState`."""
+ pi = SquashedGaussianMLPActor(activation=nn.activation.silu,
+ action_space=problem.num_outputs,
+ action_limit=problem.action_limit)
+ # We want q1 and q2 to have different network architectures so they pick up differnet things.
+ # SiLu is used in DreamerV3 so we use it: https://arxiv.org/pdf/2301.04104v2.
+ q1 = MLPQFunction(activation=nn.activation.silu, hidden_sizes=[128, 256])
+ q2 = MLPQFunction(activation=nn.activation.silu, hidden_sizes=[256, 128])
+
+ @jax.jit
+ def init_params(rng):
+ pi_rng, q1_rng, q2_rng = jax.random.split(rng, num=3)
+
+ pi_params = pi.init(
+ pi_rng,
+ observation=jax.numpy.ones([problem.num_unwrapped_states]),
+ R=jax.numpy.ones([problem.num_goals]),
+ )['params']
+ q1_params = q1.init(
+ q1_rng,
+ observation=jax.numpy.ones([problem.num_unwrapped_states]),
+ R=jax.numpy.ones([problem.num_goals]),
+ action=jax.numpy.ones([problem.num_outputs]),
+ )['params']
+ q2_params = q2.init(
+ q2_rng,
+ observation=jax.numpy.ones([problem.num_unwrapped_states]),
+ R=jax.numpy.ones([problem.num_goals]),
+ action=jax.numpy.ones([problem.num_outputs]),
+ )['params']
+
+ if FLAGS.alpha < 0.0:
+ logalpha = FLAGS.initial_logalpha
+ else:
+ logalpha = jax.numpy.log(FLAGS.alpha)
+
+ return {
+ 'q1': q1_params,
+ 'q2': q2_params,
+ 'pi': pi_params,
+ 'logalpha': logalpha,
+ }
+
+ if FLAGS.dreamer_solver:
+ pi_tx = create_dreamer_solver(learning_rate=pi_learning_rate)
+ q_tx = create_dreamer_solver(learning_rate=q_learning_rate)
+ alpha_tx = create_dreamer_solver(learning_rate=alpha_learning_rate)
+ else:
+ pi_tx = optax.adam(learning_rate=pi_learning_rate)
+ q_tx = optax.adam(learning_rate=q_learning_rate)
+ alpha_tx = optax.adam(learning_rate=alpha_learning_rate)
+
+ result = TrainState.create(
+ problem=problem,
+ params=init_params(rng),
+ pi_tx=pi_tx,
+ q_tx=q_tx,
+ alpha_tx=alpha_tx,
+ pi_apply_fn=pi.apply,
+ q1_apply_fn=q1.apply,
+ q2_apply_fn=q2.apply,
+ )
+
+ return result
+
+
+# Solver from dreamer v3: https://arxiv.org/pdf/2301.04104v2.
+# TODO(austin): How many of these pieces are actually in optax already?
+def scale_by_rms(beta=0.999, eps=1e-8):
+
+ def init_fn(params):
+ nu = jax.tree_util.tree_map(
+ lambda t: jax.numpy.zeros_like(t, jax.numpy.float32), params)
+ step = jax.numpy.zeros((), jax.numpy.int32)
+ return (step, nu)
+
+ def update_fn(updates, state, params=None):
+ step, nu = state
+ step = optax.safe_int32_increment(step)
+ nu = jax.tree_util.tree_map(
+ lambda v, u: beta * v + (1 - beta) * (u * u), nu, updates)
+ nu_hat = optax.bias_correction(nu, beta, step)
+ updates = jax.tree_util.tree_map(
+ lambda u, v: u / (jax.numpy.sqrt(v) + eps), updates, nu_hat)
+ return updates, (step, nu)
+
+ return optax.GradientTransformation(init_fn, update_fn)
+
+
+def scale_by_agc(clip=0.03, pmin=1e-3):
+
+ def init_fn(params):
+ return ()
+
+ def update_fn(updates, state, params=None):
+
+ def fn(param, update):
+ unorm = jax.numpy.linalg.norm(update.flatten(), 2)
+ pnorm = jax.numpy.linalg.norm(param.flatten(), 2)
+ upper = clip * jax.numpy.maximum(pmin, pnorm)
+ return update * (1 / jax.numpy.maximum(1.0, unorm / upper))
+
+ updates = jax.tree_util.tree_map(fn, params, updates)
+ return updates, ()
+
+ return optax.GradientTransformation(init_fn, update_fn)
+
+
+def scale_by_momentum(beta=0.9, nesterov=False):
+
+ def init_fn(params):
+ mu = jax.tree_util.tree_map(
+ lambda t: jax.numpy.zeros_like(t, jax.numpy.float32), params)
+ step = jax.numpy.zeros((), jax.numpy.int32)
+ return (step, mu)
+
+ def update_fn(updates, state, params=None):
+ step, mu = state
+ step = optax.safe_int32_increment(step)
+ mu = optax.update_moment(updates, mu, beta, 1)
+ if nesterov:
+ mu_nesterov = optax.update_moment(updates, mu, beta, 1)
+ mu_hat = optax.bias_correction(mu_nesterov, beta, step)
+ else:
+ mu_hat = optax.bias_correction(mu, beta, step)
+ return mu_hat, (step, mu)
+
+ return optax.GradientTransformation(init_fn, update_fn)
+
+
+def create_dreamer_solver(
+ learning_rate,
+ agc: float = 0.3,
+ pmin: float = 1e-3,
+ beta1: float = 0.9,
+ beta2: float = 0.999,
+ eps: float = 1e-20,
+ nesterov: bool = False,
+) -> optax.base.GradientTransformation:
+ # From dreamer v3.
+ return optax.chain(
+ # Adaptive gradient clipping.
+ scale_by_agc(agc, pmin),
+ scale_by_rms(beta2, eps),
+ scale_by_momentum(beta1, nesterov),
+ optax.scale_by_learning_rate(learning_rate),
+ )
+
+
+def create_learning_rate_fn(
+ base_learning_rate: float,
+ final_learning_rate: float,
+):
+ """Create learning rate schedule."""
+ warmup_fn = optax.linear_schedule(
+ init_value=base_learning_rate,
+ end_value=base_learning_rate,
+ transition_steps=FLAGS.warmup_steps,
+ )
+
+ cosine_epochs = max(FLAGS.steps - FLAGS.warmup_steps, 1)
+ cosine_fn = optax.cosine_decay_schedule(init_value=base_learning_rate,
+ decay_steps=cosine_epochs,
+ alpha=final_learning_rate)
+
+ schedule_fn = optax.join_schedules(
+ schedules=[warmup_fn, cosine_fn],
+ boundaries=[FLAGS.warmup_steps],
+ )
+ return schedule_fn
diff --git a/frc971/control_loops/swerve/velocity_controller/physics.py b/frc971/control_loops/swerve/velocity_controller/physics.py
new file mode 100644
index 0000000..accd0d6
--- /dev/null
+++ b/frc971/control_loops/swerve/velocity_controller/physics.py
@@ -0,0 +1,247 @@
+import jax, numpy
+from functools import partial
+from absl import logging
+from frc971.control_loops.swerve import jax_dynamics
+from frc971.control_loops.python import controls
+from flax.typing import PRNGKey
+
+
+class Problem(object):
+
+ def __init__(self, num_states: int, num_unwrapped_states: int,
+ num_outputs: int, num_goals: int, action_limit: float):
+ self.num_states = num_states
+ self.num_unwrapped_states = num_unwrapped_states
+ self.num_outputs = num_outputs
+ self.num_goals = num_goals
+ self.action_limit = action_limit
+ self.dt = 0.005
+
+ def integrate_dynamics(self, X: jax.typing.ArrayLike,
+ U: jax.typing.ArrayLike):
+ m = 2 # RK4 steps per interval
+ dt = self.dt / m
+
+ def iteration(i, X):
+ weights = jax.numpy.array([[0.0, 0.5, 0.5, 1.0],
+ [1.0, 2.0, 2.0, 1.0]])
+
+ def rk_iteration(i, val):
+ kx_previous, weighted_sum = val
+ kx = self.xdot(X + dt * weights[0, i] * kx_previous, U)
+ weighted_sum += dt * weights[1, i] * kx / 6.0
+ return (kx, weighted_sum)
+
+ return jax.lax.fori_loop(lower=0,
+ upper=4,
+ body_fun=rk_iteration,
+ init_val=(X, X))[1]
+
+ return jax.lax.fori_loop(lower=0,
+ upper=m,
+ body_fun=iteration,
+ init_val=X)
+
+ def unwrap_angles(self, X: jax.typing.ArrayLike):
+ return X
+
+ def xdot(self, X: jax.typing.ArrayLike, U: jax.typing.ArrayLike):
+ raise NotImplemented("xdot not implemented")
+
+ def cost(self, X: jax.typing.ArrayLike, U: jax.typing.ArrayLike,
+ goal: jax.typing.ArrayLike):
+ raise NotImplemented("cost not implemented")
+
+ def random_states(self, rng: PRNGKey, dimensions=None):
+ raise NotImplemented("random_states not implemented")
+
+ def random_actions(self,
+ rng: PRNGKey,
+ X: jax.typing.ArrayLike,
+ goal: jax.typing.ArrayLike,
+ dimensions=None):
+ """Produces a uniformly random action in the action space."""
+ return jax.random.uniform(
+ rng,
+ (dimensions or FLAGS.num_agents, self.num_outputs),
+ minval=-1.0,
+ maxval=1.0,
+ )
+
+ def random_goals(self, rng: PRNGKey, dimensions=None):
+ """Produces a random goal in the goal space."""
+ raise NotImplemented("random_states not implemented")
+
+
+class TurretProblem(Problem):
+
+ def __init__(self):
+ super().__init__(num_states=2,
+ num_unwrapped_states=2,
+ num_outputs=1,
+ num_goals=2,
+ action_limit=30.0)
+ self.A = numpy.matrix([[1., 0.00456639], [0., 0.83172142]])
+ self.B = numpy.matrix([[0.00065992], [0.25610763]])
+
+ self.Q = numpy.matrix([[2.77777778, 0.], [0., 0.01]])
+ self.R = numpy.matrix([[0.00694444]])
+
+ # Compute the optimal LQR cost + controller.
+ self.F, self.P = controls.dlqr(self.A,
+ self.B,
+ self.Q,
+ self.R,
+ optimal_cost_function=True)
+
+ def xdot(self, X: jax.typing.ArrayLike, U: jax.typing.ArrayLike):
+ A_continuous = jax.numpy.array([[0., 1.], [0., -36.85154548]])
+ B_continuous = jax.numpy.array([[0.], [56.08534375]])
+
+ U = U * self.action_limit
+ return A_continuous @ X + B_continuous @ U
+
+ def reward(self, X: jax.typing.ArrayLike, U: jax.typing.ArrayLike,
+ goal: jax.typing.ArrayLike):
+ return -(X - goal).T @ jax.numpy.array(
+ self.Q) @ (X - goal) - U.T @ jax.numpy.array(self.R) @ U
+
+ def random_states(self, rng: PRNGKey, dimensions=None):
+ rng1, rng2 = jax.random.split(rng)
+
+ return jax.numpy.hstack(
+ (jax.random.uniform(rng1, (dimensions or FLAGS.num_agents, 1),
+ minval=-1.0,
+ maxval=1.0),
+ jax.random.uniform(rng2, (dimensions or FLAGS.num_agents, 1),
+ minval=-10.0,
+ maxval=10.0)))
+
+ def random_goals(self, rng: PRNGKey, dimensions=None):
+ """Produces a random goal in the goal space."""
+ return jax.numpy.hstack((
+ jax.random.uniform(rng, (dimensions or FLAGS.num_agents, 1),
+ minval=-0.1,
+ maxval=0.1),
+ jax.numpy.zeros((dimensions or FLAGS.num_agents, 1)),
+ ))
+
+
+class SwerveProblem(Problem):
+
+ def __init__(self, coefficients: jax_dynamics.CoefficientsType):
+ super().__init__(num_states=jax_dynamics.NUM_VELOCITY_STATES,
+ num_unwrapped_states=17,
+ num_outputs=8,
+ num_goals=3,
+ action_limit=40.0)
+
+ self.coefficients = coefficients
+
+ def random_actions(self,
+ rng: PRNGKey,
+ X: jax.typing.ArrayLike,
+ goal: jax.typing.ArrayLike,
+ dimensions=None):
+ """Produces a uniformly random action in the action space."""
+ return jax.random.uniform(
+ rng,
+ (dimensions or FLAGS.num_agents, self.num_outputs),
+ minval=-1.0,
+ maxval=1.0,
+ )
+
+ def unwrap_angles(self, X: jax.typing.ArrayLike):
+ return jax.numpy.stack([
+ jax.numpy.cos(X[..., jax_dynamics.VELOCITY_STATE_THETAS0]),
+ jax.numpy.sin(X[..., jax_dynamics.VELOCITY_STATE_THETAS0]),
+ X[..., jax_dynamics.VELOCITY_STATE_OMEGAS0],
+ jax.numpy.cos(X[..., jax_dynamics.VELOCITY_STATE_THETAS1]),
+ jax.numpy.sin(X[..., jax_dynamics.VELOCITY_STATE_THETAS1]),
+ X[..., jax_dynamics.VELOCITY_STATE_OMEGAS1],
+ jax.numpy.cos(X[..., jax_dynamics.VELOCITY_STATE_THETAS2]),
+ jax.numpy.sin(X[..., jax_dynamics.VELOCITY_STATE_THETAS2]),
+ X[..., jax_dynamics.VELOCITY_STATE_OMEGAS2],
+ jax.numpy.cos(X[..., jax_dynamics.VELOCITY_STATE_THETAS3]),
+ jax.numpy.sin(X[..., jax_dynamics.VELOCITY_STATE_THETAS3]),
+ X[..., jax_dynamics.VELOCITY_STATE_OMEGAS3],
+ jax.numpy.cos(X[..., jax_dynamics.VELOCITY_STATE_THETA]),
+ jax.numpy.sin(X[..., jax_dynamics.VELOCITY_STATE_THETA]),
+ X[..., jax_dynamics.VELOCITY_STATE_VX],
+ X[..., jax_dynamics.VELOCITY_STATE_VY],
+ X[..., jax_dynamics.VELOCITY_STATE_OMEGA],
+ ],
+ axis=-1)
+
+ def xdot(self, X: jax.typing.ArrayLike, U: jax.typing.ArrayLike):
+ return jax_dynamics.velocity_dynamics(self.coefficients, X,
+ self.action_limit * U)
+
+ def reward(self, X: jax.typing.ArrayLike, U: jax.typing.ArrayLike,
+ goal: jax.typing.ArrayLike):
+ return -jax_dynamics.mpc_cost(coefficients=self.coefficients,
+ X=X,
+ U=self.action_limit * U,
+ goal=goal)
+
+ def random_states(self, rng: PRNGKey, dimensions=None):
+ rng, rng1, rng2, rng3, rng4, rng5, rng6, rng7, rng8, rng9, rng10, rng11 = jax.random.split(
+ rng, num=12)
+
+ return jax.numpy.hstack((
+ # VELOCITY_STATE_THETAS0 = 0
+ self._random_angle(rng1, dimensions),
+ # VELOCITY_STATE_OMEGAS0 = 1
+ self._random_module_velocity(rng2, dimensions),
+ # VELOCITY_STATE_THETAS1 = 2
+ self._random_angle(rng3, dimensions),
+ # VELOCITY_STATE_OMEGAS1 = 3
+ self._random_module_velocity(rng4, dimensions),
+ # VELOCITY_STATE_THETAS2 = 4
+ self._random_angle(rng5, dimensions),
+ # VELOCITY_STATE_OMEGAS2 = 5
+ self._random_module_velocity(rng6, dimensions),
+ # VELOCITY_STATE_THETAS3 = 6
+ self._random_angle(rng7, dimensions),
+ # VELOCITY_STATE_OMEGAS3 = 7
+ self._random_module_velocity(rng8, dimensions),
+ # VELOCITY_STATE_THETA = 8
+ self._random_angle(rng9, dimensions),
+ # VELOCITY_STATE_VX = 9
+ # VELOCITY_STATE_VY = 10
+ self._random_robot_velocity(rng10, dimensions),
+ # VELOCITY_STATE_OMEGA = 11
+ self._random_robot_angular_velocity(rng11, dimensions),
+ ))
+
+ def random_goals(self, rng: PRNGKey, dimensions=None):
+ """Produces a random goal in the goal space."""
+ return jax.numpy.hstack((
+ jax.random.uniform(rng, (dimensions or FLAGS.num_agents, 1),
+ minval=1.0,
+ maxval=1.0),
+ jax.numpy.zeros((dimensions or FLAGS.num_agents, 2)),
+ ))
+
+ MODULE_VELOCITY = 1.0
+ ROBOT_ANGULAR_VELOCITY = 0.5
+
+ def _random_angle(self, rng: PRNGKey, dimensions=None):
+ return jax.random.uniform(rng, (dimensions or FLAGS.num_agents, 1),
+ minval=-0.1 * jax.numpy.pi,
+ maxval=0.1 * jax.numpy.pi)
+
+ def _random_module_velocity(self, rng: PRNGKey, dimensions=None):
+ return jax.random.uniform(rng, (dimensions or FLAGS.num_agents, 1),
+ minval=-self.MODULE_VELOCITY,
+ maxval=self.MODULE_VELOCITY)
+
+ def _random_robot_velocity(self, rng: PRNGKey, dimensions=None):
+ return jax.random.uniform(rng, (dimensions or FLAGS.num_agents, 2),
+ minval=0.9,
+ maxval=1.1)
+
+ def _random_robot_angular_velocity(self, rng: PRNGKey, dimensions=None):
+ return jax.random.uniform(rng, (dimensions or FLAGS.num_agents, 1),
+ minval=-self.ROBOT_ANGULAR_VELOCITY,
+ maxval=self.ROBOT_ANGULAR_VELOCITY)
diff --git a/frc971/control_loops/swerve/velocity_controller/plot.py b/frc971/control_loops/swerve/velocity_controller/plot.py
new file mode 100644
index 0000000..502a3e2
--- /dev/null
+++ b/frc971/control_loops/swerve/velocity_controller/plot.py
@@ -0,0 +1,430 @@
+#!/usr/bin/env python3
+
+import os
+
+os.environ['XLA_FLAGS'] = ' '.join([
+ # Teach it where to find CUDA
+ '--xla_gpu_cuda_data_dir=/usr/lib/cuda',
+ # Use up to 20 cores
+ '--xla_force_host_platform_device_count=20',
+ # Dump XLA to /tmp/foo to aid debugging
+ #'--xla_dump_to=/tmp/foo',
+ #'--xla_gpu_enable_command_buffer='
+])
+
+os.environ['JAX_PLATFORMS'] = 'cpu'
+# Don't pre-allocate memory
+os.environ['XLA_PYTHON_CLIENT_PREALLOCATE'] = 'false'
+
+import absl
+from absl import logging
+from matplotlib.animation import FuncAnimation
+import matplotlib
+import numpy
+import scipy
+import time
+
+matplotlib.use("gtk3agg")
+
+from matplotlib import pylab
+from matplotlib import pyplot
+from flax.training import checkpoints
+import tensorflow as tf
+from jax.experimental.ode import odeint
+import threading
+import collections
+
+from frc971.control_loops.swerve.velocity_controller.model import *
+from frc971.control_loops.swerve.velocity_controller.physics import *
+
+# Container for the data.
+Data = collections.namedtuple('Data', [
+ 't', 'X', 'U', 'logp_pi', 'cost', 'q1_grid', 'q2_grid', 'q_grid',
+ 'target_q_grid', 'pi_grid_U', 'grid_X', 'grid_Y', 'reward', 'step',
+ 'rewards'
+])
+
+FLAGS = absl.flags.FLAGS
+
+absl.flags.DEFINE_string('workdir', None, 'Directory to store model data.')
+
+absl.flags.DEFINE_integer(
+ 'horizon',
+ default=100,
+ help='MPC horizon',
+)
+
+numpy.set_printoptions(linewidth=200, )
+
+absl.flags.DEFINE_float(
+ 'alpha',
+ default=0.2,
+ help='Entropy. If negative, automatically solve for it.',
+)
+
+
+def restore_checkpoint(state: TrainState, workdir: str):
+ return checkpoints.restore_checkpoint(workdir, state)
+
+
+dt = 0.005
+
+
+def X0Full():
+ module_theta = 0.0
+ module_omega = 0.0
+ theta = 0.0
+ vx = 1.0
+ dtheta = 0.05
+ vy = 0.0
+ drive_omega = jax.numpy.hypot(vx, vy) / jax_dynamics.WHEEL_RADIUS
+ omega = 0.0
+ return jax.numpy.array([
+ module_theta + dtheta,
+ 0.0,
+ module_omega,
+ drive_omega,
+ module_theta + dtheta,
+ 0.0,
+ module_omega,
+ drive_omega,
+ module_theta - dtheta,
+ 0.0,
+ module_omega,
+ drive_omega,
+ module_theta - dtheta,
+ 0.0,
+ module_omega,
+ drive_omega,
+ 0.0,
+ 0.0,
+ theta,
+ vx,
+ vy,
+ omega,
+ 0.0,
+ 0.0,
+ 0.0,
+ ])
+
+
+def generate_data(step=None):
+ grid_X = numpy.arange(-1, 1, 0.1)
+ grid_Y = numpy.arange(-10, 10, 0.1)
+ grid_X, grid_Y = numpy.meshgrid(grid_X, grid_Y)
+ grid_X = jax.numpy.array(grid_X)
+ grid_Y = jax.numpy.array(grid_Y)
+ # Load the training state.
+ physics_constants = jax_dynamics.Coefficients()
+ problem = physics.SwerveProblem(physics_constants)
+
+ rng = jax.random.key(0)
+ rng, init_rng = jax.random.split(rng)
+
+ state = create_train_state(init_rng,
+ problem,
+ FLAGS.q_learning_rate,
+ FLAGS.pi_learning_rate,
+ alpha_learning_rate=0.001)
+
+ state = restore_checkpoint(state, FLAGS.workdir)
+
+ X = X0Full()
+ X_lqr = X.copy()
+ goal = jax.numpy.array([1.0, 0.0, 0.0])
+
+ logging.info('X: %s', X)
+ logging.info('goal: %s', goal)
+ logging.debug('params: %s', state.params)
+
+ # Now simulate the robot, accumulating up things to plot.
+ def loop(i, val):
+ X, data, params = val
+ t = data.t.at[i].set(i * problem.dt)
+
+ U, logp_pi, std = state.pi_apply(
+ rng,
+ params,
+ observation=state.problem.unwrap_angles(
+ jax_dynamics.to_velocity_state(X)),
+ R=goal,
+ deterministic=True)
+
+ logp_pi = logp_pi * jax.numpy.exp(params['logalpha'])
+
+ jax.debug.print('mu: {mu} std: {std}', mu=U, std=std)
+
+ step_reward = state.problem.q_reward(jax_dynamics.to_velocity_state(X),
+ U, goal)
+ reward = data.reward + step_reward
+
+ cost = jax.numpy.minimum(
+ state.q1_apply(params,
+ observation=state.problem.unwrap_angles(
+ jax_dynamics.to_velocity_state(X)),
+ R=goal,
+ action=U),
+ state.q2_apply(params,
+ observation=state.problem.unwrap_angles(
+ jax_dynamics.to_velocity_state(X)),
+ R=goal,
+ action=U))
+
+ U = U * problem.action_limit
+ U_plot = data.U.at[i, :].set(U)
+ rewards = data.rewards.at[i, :].set(step_reward)
+ X_plot = data.X.at[i, :].set(X)
+ cost_plot = data.cost.at[i, :].set(cost)
+ logp_pi_plot = data.logp_pi.at[i, :].set(logp_pi)
+
+ # TODO(austin): I'd really like to visualize the slip angle per wheel.
+ # Maybe also the force deviation, etc.
+ # I think that would help enormously in figuring out how good a specific solution is.
+
+ def fn(X, t):
+ return jax_dynamics.full_dynamics(problem.coefficients, X,
+ U).flatten()
+
+ X = odeint(fn, X, jax.numpy.array([0, problem.dt]))
+
+ return X[1, :], data._replace(
+ t=t,
+ U=U_plot,
+ X=X_plot,
+ logp_pi=logp_pi_plot,
+ cost=cost_plot,
+ reward=reward,
+ rewards=rewards,
+ ), params
+
+ # Do it.
+ @jax.jit
+ def integrate(data, X, params):
+ return jax.lax.fori_loop(0, FLAGS.horizon, loop, (X, data, params))
+
+ X, data, params = integrate(
+ Data(
+ t=jax.numpy.zeros((FLAGS.horizon, )),
+ X=jax.numpy.zeros((FLAGS.horizon, jax_dynamics.NUM_STATES)),
+ U=jax.numpy.zeros((FLAGS.horizon, state.problem.num_outputs)),
+ logp_pi=jax.numpy.zeros((FLAGS.horizon, 1)),
+ rewards=jax.numpy.zeros((FLAGS.horizon, 1)),
+ cost=jax.numpy.zeros((FLAGS.horizon, 1)),
+ q1_grid=jax.numpy.zeros(grid_X.shape),
+ q2_grid=jax.numpy.zeros(grid_X.shape),
+ q_grid=jax.numpy.zeros(grid_X.shape),
+ target_q_grid=jax.numpy.zeros(grid_X.shape),
+ pi_grid_U=jax.numpy.zeros(grid_X.shape),
+ grid_X=grid_X,
+ grid_Y=grid_Y,
+ reward=0.0,
+ step=state.step,
+ ), X, state.params)
+
+ logging.info('Reward: %s', float(data.reward))
+
+ # Convert back to numpy for plotting.
+ return Data(
+ t=numpy.array(data.t),
+ X=numpy.array(data.X),
+ U=numpy.array(data.U),
+ logp_pi=numpy.array(data.logp_pi),
+ cost=numpy.array(data.cost),
+ q1_grid=numpy.array(data.q1_grid),
+ q2_grid=numpy.array(data.q2_grid),
+ q_grid=numpy.array(data.q_grid),
+ target_q_grid=numpy.array(data.target_q_grid),
+ pi_grid_U=numpy.array(data.pi_grid_U),
+ grid_X=numpy.array(data.grid_X),
+ grid_Y=numpy.array(data.grid_Y),
+ rewards=numpy.array(data.rewards),
+ reward=float(data.reward),
+ step=data.step,
+ )
+
+
+class Plotter(object):
+
+ def __init__(self, data):
+ # Make all the plots and axis.
+ self.fig0, self.axs0 = pylab.subplots(3)
+ self.fig0.supxlabel('Seconds')
+
+ self.vx, = self.axs0[0].plot([], [], label="vx")
+ self.vy, = self.axs0[0].plot([], [], label="vy")
+ self.omega, = self.axs0[0].plot([], [], label="omega")
+ self.axs0[0].set_ylabel('Velocity')
+ self.axs0[0].legend()
+ self.axs0[0].grid()
+
+ self.steer0, = self.axs0[1].plot([], [], label="Steer0")
+ self.steer1, = self.axs0[1].plot([], [], label="Steer1")
+ self.steer2, = self.axs0[1].plot([], [], label="Steer2")
+ self.steer3, = self.axs0[1].plot([], [], label="Steer3")
+ self.axs0[1].set_ylabel('Amps')
+ self.axs0[1].legend()
+ self.axs0[1].grid()
+
+ self.drive0, = self.axs0[2].plot([], [], label="Drive0")
+ self.drive1, = self.axs0[2].plot([], [], label="Drive1")
+ self.drive2, = self.axs0[2].plot([], [], label="Drive2")
+ self.drive3, = self.axs0[2].plot([], [], label="Drive3")
+ self.axs0[2].set_ylabel('Amps')
+ self.axs0[2].legend()
+ self.axs0[2].grid()
+
+ self.fig1, self.axs1 = pylab.subplots(3)
+ self.fig1.supxlabel('Seconds')
+
+ self.theta0, = self.axs1[0].plot([], [], label='steer position0')
+ self.theta1, = self.axs1[0].plot([], [], label='steer position1')
+ self.theta2, = self.axs1[0].plot([], [], label='steer position2')
+ self.theta3, = self.axs1[0].plot([], [], label='steer position3')
+ self.axs1[0].set_ylabel('Radians')
+ self.axs1[0].legend()
+ self.omega0, = self.axs1[1].plot([], [], label='steer velocity0')
+ self.omega1, = self.axs1[1].plot([], [], label='steer velocity1')
+ self.omega2, = self.axs1[1].plot([], [], label='steer velocity2')
+ self.omega3, = self.axs1[1].plot([], [], label='steer velocity3')
+ self.axs1[1].set_ylabel('Radians/second')
+ self.axs1[1].legend()
+
+ self.logp_axis = self.axs1[2].twinx()
+ self.cost, = self.axs1[2].plot([], [], label='cost')
+ self.reward, = self.axs1[2].plot([], [], label='reward')
+ self.axs1[2].set_ylabel('Radians/second')
+ self.axs1[2].legend()
+
+ self.logp_pi, = self.logp_axis.plot([], [],
+ label='logp_pi',
+ color='C2')
+ self.logp_axis.set_ylabel('log(liklihood)*alpha')
+ self.logp_axis.legend()
+
+ self.last_robot_step = 0
+ self.last_steer_step = 0
+
+ def update_robot_plot(self, data):
+ if data.step is not None and data.step == self.last_robot_step:
+ return
+ self.last_robot_step = data.step
+ logging.info('Updating robot plots')
+ self.fig0.suptitle(f'Step {data.step}')
+
+ self.vx.set_data(data.t, data.X[:, jax_dynamics.STATE_VX])
+ self.vy.set_data(data.t, data.X[:, jax_dynamics.STATE_VY])
+ self.omega.set_data(data.t, data.X[:, jax_dynamics.STATE_OMEGA])
+
+ self.axs0[0].relim()
+ self.axs0[0].autoscale_view()
+
+ self.steer0.set_data(data.t, data.U[:, 0])
+ self.steer1.set_data(data.t, data.U[:, 2])
+ self.steer2.set_data(data.t, data.U[:, 4])
+ self.steer3.set_data(data.t, data.U[:, 6])
+ self.axs0[1].relim()
+ self.axs0[1].autoscale_view()
+
+ self.drive0.set_data(data.t, data.U[:, 1])
+ self.drive1.set_data(data.t, data.U[:, 3])
+ self.drive2.set_data(data.t, data.U[:, 5])
+ self.drive3.set_data(data.t, data.U[:, 7])
+ self.axs0[2].relim()
+ self.axs0[2].autoscale_view()
+
+ return (self.vx, self.vy, self.omega, self.steer0, self.steer1,
+ self.steer2, self.steer3, self.drive0, self.drive1,
+ self.drive2, self.drive3)
+
+ def update_steer_plot(self, data):
+ if data.step == self.last_steer_step:
+ return
+ self.last_steer_step = data.step
+ logging.info('Updating steer plots')
+ self.fig1.suptitle(f'Step {data.step}')
+
+ self.theta0.set_data(data.t, data.X[:, jax_dynamics.STATE_THETAS0])
+ self.theta1.set_data(data.t, data.X[:, jax_dynamics.STATE_THETAS1])
+ self.theta2.set_data(data.t, data.X[:, jax_dynamics.STATE_THETAS2])
+ self.theta3.set_data(data.t, data.X[:, jax_dynamics.STATE_THETAS3])
+ self.axs1[0].relim()
+ self.axs1[0].autoscale_view()
+
+ self.omega0.set_data(data.t, data.X[:, jax_dynamics.STATE_OMEGAS0])
+ self.omega1.set_data(data.t, data.X[:, jax_dynamics.STATE_OMEGAS1])
+ self.omega2.set_data(data.t, data.X[:, jax_dynamics.STATE_OMEGAS2])
+ self.omega3.set_data(data.t, data.X[:, jax_dynamics.STATE_OMEGAS3])
+ self.axs1[1].relim()
+ self.axs1[1].autoscale_view()
+
+ self.cost.set_data(data.t, data.cost)
+ self.reward.set_data(data.t, data.rewards)
+ self.logp_pi.set_data(data.t, data.logp_pi)
+ self.axs1[2].relim()
+ self.axs1[2].autoscale_view()
+ self.logp_axis.relim()
+ self.logp_axis.autoscale_view()
+
+ return (self.theta0, self.theta1, self.theta2, self.theta3,
+ self.omega0, self.omega1, self.omega2, self.omega3, self.cost,
+ self.logp_pi, self.reward)
+
+
+def main(argv):
+ if len(argv) > 1:
+ raise absl.app.UsageError('Too many command-line arguments.')
+
+ tf.config.experimental.set_visible_devices([], 'GPU')
+
+ lock = threading.Lock()
+
+ # Load data.
+ data = generate_data()
+
+ plotter = Plotter(data)
+
+ # Event for shutting down the thread.
+ shutdown = threading.Event()
+
+ # Thread to grab new data periodically.
+ def do_update():
+ while True:
+ nonlocal data
+
+ my_data = generate_data(data.step)
+
+ if my_data is not None:
+ with lock:
+ data = my_data
+
+ if shutdown.wait(timeout=3):
+ return
+
+ update_thread = threading.Thread(target=do_update)
+ update_thread.start()
+
+ # Now, update each of the plots every second with the new data.
+ def update0(frame):
+ with lock:
+ my_data = data
+
+ return plotter.update_robot_plot(my_data)
+
+ def update1(frame):
+ with lock:
+ my_data = data
+
+ return plotter.update_steer_plot(my_data)
+
+ animation0 = FuncAnimation(plotter.fig0, update0, interval=1000)
+ animation1 = FuncAnimation(plotter.fig1, update1, interval=1000)
+
+ pyplot.show()
+
+ shutdown.set()
+ update_thread.join()
+
+
+if __name__ == '__main__':
+ absl.flags.mark_flags_as_required(['workdir'])
+ absl.app.run(main)
diff --git a/frc971/control_loops/swerve/velocity_controller/train.py b/frc971/control_loops/swerve/velocity_controller/train.py
new file mode 100644
index 0000000..34d904a
--- /dev/null
+++ b/frc971/control_loops/swerve/velocity_controller/train.py
@@ -0,0 +1,517 @@
+# Machine learning based on Soft Actor Critic(SAC) which was initially proposed in https://arxiv.org/pdf/1801.01290.
+# Our implementation was heavily based on OpenAI's spinning up reference implementation https://spinningup.openai.com/en/latest/algorithms/sac.html.
+
+import absl
+import time
+import collections
+from absl import logging
+import flax
+import matplotlib
+from matplotlib import pyplot
+from flax import linen as nn
+from flax.training import train_state
+from flax.training import checkpoints
+import jax
+import inspect
+import aim
+import jax.numpy as jnp
+import ml_collections
+import numpy as np
+import optax
+import numpy
+from frc971.control_loops.swerve import jax_dynamics
+from functools import partial
+import flashbax
+from jax.experimental.ode import odeint
+import orbax.checkpoint
+from frc971.control_loops.swerve.velocity_controller.model import *
+from frc971.control_loops.swerve.velocity_controller.physics import *
+
+numpy.set_printoptions(linewidth=200, )
+
+FLAGS = absl.flags.FLAGS
+
+absl.flags.DEFINE_integer(
+ 'horizon',
+ default=25,
+ help='MPC horizon',
+)
+
+absl.flags.DEFINE_integer(
+ 'random_sample_steps',
+ default=10000,
+ help='Number of steps to randomly sample before using the policy',
+)
+
+absl.flags.DEFINE_integer(
+ 'steps',
+ default=400000,
+ help='Number of steps to run and train the agent',
+)
+
+absl.flags.DEFINE_integer(
+ 'warmup_steps',
+ default=300000,
+ help='Number of steps to warm up training',
+)
+
+absl.flags.DEFINE_float(
+ 'gamma',
+ default=0.999,
+ help='Future discount.',
+)
+
+absl.flags.DEFINE_float(
+ 'alpha',
+ default=0.2,
+ help='Entropy. If negative, automatically solve for it.',
+)
+
+absl.flags.DEFINE_float(
+ 'polyak',
+ default=0.995,
+ help='Time constant in polyak averaging for the target network.',
+)
+
+absl.flags.DEFINE_bool(
+ 'debug_nan',
+ default=False,
+ help='If true, explode on any NaNs found, and print them.',
+)
+
+absl.flags.DEFINE_bool(
+ 'maximum_entropy_q',
+ default=True,
+ help=
+ 'If false, do not add the maximum entropy term to the bellman backup for Q.',
+)
+
+
+def save_checkpoint(state: TrainState, workdir: str):
+ """Saves a checkpoint in the workdir."""
+ # TODO(austin): use orbax directly.
+ step = int(state.step)
+ logging.info('Saving checkpoint step %d.', step)
+ checkpoints.save_checkpoint_multiprocess(workdir, state, step, keep=10)
+
+
+def restore_checkpoint(state: TrainState, workdir: str):
+ """Restores the latest checkpoint from the workdir."""
+ return checkpoints.restore_checkpoint(workdir, state)
+
+
+def has_nan(x):
+ if isinstance(x, jnp.ndarray):
+ return jnp.any(jnp.isnan(x))
+ else:
+ return jnp.any(
+ jax.numpy.array([has_nan(v)
+ for v in jax.tree_util.tree_leaves(x)]))
+
+
+def print_nan(step, x):
+ if not FLAGS.debug_nan:
+ return
+
+ caller = inspect.getframeinfo(inspect.stack()[1][0])
+ # TODO(austin): It is helpful to sometimes start printing at a certain step.
+ jax.lax.cond(
+ has_nan(x), lambda: jax.debug.print(caller.filename +
+ ':{l} step {s} isnan(X) -> {x}',
+ l=caller.lineno,
+ s=step,
+ x=x), lambda: None)
+
+
+@jax.jit
+def compute_loss_q(state: TrainState, rng: PRNGKey, params, data: ArrayLike):
+ """Computes the Soft Actor-Critic loss for Q1 and Q2."""
+ observations1 = data['observations1']
+ actions = data['actions']
+ rewards = data['rewards']
+ observations2 = data['observations2']
+ R = data['goals']
+
+ # Compute the ending actions from the current network.
+ action2, logp_pi2, _ = state.pi_apply(rng=rng,
+ params=params,
+ observation=observations2,
+ R=R)
+
+ # Compute target network Q values
+ q1_pi_target = state.q1_apply(state.target_params,
+ observation=observations2,
+ R=R,
+ action=action2)
+ q2_pi_target = state.q2_apply(state.target_params,
+ observation=observations2,
+ R=R,
+ action=action2)
+ q_pi_target = jax.numpy.minimum(q1_pi_target, q2_pi_target)
+
+ alpha = jax.numpy.exp(params['logalpha'])
+
+ # Now we can compute the Bellman backup
+ # Max entropy SAC is based on https://arxiv.org/pdf/1812.05905.
+ if FLAGS.maximum_entropy_q:
+ bellman_backup = jax.lax.stop_gradient(
+ rewards + FLAGS.gamma * (q_pi_target - alpha * logp_pi2))
+ else:
+ bellman_backup = jax.lax.stop_gradient(rewards +
+ FLAGS.gamma * q_pi_target)
+
+ # Compute the starting Q values from the Q network being optimized.
+ q1 = state.q1_apply(params, observation=observations1, R=R, action=actions)
+ q2 = state.q2_apply(params, observation=observations1, R=R, action=actions)
+
+ # Mean squared error loss against Bellman backup
+ q1_loss = ((q1 - bellman_backup)**2).mean()
+ q2_loss = ((q2 - bellman_backup)**2).mean()
+ return q1_loss + q2_loss
+
+
+@jax.jit
+def compute_loss_pi(state: TrainState, rng: PRNGKey, params, data: ArrayLike):
+ """Computes the Soft Actor-Critic loss for pi."""
+ observations1 = data['observations1']
+ R = data['goals']
+ # TODO(austin): We've got differentiable policy and differentiable physics. Can we use those here? Have Q learn the future, not the current step?
+
+ # Compute the action
+ pi, logp_pi, _ = state.pi_apply(rng=rng,
+ params=params,
+ observation=observations1,
+ R=R)
+ q1_pi = state.q1_apply(jax.lax.stop_gradient(params),
+ observation=observations1,
+ R=R,
+ action=pi)
+ q2_pi = state.q2_apply(jax.lax.stop_gradient(params),
+ observation=observations1,
+ R=R,
+ action=pi)
+
+ # And compute the Q of that action.
+ q_pi = jax.numpy.minimum(q1_pi, q2_pi)
+
+ alpha = jax.lax.stop_gradient(jax.numpy.exp(params['logalpha']))
+
+ # Compute the entropy-regularized policy loss
+ return (alpha * logp_pi - q_pi).mean()
+
+
+@jax.jit
+def compute_loss_alpha(state: TrainState, rng: PRNGKey, params,
+ data: ArrayLike):
+ """Computes the Soft Actor-Critic loss for alpha."""
+ observations1 = data['observations1']
+ R = data['goals']
+ pi, logp_pi, _ = jax.lax.stop_gradient(
+ state.pi_apply(rng=rng, params=params, observation=observations1, R=R))
+
+ return (-jax.numpy.exp(params['logalpha']) *
+ (logp_pi + state.target_entropy)).mean(), logp_pi.mean()
+
+
+@jax.jit
+def compute_batched_loss_q(state: TrainState, rng: PRNGKey, params,
+ data: ArrayLike):
+
+ def bound_compute_loss_q(rng, data):
+ return compute_loss_q(state, rng, params, data)
+
+ return jax.vmap(bound_compute_loss_q)(
+ jax.random.split(rng, FLAGS.num_agents),
+ data,
+ ).mean()
+
+
+@jax.jit
+def compute_batched_loss_pi(state: TrainState, rng: PRNGKey, params,
+ data: ArrayLike):
+
+ def bound_compute_loss_pi(rng, data):
+ return compute_loss_pi(state, rng, params, data)
+
+ return jax.vmap(bound_compute_loss_pi)(
+ jax.random.split(rng, FLAGS.num_agents),
+ data,
+ ).mean()
+
+
+@jax.jit
+def compute_batched_loss_alpha(state: TrainState, rng: PRNGKey, params,
+ data: ArrayLike):
+
+ def bound_compute_loss_alpha(rng, data):
+ return compute_loss_alpha(state, rng, params, data)
+
+ loss, entropy = jax.vmap(bound_compute_loss_alpha)(
+ jax.random.split(rng, FLAGS.num_agents),
+ data,
+ )
+ return (loss.mean(), entropy.mean())
+
+
+@jax.jit
+def train_step(state: TrainState, data, update_rng: PRNGKey,
+ step: int) -> TrainState:
+ """Updates the parameters for Q, Pi, target Q, and alpha."""
+ update_rng, q_grad_rng = jax.random.split(update_rng)
+ print_nan(step, data)
+
+ # Update Q
+ q_grad_fn = jax.value_and_grad(
+ lambda params: compute_batched_loss_q(state, q_grad_rng, params, data))
+ q_loss, q_grads = q_grad_fn(state.params)
+ print_nan(step, q_loss)
+ print_nan(step, q_grads)
+
+ state = state.q_apply_gradients(step=step, grads=q_grads)
+
+ # Update pi
+ update_rng, pi_grad_rng = jax.random.split(update_rng)
+ pi_grad_fn = jax.value_and_grad(lambda params: compute_batched_loss_pi(
+ state, pi_grad_rng, params, data))
+ pi_loss, pi_grads = pi_grad_fn(state.params)
+ state = state.pi_apply_gradients(step=step, grads=pi_grads)
+
+ update_rng, alpha_grad_rng = jax.random.split(update_rng)
+
+ if FLAGS.alpha < 0.0:
+ # Update alpha
+ alpha_grad_fn = jax.value_and_grad(
+ lambda params: compute_batched_loss_alpha(state, alpha_grad_rng,
+ params, data),
+ has_aux=True,
+ )
+ (alpha_loss, entropy), alpha_grads = alpha_grad_fn(state.params)
+ print_nan(step, alpha_loss)
+ print_nan(step, alpha_grads)
+ state = state.alpha_apply_gradients(step=step, grads=alpha_grads)
+ else:
+ entropy = 0.0
+ alpha_loss = 0.0
+
+ return state, q_loss, pi_loss, alpha_loss, entropy
+
+
+@jax.jit
+def collect_experience(state: TrainState, replay_buffer_state,
+ step_rng: PRNGKey, step):
+ """Collects experience by simulating."""
+ pi_rng = jax.random.fold_in(step_rng, step)
+ pi_rng, initialization_rng = jax.random.split(pi_rng)
+ pi_rng, goal_rng = jax.random.split(pi_rng)
+
+ observation = jax.lax.with_sharding_constraint(
+ state.problem.random_states(initialization_rng, FLAGS.num_agents),
+ state.sharding)
+
+ R = state.problem.random_goals(goal_rng, FLAGS.num_agents)
+
+ def loop(i, val):
+ """Runs 1 step of our simulation."""
+ observation, pi_rng, replay_buffer_state = val
+ pi_rng, action_rng = jax.random.split(pi_rng)
+ logging.info('Observation shape: %s', observation.shape)
+
+ def true_fn(i):
+ # We are at the beginning of the process, pick a random action.
+ return state.problem.random_actions(action_rng,
+ X=observation,
+ goal=R,
+ dimensions=FLAGS.num_agents)
+
+ def false_fn(i):
+ # We are past the beginning of the process, use the trained network.
+ pi_action, _, _ = state.pi_apply(rng=action_rng,
+ params=state.params,
+ observation=observation,
+ R=R,
+ deterministic=False)
+ return pi_action
+
+ pi_action = jax.lax.cond(
+ step <= FLAGS.random_sample_steps,
+ true_fn,
+ false_fn,
+ i,
+ )
+
+ # Compute the destination state.
+ observation2 = jax.vmap(
+ lambda o, pi: state.problem.integrate_dynamics(o, pi),
+ in_axes=(0, 0))(observation, pi_action)
+
+ reward = jax.vmap(state.problem.reward)(X=observation2,
+ U=pi_action,
+ goal=R)
+
+ replay_buffer_state = state.replay_buffer.add(
+ replay_buffer_state, {
+ 'observations1': observation,
+ 'observations2': observation2,
+ 'actions': pi_action,
+ 'rewards': reward.reshape((FLAGS.num_agents, 1)),
+ 'goals': R,
+ })
+
+ return observation2, pi_rng, replay_buffer_state
+
+ # Run 1 horizon of simulation
+ final_observation, final_pi_rng, final_replay_buffer_state = jax.lax.fori_loop(
+ 0, FLAGS.horizon + 1, loop, (observation, pi_rng, replay_buffer_state))
+
+ return state, final_replay_buffer_state
+
+
+@jax.jit
+def update_gradients(rng: PRNGKey, state: TrainState, replay_buffer_state,
+ step: int):
+ rng, sample_rng = jax.random.split(rng)
+
+ def update_iteration(i, val):
+ rng, state, q_loss, pi_loss, alpha_loss, replay_buffer_state, entropy = val
+ rng, sample_rng, update_rng = jax.random.split(rng, 3)
+
+ batch = state.replay_buffer.sample(replay_buffer_state, sample_rng)
+
+ print_nan(i, replay_buffer_state)
+ print_nan(i, batch)
+
+ state, q_loss, pi_loss, alpha_loss, entropy = train_step(
+ state, data=batch.experience, update_rng=update_rng, step=i)
+
+ return rng, state, q_loss, pi_loss, alpha_loss, replay_buffer_state, entropy
+
+ rng, state, q_loss, pi_loss, alpha_loss, replay_buffer_state, entropy = jax.lax.fori_loop(
+ step, step + FLAGS.horizon + 1, update_iteration,
+ (rng, state, 0.0, 0.0, 0.0, replay_buffer_state, 0))
+
+ state = state.target_apply_gradients(step=state.step)
+
+ return rng, state, q_loss, pi_loss, alpha_loss, entropy
+
+
+def train(workdir: str, problem: Problem) -> train_state.TrainState:
+ """Trains a Soft Actor-Critic controller."""
+ rng = jax.random.key(0)
+ rng, r_rng = jax.random.split(rng)
+
+ run = aim.Run(repo='aim://127.0.0.1:53800')
+
+ run['hparams'] = {
+ 'q_learning_rate': FLAGS.q_learning_rate,
+ 'pi_learning_rate': FLAGS.pi_learning_rate,
+ 'alpha_learning_rate': FLAGS.alpha_learning_rate,
+ 'random_sample_steps': FLAGS.random_sample_steps,
+ 'batch_size': FLAGS.batch_size,
+ 'horizon': FLAGS.horizon,
+ 'warmup_steps': FLAGS.warmup_steps,
+ 'steps': FLAGS.steps,
+ 'replay_size': FLAGS.replay_size,
+ 'num_agents': FLAGS.num_agents,
+ 'polyak': FLAGS.polyak,
+ 'gamma': FLAGS.gamma,
+ 'alpha': FLAGS.alpha,
+ 'final_q_learning_rate': FLAGS.final_q_learning_rate,
+ 'final_pi_learning_rate': FLAGS.final_pi_learning_rate,
+ }
+
+ # Setup TrainState
+ rng, init_rng = jax.random.split(rng)
+ q_learning_rate = create_learning_rate_fn(
+ base_learning_rate=FLAGS.q_learning_rate,
+ final_learning_rate=FLAGS.final_q_learning_rate)
+ pi_learning_rate = create_learning_rate_fn(
+ base_learning_rate=FLAGS.pi_learning_rate,
+ final_learning_rate=FLAGS.final_pi_learning_rate)
+ state = create_train_state(
+ init_rng,
+ problem,
+ q_learning_rate=q_learning_rate,
+ pi_learning_rate=pi_learning_rate,
+ alpha_learning_rate=FLAGS.alpha_learning_rate,
+ )
+ state = restore_checkpoint(state, workdir)
+
+ logging.debug(nn.get_sharding(state, state.mesh))
+
+ replay_buffer_state = state.replay_buffer.init({
+ 'observations1':
+ jax.numpy.zeros((problem.num_states, )),
+ 'observations2':
+ jax.numpy.zeros((problem.num_states, )),
+ 'actions':
+ jax.numpy.zeros((problem.num_outputs, )),
+ 'rewards':
+ jax.numpy.zeros((1, )),
+ 'goals':
+ jax.numpy.zeros((problem.num_goals, )),
+ })
+
+ logging.debug(nn.get_sharding(replay_buffer_state, state.mesh))
+
+ # Number of gradients to accumulate before doing decent.
+ update_after = FLAGS.batch_size // FLAGS.num_agents
+
+ @partial(jax.jit, donate_argnums=(1, 2))
+ def train_loop(state: TrainState, replay_buffer_state, rng: PRNGKey,
+ step: int):
+ rng, step_rng = jax.random.split(rng)
+ # Collect experience
+ state, replay_buffer_state = collect_experience(
+ state,
+ replay_buffer_state,
+ step_rng,
+ step,
+ )
+
+ def nop(rng, state, replay_buffer_state, step):
+ return rng, state.update_step(step=step), 0.0, 0.0, 0.0, 0.0
+
+ # Train
+ rng, state, q_loss, pi_loss, alpha_loss, entropy = jax.lax.cond(
+ step >= update_after, update_gradients, nop, rng, state,
+ replay_buffer_state, step)
+
+ return state, replay_buffer_state, rng, q_loss, pi_loss, alpha_loss, entropy
+
+ last_time = time.time()
+ for step in range(0, FLAGS.steps, FLAGS.horizon):
+ state, replay_buffer_state, rng, q_loss, pi_loss, alpha_loss, entropy = train_loop(
+ state, replay_buffer_state, rng, step)
+
+ if FLAGS.debug_nan and has_nan(state.params):
+ logging.fatal('Nan params, aborting')
+
+ logging.info(
+ 'Step %s: q_loss=%s, pi_loss=%s, alpha_loss=%s, q_learning_rate=%s, pi_learning_rate=%s, alpha=%s, entropy=%s, random=%s',
+ step,
+ q_loss,
+ pi_loss,
+ alpha_loss,
+ q_learning_rate(step),
+ pi_learning_rate(step),
+ jax.numpy.exp(state.params['logalpha']),
+ entropy,
+ step <= FLAGS.random_sample_steps,
+ )
+
+ run.track(
+ {
+ 'q_loss': float(q_loss),
+ 'pi_loss': float(pi_loss),
+ 'alpha_loss': float(alpha_loss),
+ 'alpha': float(jax.numpy.exp(state.params['logalpha'])),
+ 'entropy': entropy,
+ },
+ step=step)
+
+ if time.time() > last_time + 3.0 and step > update_after:
+ # TODO(austin): Simulate a rollout and accumulate the reward. How good are we doing?
+ save_checkpoint(state, workdir)
+ last_time = time.time()
+
+ return state
diff --git a/frc971/imu_fdcan/README.md b/frc971/imu_fdcan/README.md
index 8e82f73..7bf7328 100644
--- a/frc971/imu_fdcan/README.md
+++ b/frc971/imu_fdcan/README.md
@@ -23,7 +23,8 @@
* The main code lives in [`Dual_IMU/Core/Src`](/Dual_IMU/Core/Src/). Make sure your changes happen inside sections marked `/* USER CODE BEGIN ... */` `/* USER CODE END ... */`. Code outside these markers will be overwritten by CubeIDE when generating code after changes to the `.ioc` file.
3) Build + Run:
* Option 1: Open CubeIDE GUI to build, debug, or run.
- * Option 2:
+ <!-- TODO(sindy): fix this build script -->
+ * Option 2 (DO NOT USE. NOT SAFE)
1) SSH onto the build server.
2) Run `bazel build -c opt --config=cortex-m4f-imu //frc971/imu_fdcan/Dual_IMU/Core:main.elf`. The output .elf file should be in bazel-bin/frc971/imu_fdcan/Dual_IMU/Core.
3) (If deploying code locally) Move file to local directory. For example: `scp <username>@build.frc971.org:<path/to/main.elf> <local/path/to/save/file/`. A good spot to put this locally is ./Dual_IMU/Debug/.
diff --git a/frc971/orin/set_orin_clock.sh b/frc971/orin/set_orin_clock.sh
index bc9dd8f..fd615c5 100755
--- a/frc971/orin/set_orin_clock.sh
+++ b/frc971/orin/set_orin_clock.sh
@@ -12,7 +12,7 @@
for orin in $ORIN_LIST; do
echo "========================================================"
- echo "Setting clock for ${ROBOT_PREFIX}71.10${orin}"
+ echo "Setting clock for 10.${ROBOT_PREFIX}.71.10${orin}"
echo "========================================================"
current_time=`sudo hwclock`
IFS="."
diff --git a/frc971/vision/image_logger.cc b/frc971/vision/image_logger.cc
index cb8fc4e..01ceaf4 100644
--- a/frc971/vision/image_logger.cc
+++ b/frc971/vision/image_logger.cc
@@ -75,6 +75,8 @@
});
}
+ LOG(INFO) << "Starting image_logger; will wait on joystick enabled to start "
+ "logging";
event_loop.OnRun([]() {
errno = 0;
setpriority(PRIO_PROCESS, 0, -20);
diff --git a/frc971/wpilib/talonfx.cc b/frc971/wpilib/talonfx.cc
index 4338cfd..0da7603 100644
--- a/frc971/wpilib/talonfx.cc
+++ b/frc971/wpilib/talonfx.cc
@@ -58,11 +58,12 @@
void TalonFX::WriteConfigs() {
ctre::phoenix6::configs::CurrentLimitsConfigs current_limits;
- current_limits.StatorCurrentLimit = stator_current_limit_;
+ current_limits.StatorCurrentLimit =
+ units::current::ampere_t{stator_current_limit_};
current_limits.StatorCurrentLimitEnable = true;
- current_limits.SupplyCurrentLimit = supply_current_limit_;
+ current_limits.SupplyCurrentLimit =
+ units::current::ampere_t{supply_current_limit_};
current_limits.SupplyCurrentLimitEnable = true;
- current_limits.SupplyTimeThreshold = 0.0;
ctre::phoenix6::configs::MotorOutputConfigs output_configs;
output_configs.NeutralMode = neutral_mode_;
diff --git a/frc971/zeroing/continuous_absolute_encoder.cc b/frc971/zeroing/continuous_absolute_encoder.cc
index 3381833..733d46d 100644
--- a/frc971/zeroing/continuous_absolute_encoder.cc
+++ b/frc971/zeroing/continuous_absolute_encoder.cc
@@ -165,4 +165,14 @@
return builder.Finish();
}
+void ContinuousAbsoluteEncoderZeroingEstimator::GetEstimatorState(
+ AbsoluteEncoderEstimatorStateStatic *fbs) const {
+ errors_.ToStaticFlatbuffer(fbs->add_errors());
+
+ fbs->set_error(error_);
+ fbs->set_zeroed(zeroed_);
+ fbs->set_position(position_);
+ fbs->set_absolute_position(filtered_absolute_encoder_);
+}
+
} // namespace frc971::zeroing
diff --git a/frc971/zeroing/continuous_absolute_encoder.h b/frc971/zeroing/continuous_absolute_encoder.h
index 4994280..5e700ee 100644
--- a/frc971/zeroing/continuous_absolute_encoder.h
+++ b/frc971/zeroing/continuous_absolute_encoder.h
@@ -47,6 +47,8 @@
virtual flatbuffers::Offset<State> GetEstimatorState(
flatbuffers::FlatBufferBuilder *fbb) const override;
+ void GetEstimatorState(AbsoluteEncoderEstimatorStateStatic *fbs) const;
+
private:
struct PositionStruct {
PositionStruct(const AbsolutePosition &position_buffer)
diff --git a/frc971/zeroing/zeroing.h b/frc971/zeroing/zeroing.h
index 68ef38f..01c2c61 100644
--- a/frc971/zeroing/zeroing.h
+++ b/frc971/zeroing/zeroing.h
@@ -10,7 +10,7 @@
#include "flatbuffers/flatbuffers.h"
#include "frc971/constants.h"
-#include "frc971/control_loops/control_loops_generated.h"
+#include "frc971/control_loops/control_loops_static.h"
// TODO(pschrader): Flag an error if encoder index pulse is not n revolutions
// away from the last one (i.e. got extra counts from noise, etc..)
diff --git a/motors/pistol_grip/generate_cogging.py b/motors/pistol_grip/generate_cogging.py
index 5b0a6e6..dc9f87d 100644
--- a/motors/pistol_grip/generate_cogging.py
+++ b/motors/pistol_grip/generate_cogging.py
@@ -8,7 +8,7 @@
def main(argv):
if len(argv) < 4:
- print 'Args: input output.cc struct_name'
+ print('Args: input output.cc struct_name')
return 1
data_sum = [0.0] * 4096
data_count = [0] * 4096
diff --git a/motors/python/haptic_phase_current.py b/motors/python/haptic_phase_current.py
index fec909d..ed0062a 100755
--- a/motors/python/haptic_phase_current.py
+++ b/motors/python/haptic_phase_current.py
@@ -117,11 +117,11 @@
# by to get motor current.
one_amp_scalar = (phases(f_single, 0.0).T * phases(g_single, 0.0))[0, 0]
-print 'Max BEMF', max(f(theta_range))
-print 'Max current', max(g(theta_range))
-print 'Max drive voltage (one_amp_driving_voltage)', max(
- one_amp_driving_voltage)
-print 'one_amp_scalar', one_amp_scalar
+print('Max BEMF', max(f(theta_range)))
+print('Max current', max(g(theta_range)))
+print('Max drive voltage (one_amp_driving_voltage)',
+ max(one_amp_driving_voltage))
+print('one_amp_scalar', one_amp_scalar)
pylab.figure()
pylab.subplot(1, 1, 1)
@@ -464,19 +464,20 @@
self.B_discrete_inverse_model = numpy.matrix(numpy.eye(3)) / (
self.B_discrete_model[0, 0] - self.B_discrete_model[1, 0])
- print 'constexpr double kL = %g;' % self.L_model
- print 'constexpr double kM = %g;' % self.M_model
- print 'constexpr double kR = %g;' % self.R_model
- print 'constexpr float kAdiscrete_diagonal = %gf;' % self.A_discrete_model[
- 0, 0]
- print 'constexpr float kAdiscrete_offdiagonal = %gf;' % self.A_discrete_model[
- 1, 0]
- print 'constexpr float kBdiscrete_inv_diagonal = %gf;' % self.B_discrete_inverse_model[
- 0, 0]
- print 'constexpr float kBdiscrete_inv_offdiagonal = %gf;' % self.B_discrete_inverse_model[
- 1, 0]
- print 'constexpr double kOneAmpScalar = %g;' % one_amp_scalar
- print 'constexpr double kMaxOneAmpDrivingVoltage = %g;' % max_one_amp_driving_voltage
+ print('constexpr double kL = %g;' % self.L_model)
+ print('constexpr double kM = %g;' % self.M_model)
+ print('constexpr double kR = %g;' % self.R_model)
+ print('constexpr float kAdiscrete_diagonal = %gf;' %
+ self.A_discrete_model[0, 0])
+ print('constexpr float kAdiscrete_offdiagonal = %gf;' %
+ self.A_discrete_model[1, 0])
+ print('constexpr float kBdiscrete_inv_diagonal = %gf;' %
+ self.B_discrete_inverse_model[0, 0])
+ print('constexpr float kBdiscrete_inv_offdiagonal = %gf;' %
+ self.B_discrete_inverse_model[1, 0])
+ print('constexpr double kOneAmpScalar = %g;' % one_amp_scalar)
+ print('constexpr double kMaxOneAmpDrivingVoltage = %g;' %
+ max_one_amp_driving_voltage)
print('A_discrete', self.A_discrete)
print('B_discrete', self.B_discrete)
print('B_discrete_sub', numpy.linalg.inv(self.B_discrete[0:2, 0:2]))
@@ -574,8 +575,8 @@
# Subtract that, and then run the stock statespace equation.
Vn_ff = self.B_discrete_inverse * (Inext - self.A_discrete *
(Icurrent - p) - p_next_imag.real)
- print 'Vn_ff', Vn_ff
- print 'Inext', Inext
+ print('Vn_ff', Vn_ff)
+ print('Inext', Inext)
Vn = Vn_ff + self.K * (Icurrent - measured_current)
E = phases(f_single, self.X[3, 0]) / Kv * self.X[4, 0]
@@ -629,7 +630,7 @@
self.current_time = t
- print 'Took %f to simulate' % (time.time() - start_wall_time)
+ print('Took %f to simulate' % (time.time() - start_wall_time))
self.data_logger.plot()
diff --git a/scouting/deploy/BUILD b/scouting/deploy/BUILD
index 65b33fb..e453b0b 100644
--- a/scouting/deploy/BUILD
+++ b/scouting/deploy/BUILD
@@ -17,15 +17,6 @@
include_runfiles = True,
package_dir = "opt/frc971/scouting_server",
strip_prefix = ".",
- # The "include_runfiles" attribute creates a runfiles tree as seen from
- # within the workspace directory. But what we really want is the runfiles
- # tree as seen from the root of the runfiles tree (i.e. one directory up).
- # So we work around it by manually adding some symlinks that let us pretend
- # that we're at the root of the runfiles tree.
- symlinks = {
- "org_frc971": ".",
- "bazel_tools": "external/bazel_tools",
- },
)
pkg_tar(
diff --git a/scouting/deploy/postinst b/scouting/deploy/postinst
index be2b170..20f6052 100644
--- a/scouting/deploy/postinst
+++ b/scouting/deploy/postinst
@@ -21,7 +21,7 @@
# Update the timestamps on the files so that web browsers pull the new version.
# Otherwise users have to explicitly bypass the cache when visiting the site.
-find /opt/frc971/scouting_server/scouting/www/ -type f -exec touch {} +
+find /opt/frc971/scouting_server/scouting/scouting.runfiles/org_frc971/scouting/www/ -type f -exec touch {} +
systemctl daemon-reload
systemctl enable scouting.service
diff --git a/scouting/deploy/scouting.service b/scouting/deploy/scouting.service
index 2c55676..f5b0431 100644
--- a/scouting/deploy/scouting.service
+++ b/scouting/deploy/scouting.service
@@ -6,8 +6,8 @@
User=www-data
Group=www-data
Type=simple
-WorkingDirectory=/opt/frc971/scouting_server
-Environment=RUNFILES_DIR=/opt/frc971/scouting_server
+WorkingDirectory=/opt/frc971/scouting_server/scouting/scouting.runfiles/org_frc971
+Environment=RUNFILES_DIR=/opt/frc971/scouting_server/scouting/scouting.runfiles
# Add "julia" to the PATH.
Environment=PATH=/opt/frc971/julia_runtime/bin:/usr/local/bin:/usr/bin:/bin
# Use the Julia cache set up by the frc971-scouting-julia package.
diff --git a/scouting/scouting_test.cy.js b/scouting/scouting_test.cy.js
index 2727104..7157880 100644
--- a/scouting/scouting_test.cy.js
+++ b/scouting/scouting_test.cy.js
@@ -102,7 +102,12 @@
cy.contains(/Harmony/).click();
clickButton('End Match');
+
+ clickButton('UNDO');
+ clickButton('End Match');
+
headerShouldBe(teamNumber + ' Review and Submit ');
+
cy.get('#review_data li')
.eq(0)
.should('have.text', ' Started match at position 1 ');
@@ -113,6 +118,8 @@
'have.text',
' Ended Match; stageType: kHARMONY, trapNote: false, spotlight: false '
);
+ // Ensure that the penalties action is only submitted once.
+ cy.get('#review_data li:contains("Penalties")').its('length').should('eq', 1);
clickButton('Submit');
headerShouldBe(teamNumber + ' Success ');
diff --git a/scouting/www/entry/entry.component.ts b/scouting/www/entry/entry.component.ts
index 1a757a0..3c8aba9 100644
--- a/scouting/www/entry/entry.component.ts
+++ b/scouting/www/entry/entry.component.ts
@@ -334,6 +334,9 @@
break;
case ActionType.EndMatchAction:
this.section = 'Endgame';
+ // Also delete the penalty action.
+ this.undoLastAction();
+ break;
case ActionType.MobilityAction:
this.mobilityCompleted = false;
break;
diff --git a/scouting/www/entry/entry.ng.html b/scouting/www/entry/entry.ng.html
index 1b3a966..67d9f9f 100644
--- a/scouting/www/entry/entry.ng.html
+++ b/scouting/www/entry/entry.ng.html
@@ -467,6 +467,9 @@
<span *ngSwitchCase="ActionType.EndAutoPhaseAction">
Ended auto phase
</span>
+ <span *ngSwitchCase="ActionType.EndTeleopPhaseAction">
+ Ended teleop phase
+ </span>
<span *ngSwitchCase="ActionType.EndMatchAction">
Ended Match; stageType: {{stringifyStageType((action.actionTaken |
cast: EndMatchActionT).stageType)}}, trapNote:
diff --git a/tools/foxglove/creation_wrapper_npm.py b/tools/foxglove/creation_wrapper_npm.py
index 6483536..34ca6ab 100644
--- a/tools/foxglove/creation_wrapper_npm.py
+++ b/tools/foxglove/creation_wrapper_npm.py
@@ -33,9 +33,10 @@
package.rsplit("@", maxsplit=1) for package in packages)
package_json_file = Path.cwd() / "package.json"
package_json = json.loads(package_json_file.read_text())
- package_json.setdefault("dependencies", {}).update(
- {package: version
- for package, version in package_version_pairs})
+ package_json.setdefault("dependencies", {}).update({
+ package: version
+ for package, version in package_version_pairs
+ })
package_json_file.write_text(
json.dumps(package_json, sort_keys=True, indent=4))
diff --git a/tools/python/BUILD b/tools/python/BUILD
index 40698ef..1835e0d 100644
--- a/tools/python/BUILD
+++ b/tools/python/BUILD
@@ -4,6 +4,10 @@
# Invoke this via "bazel run //tools/python:requirements.update".
compile_pip_requirements(
name = "requirements",
+ extra_args = [
+ # Make it so we can depend on setuptools.
+ "--allow-unsafe",
+ ],
requirements_in = "requirements.txt",
requirements_txt = "requirements.lock.txt",
tags = [
diff --git a/tools/python/requirements.lock.txt b/tools/python/requirements.lock.txt
index 4398d95..d465241 100644
--- a/tools/python/requirements.lock.txt
+++ b/tools/python/requirements.lock.txt
@@ -7,11 +7,169 @@
absl-py==2.1.0 \
--hash=sha256:526a04eadab8b4ee719ce68f204172ead1027549089702d99b9059f129ff1308 \
--hash=sha256:7820790efbb316739cde8b4e19357243fc3608a152024288513dd968d7d959ff
+ # via
+ # -r tools/python/requirements.txt
+ # array-record
+ # chex
+ # clu
+ # keras
+ # ml-collections
+ # optax
+ # orbax-checkpoint
+ # tensorboard
+ # tensorflow
+ # tensorflow-datasets
+ # tensorflow-metadata
+ # tensorflow-probability
+aim==3.24.0 \
+ --hash=sha256:1266fac2453f2d356d2e39c98d15b46ba7a71ecab14cdaa6eaa6d390f5add898 \
+ --hash=sha256:1322659dcecb701c264f5067375c74811faf3514bb316e1ca1e53b9de6b62766 \
+ --hash=sha256:13dff702a680ad2d25344543e3b912c217a0fd305d5355f388fcd14f030af4f0 \
+ --hash=sha256:14a70cd508b4761d7d4e1f302207feb58906ac3ab27d2d64eeb4f1cbb8d4dc47 \
+ --hash=sha256:1789bcc9edf69ae90bb18a6f3fa4862095b8020eadc7e5e0e93ba4f242250947 \
+ --hash=sha256:29949cf7e5b5a46cff6a1d868805962e6563929934cd1d5d47678a58a4c9b777 \
+ --hash=sha256:2a9158717267e4f04ac12ffef8ef22c3e72af3b284ce4a86906a511d57ee98b9 \
+ --hash=sha256:2b0e41e6b46b6e435be845aeda4792cc6b392fb17bb5096e6ca186fffeb96547 \
+ --hash=sha256:2ea588e075a5508014af74be4821adc58041ac034af81b106936482043fcb124 \
+ --hash=sha256:39462568e7e4270574c20812b2ede4747e908c0320f947c39b94cdcbda63141b \
+ --hash=sha256:430000ece9e045d4b5313b0e683c363730b712260147834c4a6f89a2fd06513d \
+ --hash=sha256:4903a1ead28681dd5a51b4c8b613e6af5a158bde11d77678a64d6eeab9d9e97f \
+ --hash=sha256:663f939ebd89d053ca2a31f921cf2389f94b75fe3a97a66840b33ac0c8888b46 \
+ --hash=sha256:6937cb8736063e3734292f32aed8de141173be83d6dc9c49d8f05a58bb99a713 \
+ --hash=sha256:696aa9bb1c4316fb9171410daaff640293d5d2ee215055dd7eda27445318240b \
+ --hash=sha256:6b1b12e6724677c1bf9d9c62a0ddb30cc5b130080765fd217792e36a6622a3e3 \
+ --hash=sha256:8328b7703b7626f1f5082e947c5e203011536de039c64e551364444299ff68e1 \
+ --hash=sha256:8aff59858e5944ede0eb7ecbd56d4131418913a5cb13436dbe55e1795b85a838 \
+ --hash=sha256:92a794755de87c920bc1de49856a0ec864a903c2e4fb090a4fe6b0a71136c865 \
+ --hash=sha256:b2a2755115aa9b8efc57d262bef9ce9f13ca56068e6833bf359884228cab9803 \
+ --hash=sha256:c0f8dd9542bdf251b195d8c1680367b7c043a1fb59fd170944679157f2cf2b05 \
+ --hash=sha256:cb9d3e638598309e7e1d9970c62ec93d329ffcdeab7753886eee985b2b15a207 \
+ --hash=sha256:d52419e43d5a879455ca874843e5e45d4725022665a7c560f6b2193ad6a181a4 \
+ --hash=sha256:d63186f069f097de107a373fca2de9a5e7662c7d2ed4364b8937b5a5544e92f7 \
+ --hash=sha256:e481ef1e6e3ea17632fd4ecdee89cabb3f815929a5b080ee0e868e553f893c55 \
+ --hash=sha256:eaf98b0cba60d97cbce75a88ae96ce4c2439b3ba77572b9f17a5885fb76e9154 \
+ --hash=sha256:ec3bd85fdb5b85b9655d77fd0474e3f5c78f5065ca77c59efd77dbfae8005e40 \
+ --hash=sha256:f98f52fab910cdaee91256cf722e51b3edb131d9a0331519bccc9b6f06c28f6a
# via -r tools/python/requirements.txt
-bokeh==3.4.1 \
- --hash=sha256:1e3c502a0a8205338fc74dadbfa321f8a0965441b39501e36796a47b4017b642 \
- --hash=sha256:d824961e4265367b0750ce58b07e564ad0b83ca64b335521cd3421e9b9f10d89
+aim-ui==3.24.0 \
+ --hash=sha256:d24ca6059095f76f29b4bee211b71dcfa5ed2e4fa6d16d82a343c900d5a37498
+ # via aim
+aimrecords==0.0.7 \
+ --hash=sha256:9b562fa5b5109b4b3dd4f83be0061cadbac63fa8031f281b8b5c8ae29967072f \
+ --hash=sha256:b9276890891c5fd68f817e20fc5d466a80c01e22fa468eaa979331448a75d601
+ # via aim
+aimrocks==0.5.2 \
+ --hash=sha256:03ca9bd3a7d379f40c678e648d3ec1445738a32fee337009cfb6aa9aedc51964 \
+ --hash=sha256:081b59cf3a02056420e32d8fa851859d314ae227e975d6febba67e9341135208 \
+ --hash=sha256:14982839f451f8990e9a1b5c4c06ffc77cafeb3b4a7f372f92a1da19a52a8a11 \
+ --hash=sha256:18574bab2cc060231a3da26a3ca2b18b6482b79649217e8fdcf6bc29efcdf973 \
+ --hash=sha256:1c1754ba5da8f2e016ed96b85eeb31048cc325cc351c32431d668ab226a0d986 \
+ --hash=sha256:2cfc3f4f1e4b105c1973007e4798aa3cedc0fc81436f81c220e02a00d796071c \
+ --hash=sha256:2d120e114c11882e8ac7dcd76a745b21da1fd0cd10aeaf525ec8a48a08556b3f \
+ --hash=sha256:3e580c5640c61e47591873448ddfd5741979f2bccf40809157fb260c6956f1e5 \
+ --hash=sha256:3f65583d29bcfc3baa422e45e73de89c4c781490664eb49c1a4c21c074f5bbfa \
+ --hash=sha256:4aaa2ffae1dbdcd2be21535a2866ec4a9a2fbb4338cc5b955ad6ca3fae22461c \
+ --hash=sha256:4ce617cf9f11e81a70070ea1d14fa2204996c651984cbd19178246eb33b143d0 \
+ --hash=sha256:533eda940f4bd1641fee15da09595c965d6890e449706fb3442174472b468a19 \
+ --hash=sha256:5c92e843818e7b764725c1dca1ca6744202ac46b5c246b407e39e8a28e0266a1 \
+ --hash=sha256:691621709f02841a248ed2555ec61346c50bfc07df2553be54a355c9010676e3 \
+ --hash=sha256:6b11d27df8ebec63bb9a121c55bc19c8b93801a6a9064533835e056bc5a11bb6 \
+ --hash=sha256:7452149a119d4b3620254a567c3c68ecfa3e016f58f443847e4fb70b85186593 \
+ --hash=sha256:76258350f2715d686d5da12a5a2df0d7b88e1b33e45052e0ddeb549c7497a56e \
+ --hash=sha256:762f7b41793165717a9e0589658cd81bffb54161295ec7403534d40692ac9281 \
+ --hash=sha256:7635741ed2b8dbf59c7564446bd0716dd5ea431c82753000ca4851bed9e76911 \
+ --hash=sha256:79400c6f4c72bcc4485f2a4411a3e6c1f6ead7a3928a00a72739abb1ef9ec0d3 \
+ --hash=sha256:7f47ae2f2183e1c1c9299be79ac9704b1d47e66c8ae7d41356385ad33e9def4b \
+ --hash=sha256:8b3364c566e547cd1855700cdec07149a139f6665a6ad60275e3ee3679945dbd \
+ --hash=sha256:8d685e8092db34c68ff8208c4961918345e14a0bdddf0ee22017346433950cc8 \
+ --hash=sha256:95dae89ed772439a12c845d013dca1dc3abb88ccd71ee50bc8728d43afddd7d7 \
+ --hash=sha256:96d6877437108ca8f8c3c72f27aeeb987af881ca6fe78a46962d3bf96346fd23 \
+ --hash=sha256:9becbd34b2bac33dae7db5ce85f9ef70b83b20fd547794a40b7a7bd846be45fa \
+ --hash=sha256:9c88bdacf4d977f80b3c9a7555b5e152945d66feccd6e0cc7d2135a7f477d6bc \
+ --hash=sha256:9d870581e402c718549385704d3bbb373aa6eb684b1e1bc5cb935af8ebba91b6 \
+ --hash=sha256:9db95c611b04cc4fb1796436c3e09483414636282261f5eae46c73f68bd9dce9 \
+ --hash=sha256:9de44918367c5f8f2f9b638f97c720320c5bb4fd400a76e4e94d34b6d7d41cc6 \
+ --hash=sha256:9faaecf4fe0335c27e63523f6a25e038877a33c63a261ff2192582e52493b39b \
+ --hash=sha256:a3be10ecd3373c35ce51b8b531c2ac41e11ff954ee678377512e8210a01b593b \
+ --hash=sha256:a9ba647f32934ac999c4119cbb8b59510dfe69aec98558539b84db7db9f20acf \
+ --hash=sha256:aba6d805b5370eda1c946c269d6df926a083819798603652c8f3b16469fea1d2 \
+ --hash=sha256:ada99031f85364232a5f8b6c3be0ef4835d26f03b09529c86b2b80c8b027428c \
+ --hash=sha256:b26c2d9adee42ce1611add5220567cab1a831813b0f711d7921cbaa0bf633a28 \
+ --hash=sha256:b5777e4aa7a5d2715c5bf698d4b4049d3f2b95bc0704d455ac486498820cd963 \
+ --hash=sha256:bba97b8bbe82b41e7aa52b64a80e1da5279e54153cb46a0364f9947c0655e5a8 \
+ --hash=sha256:bc9a4007ffad3d9a84188f8062ec2d2122283769956895a73e2336febc5ae8f1 \
+ --hash=sha256:be3a48210a2dc25633d53b0b7c33b362b7fce8f9fe2ad4ebb4cdc03471bdeb62 \
+ --hash=sha256:c338d07e80344e15e6c49d8c125f31492ac58c8236c82f7c0d8171c81027b4dc \
+ --hash=sha256:c98ca6955a43ed2c968ae9fe44bb1049f52d59ef319d9f78eb99dd4d3359a580 \
+ --hash=sha256:d4cc1523e7cd766937600da915b061538a44efec1f814b08b056eef3876e89cf \
+ --hash=sha256:d5e34571e930f99df9832cfeb7ad9917cbf0245ef2e3177cb82f86c29e1b273d \
+ --hash=sha256:d5e916f34a5d34d4da6a9199ece1c0d51efa93a30984ed89ad4ccaa1fb7a51c2 \
+ --hash=sha256:d74170021b17451881df18683eb0aa97417cb8b030b3dea425d7580891c22608 \
+ --hash=sha256:e018df19877ed13e93bbc8e8c32664cedade08d483eb0aa7077fc41b8eefd005 \
+ --hash=sha256:e6a79076d669dbf221442399da893baff6c1549031edbb5d556042d1b9b6525c \
+ --hash=sha256:e9a62a21266f88337e58d443ca58e85293232f543bcf0a66832fc89d4f9a320d \
+ --hash=sha256:eb4adb6bc4db3f0d3a1fe6cfec05846f76fabe5a3faeabc294c9777535351864 \
+ --hash=sha256:f479567d8514a63ee7f227d0841dc886870c37c3f6e17a8724ecaebfaa1331b2 \
+ --hash=sha256:f99ae65f910cf4a505457a280c9296212c9d844f5ece8c7d28813edf62787602 \
+ --hash=sha256:fe5b69e7dc54a07188d06fba9da012318223b60c07a96d39f90ccf1b01f833f7 \
+ --hash=sha256:ff6334af4ac403438eae330bf25fff5b3a63ba9f8f87a77ebb2d34815ef36431
+ # via aim
+aiofiles==24.1.0 \
+ --hash=sha256:22a075c9e5a3810f0c2e48f3008c94d68c65d763b9b03857924c99e57355166c \
+ --hash=sha256:b4ec55f4195e3eb5d7abd1bf7e061763e864dd4954231fb8539a0ef8bb8260e5
+ # via aim
+alembic==1.13.3 \
+ --hash=sha256:203503117415561e203aa14541740643a611f641517f0209fcae63e9fa09f1a2 \
+ --hash=sha256:908e905976d15235fae59c9ac42c4c5b75cfcefe3d27c0fbf7ae15a37715d80e
+ # via aim
+annotated-types==0.7.0 \
+ --hash=sha256:1f02e8b43a8fbbc3f3e0d4f0f4bfc8131bcb4eebe8849b8e5c773f3a1c582a53 \
+ --hash=sha256:aff07c09a53a08bc8cfccb9c85b05f1aa9a2a6f23728d790723543408344ce89
+ # via pydantic
+anyio==4.6.0 \
+ --hash=sha256:137b4559cbb034c477165047febb6ff83f390fc3b20bf181c1fc0a728cb8beeb \
+ --hash=sha256:c7d2e9d63e31599eeb636c8c5c03a7e108d73b345f064f1c19fdc87b79036a9a
+ # via starlette
+array-record==0.5.1 \
+ --hash=sha256:248fb29086cb3a6322a5d8b8332d77713a030bc54f0bacdf215a6d3185f73f90 \
+ --hash=sha256:6ebe99f37e3a797322f4f5cfc6902b5e852012ba2729fac628aad6affb225247 \
+ --hash=sha256:897362036f2920093eff3d729c2a6e1844e3077f513d6bd29640cd02f98e07c7 \
+ --hash=sha256:8ebd7c12c0a159a44c6c8fdaf915036fcddfdfa499a878ddcff9761c6d1af685 \
+ --hash=sha256:9922862216a9d3be76fdc27968af1ec0ea20f986329998ba45b0f01ee3e646fa \
+ --hash=sha256:b9f2e304e59a17af9f5bf2a86b93ad4700d0eeb85d742a884aa38dc0b54dda5b \
+ --hash=sha256:ea3969b9f954f6f01ddac64f59eea45392dc4eb8c1bf3d1ca5c9bcfd7f8d46e7 \
+ --hash=sha256:f08eea9a4afbfa05fb7fafaa007b89e286a8a27a7775cb80338199576ffe07b4
+ # via tensorflow-datasets
+astunparse==1.6.3 \
+ --hash=sha256:5ad93a8456f0d084c3456d059fd9a92cce667963232cbf763eac3bc5b7940872 \
+ --hash=sha256:c2652417f2c8b5bb325c885ae329bdf3f86424075c4fd1a128674bc6fba4b8e8
+ # via tensorflow
+base58==2.0.1 \
+ --hash=sha256:365c9561d9babac1b5f18ee797508cd54937a724b6e419a130abad69cec5ca79 \
+ --hash=sha256:447adc750d6b642987ffc6d397ecd15a799852d5f6a1d308d384500243825058
+ # via aimrecords
+blinker==1.8.2 \
+ --hash=sha256:1779309f71bf239144b9399d06ae925637cf6634cf6bd131104184531bf67c01 \
+ --hash=sha256:8f77b09d3bf7c795e969e9486f39c2c5e9c39d4ee07424be2bc594ece9642d83
+ # via flask
+bokeh==3.4.3 \
+ --hash=sha256:b7c22fb0f7004b04f12e1b7b26ee0269a26737a08ded848fb58f6a34ec1eb155 \
+ --hash=sha256:c6f33817f866fc67fbeb5df79cd13a8bb592c05c591f3fd7f4f22b824f7afa01
# via -r tools/python/requirements.txt
+boto3==1.35.27 \
+ --hash=sha256:10d0fe15670b83a3f26572ab20d9152a064cee4c54b5ea9a1eeb1f0c3b807a7b \
+ --hash=sha256:3da139ca038032e92086e26d23833b557f0c257520162bfd3d6f580bf8032c86
+ # via aim
+botocore==1.35.27 \
+ --hash=sha256:c299c70b5330a8634e032883ce8a72c2c6d9fdbc985d8191199cb86b92e7cbbd \
+ --hash=sha256:f68875c26cd57a9d22c0f7a981ecb1636d7ce4d0e35797e04765b53e7bfed3e7
+ # via
+ # boto3
+ # s3transfer
+cachetools==5.5.0 \
+ --hash=sha256:02134e8439cdc2ffb62023ce1debca2944c3f289d66bb17ead3ab3dede74b292 \
+ --hash=sha256:2cc24fb4cbe39633fb7badd9db9ca6295d766d9c2995f245725a46715d050f2a
+ # via aim
casadi==3.6.6 \
--hash=sha256:0870df9ac7040c14b35fdc82b74578ccfe8f1d9d8615eb79693a560fefb42307 \
--hash=sha256:0fd493876c673ad149b03513c4f72275611643f2225f4f5d7c7ff828f75805a1 \
@@ -63,74 +221,448 @@
--hash=sha256:f5c0e9312e58f4a35f7b7a009b423bfddd1adc065447cae248dce686cec5b08d \
--hash=sha256:ffcba96fe3695223c9f88b9d870cbeb08b7adb92929bfe15bad0e2143e62790d
# via -r tools/python/requirements.txt
-certifi==2022.9.24 \
- --hash=sha256:0d9c601124e5a6ba9712dbc60d9c53c21e34f5f641fe83002317394311bdce14 \
- --hash=sha256:90c1a32f1d68f940488354e36370f6cca89f0f106db09518524c88d6ed83f382
+certifi==2024.8.30 \
+ --hash=sha256:922820b53db7a7257ffbda3f597266d435245903d80737e34f8a45ff3e3230d8 \
+ --hash=sha256:bec941d2aa8195e248a60b31ff9f0558284cf01a52591ceda73ea9afffd69fd9
# via requests
-charset-normalizer==2.1.1 \
- --hash=sha256:5a3d016c7c547f69d6f81fb0db9449ce888b418b5b9952cc5e6e66843e9dd845 \
- --hash=sha256:83e9a75d1911279afd89352c68b45348559d1fc0506b054b346651b5e7fee29f
+cffi==1.17.1 \
+ --hash=sha256:045d61c734659cc045141be4bae381a41d89b741f795af1dd018bfb532fd0df8 \
+ --hash=sha256:0984a4925a435b1da406122d4d7968dd861c1385afe3b45ba82b750f229811e2 \
+ --hash=sha256:0e2b1fac190ae3ebfe37b979cc1ce69c81f4e4fe5746bb401dca63a9062cdaf1 \
+ --hash=sha256:0f048dcf80db46f0098ccac01132761580d28e28bc0f78ae0d58048063317e15 \
+ --hash=sha256:1257bdabf294dceb59f5e70c64a3e2f462c30c7ad68092d01bbbfb1c16b1ba36 \
+ --hash=sha256:1c39c6016c32bc48dd54561950ebd6836e1670f2ae46128f67cf49e789c52824 \
+ --hash=sha256:1d599671f396c4723d016dbddb72fe8e0397082b0a77a4fab8028923bec050e8 \
+ --hash=sha256:28b16024becceed8c6dfbc75629e27788d8a3f9030691a1dbf9821a128b22c36 \
+ --hash=sha256:2bb1a08b8008b281856e5971307cc386a8e9c5b625ac297e853d36da6efe9c17 \
+ --hash=sha256:30c5e0cb5ae493c04c8b42916e52ca38079f1b235c2f8ae5f4527b963c401caf \
+ --hash=sha256:31000ec67d4221a71bd3f67df918b1f88f676f1c3b535a7eb473255fdc0b83fc \
+ --hash=sha256:386c8bf53c502fff58903061338ce4f4950cbdcb23e2902d86c0f722b786bbe3 \
+ --hash=sha256:3edc8d958eb099c634dace3c7e16560ae474aa3803a5df240542b305d14e14ed \
+ --hash=sha256:45398b671ac6d70e67da8e4224a065cec6a93541bb7aebe1b198a61b58c7b702 \
+ --hash=sha256:46bf43160c1a35f7ec506d254e5c890f3c03648a4dbac12d624e4490a7046cd1 \
+ --hash=sha256:4ceb10419a9adf4460ea14cfd6bc43d08701f0835e979bf821052f1805850fe8 \
+ --hash=sha256:51392eae71afec0d0c8fb1a53b204dbb3bcabcb3c9b807eedf3e1e6ccf2de903 \
+ --hash=sha256:5da5719280082ac6bd9aa7becb3938dc9f9cbd57fac7d2871717b1feb0902ab6 \
+ --hash=sha256:610faea79c43e44c71e1ec53a554553fa22321b65fae24889706c0a84d4ad86d \
+ --hash=sha256:636062ea65bd0195bc012fea9321aca499c0504409f413dc88af450b57ffd03b \
+ --hash=sha256:6883e737d7d9e4899a8a695e00ec36bd4e5e4f18fabe0aca0efe0a4b44cdb13e \
+ --hash=sha256:6b8b4a92e1c65048ff98cfe1f735ef8f1ceb72e3d5f0c25fdb12087a23da22be \
+ --hash=sha256:6f17be4345073b0a7b8ea599688f692ac3ef23ce28e5df79c04de519dbc4912c \
+ --hash=sha256:706510fe141c86a69c8ddc029c7910003a17353970cff3b904ff0686a5927683 \
+ --hash=sha256:72e72408cad3d5419375fc87d289076ee319835bdfa2caad331e377589aebba9 \
+ --hash=sha256:733e99bc2df47476e3848417c5a4540522f234dfd4ef3ab7fafdf555b082ec0c \
+ --hash=sha256:7596d6620d3fa590f677e9ee430df2958d2d6d6de2feeae5b20e82c00b76fbf8 \
+ --hash=sha256:78122be759c3f8a014ce010908ae03364d00a1f81ab5c7f4a7a5120607ea56e1 \
+ --hash=sha256:805b4371bf7197c329fcb3ead37e710d1bca9da5d583f5073b799d5c5bd1eee4 \
+ --hash=sha256:85a950a4ac9c359340d5963966e3e0a94a676bd6245a4b55bc43949eee26a655 \
+ --hash=sha256:8f2cdc858323644ab277e9bb925ad72ae0e67f69e804f4898c070998d50b1a67 \
+ --hash=sha256:9755e4345d1ec879e3849e62222a18c7174d65a6a92d5b346b1863912168b595 \
+ --hash=sha256:98e3969bcff97cae1b2def8ba499ea3d6f31ddfdb7635374834cf89a1a08ecf0 \
+ --hash=sha256:a08d7e755f8ed21095a310a693525137cfe756ce62d066e53f502a83dc550f65 \
+ --hash=sha256:a1ed2dd2972641495a3ec98445e09766f077aee98a1c896dcb4ad0d303628e41 \
+ --hash=sha256:a24ed04c8ffd54b0729c07cee15a81d964e6fee0e3d4d342a27b020d22959dc6 \
+ --hash=sha256:a45e3c6913c5b87b3ff120dcdc03f6131fa0065027d0ed7ee6190736a74cd401 \
+ --hash=sha256:a9b15d491f3ad5d692e11f6b71f7857e7835eb677955c00cc0aefcd0669adaf6 \
+ --hash=sha256:ad9413ccdeda48c5afdae7e4fa2192157e991ff761e7ab8fdd8926f40b160cc3 \
+ --hash=sha256:b2ab587605f4ba0bf81dc0cb08a41bd1c0a5906bd59243d56bad7668a6fc6c16 \
+ --hash=sha256:b62ce867176a75d03a665bad002af8e6d54644fad99a3c70905c543130e39d93 \
+ --hash=sha256:c03e868a0b3bc35839ba98e74211ed2b05d2119be4e8a0f224fba9384f1fe02e \
+ --hash=sha256:c59d6e989d07460165cc5ad3c61f9fd8f1b4796eacbd81cee78957842b834af4 \
+ --hash=sha256:c7eac2ef9b63c79431bc4b25f1cd649d7f061a28808cbc6c47b534bd789ef964 \
+ --hash=sha256:c9c3d058ebabb74db66e431095118094d06abf53284d9c81f27300d0e0d8bc7c \
+ --hash=sha256:ca74b8dbe6e8e8263c0ffd60277de77dcee6c837a3d0881d8c1ead7268c9e576 \
+ --hash=sha256:caaf0640ef5f5517f49bc275eca1406b0ffa6aa184892812030f04c2abf589a0 \
+ --hash=sha256:cdf5ce3acdfd1661132f2a9c19cac174758dc2352bfe37d98aa7512c6b7178b3 \
+ --hash=sha256:d016c76bdd850f3c626af19b0542c9677ba156e4ee4fccfdd7848803533ef662 \
+ --hash=sha256:d01b12eeeb4427d3110de311e1774046ad344f5b1a7403101878976ecd7a10f3 \
+ --hash=sha256:d63afe322132c194cf832bfec0dc69a99fb9bb6bbd550f161a49e9e855cc78ff \
+ --hash=sha256:da95af8214998d77a98cc14e3a3bd00aa191526343078b530ceb0bd710fb48a5 \
+ --hash=sha256:dd398dbc6773384a17fe0d3e7eeb8d1a21c2200473ee6806bb5e6a8e62bb73dd \
+ --hash=sha256:de2ea4b5833625383e464549fec1bc395c1bdeeb5f25c4a3a82b5a8c756ec22f \
+ --hash=sha256:de55b766c7aa2e2a3092c51e0483d700341182f08e67c63630d5b6f200bb28e5 \
+ --hash=sha256:df8b1c11f177bc2313ec4b2d46baec87a5f3e71fc8b45dab2ee7cae86d9aba14 \
+ --hash=sha256:e03eab0a8677fa80d646b5ddece1cbeaf556c313dcfac435ba11f107ba117b5d \
+ --hash=sha256:e221cf152cff04059d011ee126477f0d9588303eb57e88923578ace7baad17f9 \
+ --hash=sha256:e31ae45bc2e29f6b2abd0de1cc3b9d5205aa847cafaecb8af1476a609a2f6eb7 \
+ --hash=sha256:edae79245293e15384b51f88b00613ba9f7198016a5948b5dddf4917d4d26382 \
+ --hash=sha256:f1e22e8c4419538cb197e4dd60acc919d7696e5ef98ee4da4e01d3f8cfa4cc5a \
+ --hash=sha256:f3a2b4222ce6b60e2e8b337bb9596923045681d71e5a082783484d845390938e \
+ --hash=sha256:f6a16c31041f09ead72d69f583767292f750d24913dadacf5756b966aacb3f1a \
+ --hash=sha256:f75c7ab1f9e4aca5414ed4d8e5c0e303a34f4421f8a0d47a4d019ceff0ab6af4 \
+ --hash=sha256:f79fc4fc25f1c8698ff97788206bb3c2598949bfe0fef03d299eb1b5356ada99 \
+ --hash=sha256:f7f5baafcc48261359e14bcd6d9bff6d4b28d9103847c9e136694cb0501aef87 \
+ --hash=sha256:fc48c783f9c87e60831201f2cce7f3b2e4846bf4d8728eabe54d60700b318a0b
+ # via cryptography
+charset-normalizer==3.3.2 \
+ --hash=sha256:06435b539f889b1f6f4ac1758871aae42dc3a8c0e24ac9e60c2384973ad73027 \
+ --hash=sha256:06a81e93cd441c56a9b65d8e1d043daeb97a3d0856d177d5c90ba85acb3db087 \
+ --hash=sha256:0a55554a2fa0d408816b3b5cedf0045f4b8e1a6065aec45849de2d6f3f8e9786 \
+ --hash=sha256:0b2b64d2bb6d3fb9112bafa732def486049e63de9618b5843bcdd081d8144cd8 \
+ --hash=sha256:10955842570876604d404661fbccbc9c7e684caf432c09c715ec38fbae45ae09 \
+ --hash=sha256:122c7fa62b130ed55f8f285bfd56d5f4b4a5b503609d181f9ad85e55c89f4185 \
+ --hash=sha256:1ceae2f17a9c33cb48e3263960dc5fc8005351ee19db217e9b1bb15d28c02574 \
+ --hash=sha256:1d3193f4a680c64b4b6a9115943538edb896edc190f0b222e73761716519268e \
+ --hash=sha256:1f79682fbe303db92bc2b1136016a38a42e835d932bab5b3b1bfcfbf0640e519 \
+ --hash=sha256:2127566c664442652f024c837091890cb1942c30937add288223dc895793f898 \
+ --hash=sha256:22afcb9f253dac0696b5a4be4a1c0f8762f8239e21b99680099abd9b2b1b2269 \
+ --hash=sha256:25baf083bf6f6b341f4121c2f3c548875ee6f5339300e08be3f2b2ba1721cdd3 \
+ --hash=sha256:2e81c7b9c8979ce92ed306c249d46894776a909505d8f5a4ba55b14206e3222f \
+ --hash=sha256:3287761bc4ee9e33561a7e058c72ac0938c4f57fe49a09eae428fd88aafe7bb6 \
+ --hash=sha256:34d1c8da1e78d2e001f363791c98a272bb734000fcef47a491c1e3b0505657a8 \
+ --hash=sha256:37e55c8e51c236f95b033f6fb391d7d7970ba5fe7ff453dad675e88cf303377a \
+ --hash=sha256:3d47fa203a7bd9c5b6cee4736ee84ca03b8ef23193c0d1ca99b5089f72645c73 \
+ --hash=sha256:3e4d1f6587322d2788836a99c69062fbb091331ec940e02d12d179c1d53e25fc \
+ --hash=sha256:42cb296636fcc8b0644486d15c12376cb9fa75443e00fb25de0b8602e64c1714 \
+ --hash=sha256:45485e01ff4d3630ec0d9617310448a8702f70e9c01906b0d0118bdf9d124cf2 \
+ --hash=sha256:4a78b2b446bd7c934f5dcedc588903fb2f5eec172f3d29e52a9096a43722adfc \
+ --hash=sha256:4ab2fe47fae9e0f9dee8c04187ce5d09f48eabe611be8259444906793ab7cbce \
+ --hash=sha256:4d0d1650369165a14e14e1e47b372cfcb31d6ab44e6e33cb2d4e57265290044d \
+ --hash=sha256:549a3a73da901d5bc3ce8d24e0600d1fa85524c10287f6004fbab87672bf3e1e \
+ --hash=sha256:55086ee1064215781fff39a1af09518bc9255b50d6333f2e4c74ca09fac6a8f6 \
+ --hash=sha256:572c3763a264ba47b3cf708a44ce965d98555f618ca42c926a9c1616d8f34269 \
+ --hash=sha256:573f6eac48f4769d667c4442081b1794f52919e7edada77495aaed9236d13a96 \
+ --hash=sha256:5b4c145409bef602a690e7cfad0a15a55c13320ff7a3ad7ca59c13bb8ba4d45d \
+ --hash=sha256:6463effa3186ea09411d50efc7d85360b38d5f09b870c48e4600f63af490e56a \
+ --hash=sha256:65f6f63034100ead094b8744b3b97965785388f308a64cf8d7c34f2f2e5be0c4 \
+ --hash=sha256:663946639d296df6a2bb2aa51b60a2454ca1cb29835324c640dafb5ff2131a77 \
+ --hash=sha256:6897af51655e3691ff853668779c7bad41579facacf5fd7253b0133308cf000d \
+ --hash=sha256:68d1f8a9e9e37c1223b656399be5d6b448dea850bed7d0f87a8311f1ff3dabb0 \
+ --hash=sha256:6ac7ffc7ad6d040517be39eb591cac5ff87416c2537df6ba3cba3bae290c0fed \
+ --hash=sha256:6b3251890fff30ee142c44144871185dbe13b11bab478a88887a639655be1068 \
+ --hash=sha256:6c4caeef8fa63d06bd437cd4bdcf3ffefe6738fb1b25951440d80dc7df8c03ac \
+ --hash=sha256:6ef1d82a3af9d3eecdba2321dc1b3c238245d890843e040e41e470ffa64c3e25 \
+ --hash=sha256:753f10e867343b4511128c6ed8c82f7bec3bd026875576dfd88483c5c73b2fd8 \
+ --hash=sha256:7cd13a2e3ddeed6913a65e66e94b51d80a041145a026c27e6bb76c31a853c6ab \
+ --hash=sha256:7ed9e526742851e8d5cc9e6cf41427dfc6068d4f5a3bb03659444b4cabf6bc26 \
+ --hash=sha256:7f04c839ed0b6b98b1a7501a002144b76c18fb1c1850c8b98d458ac269e26ed2 \
+ --hash=sha256:802fe99cca7457642125a8a88a084cef28ff0cf9407060f7b93dca5aa25480db \
+ --hash=sha256:80402cd6ee291dcb72644d6eac93785fe2c8b9cb30893c1af5b8fdd753b9d40f \
+ --hash=sha256:8465322196c8b4d7ab6d1e049e4c5cb460d0394da4a27d23cc242fbf0034b6b5 \
+ --hash=sha256:86216b5cee4b06df986d214f664305142d9c76df9b6512be2738aa72a2048f99 \
+ --hash=sha256:87d1351268731db79e0f8e745d92493ee2841c974128ef629dc518b937d9194c \
+ --hash=sha256:8bdb58ff7ba23002a4c5808d608e4e6c687175724f54a5dade5fa8c67b604e4d \
+ --hash=sha256:8c622a5fe39a48f78944a87d4fb8a53ee07344641b0562c540d840748571b811 \
+ --hash=sha256:8d756e44e94489e49571086ef83b2bb8ce311e730092d2c34ca8f7d925cb20aa \
+ --hash=sha256:8f4a014bc36d3c57402e2977dada34f9c12300af536839dc38c0beab8878f38a \
+ --hash=sha256:9063e24fdb1e498ab71cb7419e24622516c4a04476b17a2dab57e8baa30d6e03 \
+ --hash=sha256:90d558489962fd4918143277a773316e56c72da56ec7aa3dc3dbbe20fdfed15b \
+ --hash=sha256:923c0c831b7cfcb071580d3f46c4baf50f174be571576556269530f4bbd79d04 \
+ --hash=sha256:95f2a5796329323b8f0512e09dbb7a1860c46a39da62ecb2324f116fa8fdc85c \
+ --hash=sha256:96b02a3dc4381e5494fad39be677abcb5e6634bf7b4fa83a6dd3112607547001 \
+ --hash=sha256:9f96df6923e21816da7e0ad3fd47dd8f94b2a5ce594e00677c0013018b813458 \
+ --hash=sha256:a10af20b82360ab00827f916a6058451b723b4e65030c5a18577c8b2de5b3389 \
+ --hash=sha256:a50aebfa173e157099939b17f18600f72f84eed3049e743b68ad15bd69b6bf99 \
+ --hash=sha256:a981a536974bbc7a512cf44ed14938cf01030a99e9b3a06dd59578882f06f985 \
+ --hash=sha256:a9a8e9031d613fd2009c182b69c7b2c1ef8239a0efb1df3f7c8da66d5dd3d537 \
+ --hash=sha256:ae5f4161f18c61806f411a13b0310bea87f987c7d2ecdbdaad0e94eb2e404238 \
+ --hash=sha256:aed38f6e4fb3f5d6bf81bfa990a07806be9d83cf7bacef998ab1a9bd660a581f \
+ --hash=sha256:b01b88d45a6fcb69667cd6d2f7a9aeb4bf53760d7fc536bf679ec94fe9f3ff3d \
+ --hash=sha256:b261ccdec7821281dade748d088bb6e9b69e6d15b30652b74cbbac25e280b796 \
+ --hash=sha256:b2b0a0c0517616b6869869f8c581d4eb2dd83a4d79e0ebcb7d373ef9956aeb0a \
+ --hash=sha256:b4a23f61ce87adf89be746c8a8974fe1c823c891d8f86eb218bb957c924bb143 \
+ --hash=sha256:bd8f7df7d12c2db9fab40bdd87a7c09b1530128315d047a086fa3ae3435cb3a8 \
+ --hash=sha256:beb58fe5cdb101e3a055192ac291b7a21e3b7ef4f67fa1d74e331a7f2124341c \
+ --hash=sha256:c002b4ffc0be611f0d9da932eb0f704fe2602a9a949d1f738e4c34c75b0863d5 \
+ --hash=sha256:c083af607d2515612056a31f0a8d9e0fcb5876b7bfc0abad3ecd275bc4ebc2d5 \
+ --hash=sha256:c180f51afb394e165eafe4ac2936a14bee3eb10debc9d9e4db8958fe36afe711 \
+ --hash=sha256:c235ebd9baae02f1b77bcea61bce332cb4331dc3617d254df3323aa01ab47bd4 \
+ --hash=sha256:cd70574b12bb8a4d2aaa0094515df2463cb429d8536cfb6c7ce983246983e5a6 \
+ --hash=sha256:d0eccceffcb53201b5bfebb52600a5fb483a20b61da9dbc885f8b103cbe7598c \
+ --hash=sha256:d965bba47ddeec8cd560687584e88cf699fd28f192ceb452d1d7ee807c5597b7 \
+ --hash=sha256:db364eca23f876da6f9e16c9da0df51aa4f104a972735574842618b8c6d999d4 \
+ --hash=sha256:ddbb2551d7e0102e7252db79ba445cdab71b26640817ab1e3e3648dad515003b \
+ --hash=sha256:deb6be0ac38ece9ba87dea880e438f25ca3eddfac8b002a2ec3d9183a454e8ae \
+ --hash=sha256:e06ed3eb3218bc64786f7db41917d4e686cc4856944f53d5bdf83a6884432e12 \
+ --hash=sha256:e27ad930a842b4c5eb8ac0016b0a54f5aebbe679340c26101df33424142c143c \
+ --hash=sha256:e537484df0d8f426ce2afb2d0f8e1c3d0b114b83f8850e5f2fbea0e797bd82ae \
+ --hash=sha256:eb00ed941194665c332bf8e078baf037d6c35d7c4f3102ea2d4f16ca94a26dc8 \
+ --hash=sha256:eb6904c354526e758fda7167b33005998fb68c46fbc10e013ca97f21ca5c8887 \
+ --hash=sha256:eb8821e09e916165e160797a6c17edda0679379a4be5c716c260e836e122f54b \
+ --hash=sha256:efcb3f6676480691518c177e3b465bcddf57cea040302f9f4e6e191af91174d4 \
+ --hash=sha256:f27273b60488abe721a075bcca6d7f3964f9f6f067c8c4c605743023d7d3944f \
+ --hash=sha256:f30c3cb33b24454a82faecaf01b19c18562b1e89558fb6c56de4d9118a032fd5 \
+ --hash=sha256:fb69256e180cb6c8a894fee62b3afebae785babc1ee98b81cdf68bbca1987f33 \
+ --hash=sha256:fd1abc0d89e30cc4e02e4064dc67fcc51bd941eb395c502aac3ec19fab46b519 \
+ --hash=sha256:ff8fa367d09b717b2a17a052544193ad76cd49979c805768879cb63d9ca50561
# via requests
-click==8.1.3 \
- --hash=sha256:7682dc8afb30297001674575ea00d1814d808d6a36af415a82bd481d37ba7b8e \
- --hash=sha256:bb4d8133cb15a609f44e8213d9b391b0809795062913b383c62be0ee95b1db48
- # via mkdocs
-contourpy==1.2.1 \
- --hash=sha256:00e5388f71c1a0610e6fe56b5c44ab7ba14165cdd6d695429c5cd94021e390b2 \
- --hash=sha256:10a37ae557aabf2509c79715cd20b62e4c7c28b8cd62dd7d99e5ed3ce28c3fd9 \
- --hash=sha256:11959f0ce4a6f7b76ec578576a0b61a28bdc0696194b6347ba3f1c53827178b9 \
- --hash=sha256:187fa1d4c6acc06adb0fae5544c59898ad781409e61a926ac7e84b8f276dcef4 \
- --hash=sha256:1a07fc092a4088ee952ddae19a2b2a85757b923217b7eed584fdf25f53a6e7ce \
- --hash=sha256:1cac0a8f71a041aa587410424ad46dfa6a11f6149ceb219ce7dd48f6b02b87a7 \
- --hash=sha256:1d59e739ab0e3520e62a26c60707cc3ab0365d2f8fecea74bfe4de72dc56388f \
- --hash=sha256:2855c8b0b55958265e8b5888d6a615ba02883b225f2227461aa9127c578a4922 \
- --hash=sha256:2e785e0f2ef0d567099b9ff92cbfb958d71c2d5b9259981cd9bee81bd194c9a4 \
- --hash=sha256:309be79c0a354afff9ff7da4aaed7c3257e77edf6c1b448a779329431ee79d7e \
- --hash=sha256:39f3ecaf76cd98e802f094e0d4fbc6dc9c45a8d0c4d185f0f6c2234e14e5f75b \
- --hash=sha256:457499c79fa84593f22454bbd27670227874cd2ff5d6c84e60575c8b50a69619 \
- --hash=sha256:49e70d111fee47284d9dd867c9bb9a7058a3c617274900780c43e38d90fe1205 \
- --hash=sha256:4c75507d0a55378240f781599c30e7776674dbaf883a46d1c90f37e563453480 \
- --hash=sha256:4c863140fafc615c14a4bf4efd0f4425c02230eb8ef02784c9a156461e62c965 \
- --hash=sha256:4d8908b3bee1c889e547867ca4cdc54e5ab6be6d3e078556814a22457f49423c \
- --hash=sha256:5b9eb0ca724a241683c9685a484da9d35c872fd42756574a7cfbf58af26677fd \
- --hash=sha256:6022cecf8f44e36af10bd9118ca71f371078b4c168b6e0fab43d4a889985dbb5 \
- --hash=sha256:6150ffa5c767bc6332df27157d95442c379b7dce3a38dff89c0f39b63275696f \
- --hash=sha256:62828cada4a2b850dbef89c81f5a33741898b305db244904de418cc957ff05dc \
- --hash=sha256:7b4182299f251060996af5249c286bae9361fa8c6a9cda5efc29fe8bfd6062ec \
- --hash=sha256:94b34f32646ca0414237168d68a9157cb3889f06b096612afdd296003fdd32fd \
- --hash=sha256:9ce6889abac9a42afd07a562c2d6d4b2b7134f83f18571d859b25624a331c90b \
- --hash=sha256:9cffe0f850e89d7c0012a1fb8730f75edd4320a0a731ed0c183904fe6ecfc3a9 \
- --hash=sha256:a12a813949e5066148712a0626895c26b2578874e4cc63160bb007e6df3436fe \
- --hash=sha256:a1eea9aecf761c661d096d39ed9026574de8adb2ae1c5bd7b33558af884fb2ce \
- --hash=sha256:a31f94983fecbac95e58388210427d68cd30fe8a36927980fab9c20062645609 \
- --hash=sha256:ac58bdee53cbeba2ecad824fa8159493f0bf3b8ea4e93feb06c9a465d6c87da8 \
- --hash=sha256:af3f4485884750dddd9c25cb7e3915d83c2db92488b38ccb77dd594eac84c4a0 \
- --hash=sha256:b33d2bc4f69caedcd0a275329eb2198f560b325605810895627be5d4b876bf7f \
- --hash=sha256:b59c0ffceff8d4d3996a45f2bb6f4c207f94684a96bf3d9728dbb77428dd8cb8 \
- --hash=sha256:bb6834cbd983b19f06908b45bfc2dad6ac9479ae04abe923a275b5f48f1a186b \
- --hash=sha256:bd3db01f59fdcbce5b22afad19e390260d6d0222f35a1023d9adc5690a889364 \
- --hash=sha256:bd7c23df857d488f418439686d3b10ae2fbf9bc256cd045b37a8c16575ea1040 \
- --hash=sha256:c2528d60e398c7c4c799d56f907664673a807635b857df18f7ae64d3e6ce2d9f \
- --hash=sha256:d31a63bc6e6d87f77d71e1abbd7387ab817a66733734883d1fc0021ed9bfa083 \
- --hash=sha256:d4492d82b3bc7fbb7e3610747b159869468079fe149ec5c4d771fa1f614a14df \
- --hash=sha256:ddcb8581510311e13421b1f544403c16e901c4e8f09083c881fab2be80ee31ba \
- --hash=sha256:e1d59258c3c67c865435d8fbeb35f8c59b8bef3d6f46c1f29f6123556af28445 \
- --hash=sha256:eb3315a8a236ee19b6df481fc5f997436e8ade24a9f03dfdc6bd490fea20c6da \
- --hash=sha256:ef2b055471c0eb466033760a521efb9d8a32b99ab907fc8358481a1dd29e3bd3 \
- --hash=sha256:ef5adb9a3b1d0c645ff694f9bca7702ec2c70f4d734f9922ea34de02294fdf72 \
- --hash=sha256:f32c38afb74bd98ce26de7cc74a67b40afb7b05aae7b42924ea990d51e4dac02 \
- --hash=sha256:fe0ccca550bb8e5abc22f530ec0466136379c01321fd94f30a22231e8a48d985
+chex==0.1.86 \
+ --hash=sha256:251c20821092323a3d9c28e1cf80e4a58180978bec368f531949bd9847eee568 \
+ --hash=sha256:e8b0f96330eba4144659e1617c0f7a57b161e8cbb021e55c6d5056c7378091d1
+ # via
+ # flashbax
+ # optax
+click==8.1.7 \
+ --hash=sha256:ae74fb96c20a0277a1d615f1e4d73c8414f5a98db8b799a7931d1582f3390c28 \
+ --hash=sha256:ca9853ad459e787e2192211578cc907e7594e294c7ccc834310722b41b9ca6de
+ # via
+ # aim
+ # flask
+ # mkdocs
+ # tensorflow-datasets
+ # uvicorn
+cloudpickle==3.1.0 \
+ --hash=sha256:81a929b6e3c7335c863c771d673d105f02efdb89dfaba0c90495d1c64796601b \
+ --hash=sha256:fe11acda67f61aaaec473e3afe030feb131d78a43461b718185363384f1ba12e
+ # via tensorflow-probability
+clu==0.0.12 \
+ --hash=sha256:0d183e7d25f7dd0700444510a264e24700e2f068bdabd199ed22866f7e54edba \
+ --hash=sha256:f71eaa1afbd30f57f7709257ba7e1feb8ad5c1c3dcae3606672a138678bb3ce4
+ # via -r tools/python/requirements.txt
+contextlib2==21.6.0 \
+ --hash=sha256:3fbdb64466afd23abaf6c977627b75b6139a5a3e8ce38405c5b413aed7a0471f \
+ --hash=sha256:ab1e2bfe1d01d968e1b7e8d9023bc51ef3509bba217bb730cee3827e1ee82869
+ # via ml-collections
+contourpy==1.3.0 \
+ --hash=sha256:00ccd0dbaad6d804ab259820fa7cb0b8036bda0686ef844d24125d8287178ce0 \
+ --hash=sha256:0be4d8425bfa755e0fd76ee1e019636ccc7c29f77a7c86b4328a9eb6a26d0639 \
+ --hash=sha256:0dce35502151b6bd35027ac39ba6e5a44be13a68f55735c3612c568cac3805fd \
+ --hash=sha256:0fa4c02abe6c446ba70d96ece336e621efa4aecae43eaa9b030ae5fb92b309ad \
+ --hash=sha256:14e262f67bd7e6eb6880bc564dcda30b15e351a594657e55b7eec94b6ef72843 \
+ --hash=sha256:167d6c890815e1dac9536dca00828b445d5d0df4d6a8c6adb4a7ec3166812fa8 \
+ --hash=sha256:1ec4dc6bf570f5b22ed0d7efba0dfa9c5b9e0431aeea7581aa217542d9e809a4 \
+ --hash=sha256:303c252947ab4b14c08afeb52375b26781ccd6a5ccd81abcdfc1fafd14cf93c1 \
+ --hash=sha256:31cd3a85dbdf1fc002280c65caa7e2b5f65e4a973fcdf70dd2fdcb9868069294 \
+ --hash=sha256:32b238b3b3b649e09ce9aaf51f0c261d38644bdfa35cbaf7b263457850957a84 \
+ --hash=sha256:33c92cdae89ec5135d036e7218e69b0bb2851206077251f04a6c4e0e21f03927 \
+ --hash=sha256:345af746d7766821d05d72cb8f3845dfd08dd137101a2cb9b24de277d716def8 \
+ --hash=sha256:3634b5385c6716c258d0419c46d05c8aa7dc8cb70326c9a4fb66b69ad2b52e09 \
+ --hash=sha256:364174c2a76057feef647c802652f00953b575723062560498dc7930fc9b1cb7 \
+ --hash=sha256:36e0cff201bcb17a0a8ecc7f454fe078437fa6bda730e695a92f2d9932bd507f \
+ --hash=sha256:36f965570cff02b874773c49bfe85562b47030805d7d8360748f3eca570f4cab \
+ --hash=sha256:3bb3808858a9dc68f6f03d319acd5f1b8a337e6cdda197f02f4b8ff67ad2057b \
+ --hash=sha256:3e1c7fa44aaae40a2247e2e8e0627f4bea3dd257014764aa644f319a5f8600e3 \
+ --hash=sha256:3faeb2998e4fcb256542e8a926d08da08977f7f5e62cf733f3c211c2a5586223 \
+ --hash=sha256:420d39daa61aab1221567b42eecb01112908b2cab7f1b4106a52caaec8d36973 \
+ --hash=sha256:4553c421929ec95fb07b3aaca0fae668b2eb5a5203d1217ca7c34c063c53d087 \
+ --hash=sha256:4865cd1d419e0c7a7bf6de1777b185eebdc51470800a9f42b9e9decf17762081 \
+ --hash=sha256:4cfb5c62ce023dfc410d6059c936dcf96442ba40814aefbfa575425a3a7f19dc \
+ --hash=sha256:4d63ee447261e963af02642ffcb864e5a2ee4cbfd78080657a9880b8b1868e18 \
+ --hash=sha256:570ef7cf892f0afbe5b2ee410c507ce12e15a5fa91017a0009f79f7d93a1268f \
+ --hash=sha256:637f674226be46f6ba372fd29d9523dd977a291f66ab2a74fbeb5530bb3f445d \
+ --hash=sha256:68a32389b06b82c2fdd68276148d7b9275b5f5cf13e5417e4252f6d1a34f72a2 \
+ --hash=sha256:69375194457ad0fad3a839b9e29aa0b0ed53bb54db1bfb6c3ae43d111c31ce41 \
+ --hash=sha256:6cb6cc968059db9c62cb35fbf70248f40994dfcd7aa10444bbf8b3faeb7c2d67 \
+ --hash=sha256:710a26b3dc80c0e4febf04555de66f5fd17e9cf7170a7b08000601a10570bda6 \
+ --hash=sha256:732896af21716b29ab3e988d4ce14bc5133733b85956316fb0c56355f398099b \
+ --hash=sha256:75ee7cb1a14c617f34a51d11fa7524173e56551646828353c4af859c56b766e2 \
+ --hash=sha256:76a896b2f195b57db25d6b44e7e03f221d32fe318d03ede41f8b4d9ba1bff53c \
+ --hash=sha256:76c905ef940a4474a6289c71d53122a4f77766eef23c03cd57016ce19d0f7b42 \
+ --hash=sha256:7a52040312b1a858b5e31ef28c2e865376a386c60c0e248370bbea2d3f3b760d \
+ --hash=sha256:7ffa0db17717a8ffb127efd0c95a4362d996b892c2904db72428d5b52e1938a4 \
+ --hash=sha256:81cb5ed4952aae6014bc9d0421dec7c5835c9c8c31cdf51910b708f548cf58e5 \
+ --hash=sha256:834e0cfe17ba12f79963861e0f908556b2cedd52e1f75e6578801febcc6a9f49 \
+ --hash=sha256:87ddffef1dbe5e669b5c2440b643d3fdd8622a348fe1983fad7a0f0ccb1cd67b \
+ --hash=sha256:880ea32e5c774634f9fcd46504bf9f080a41ad855f4fef54f5380f5133d343c7 \
+ --hash=sha256:8ca947601224119117f7c19c9cdf6b3ab54c5726ef1d906aa4a69dfb6dd58102 \
+ --hash=sha256:90f73a5116ad1ba7174341ef3ea5c3150ddf20b024b98fb0c3b29034752c8aeb \
+ --hash=sha256:92f8557cbb07415a4d6fa191f20fd9d2d9eb9c0b61d1b2f52a8926e43c6e9af7 \
+ --hash=sha256:94e848a6b83da10898cbf1311a815f770acc9b6a3f2d646f330d57eb4e87592e \
+ --hash=sha256:9c0da700bf58f6e0b65312d0a5e695179a71d0163957fa381bb3c1f72972537c \
+ --hash=sha256:a11077e395f67ffc2c44ec2418cfebed032cd6da3022a94fc227b6faf8e2acb8 \
+ --hash=sha256:aea348f053c645100612b333adc5983d87be69acdc6d77d3169c090d3b01dc35 \
+ --hash=sha256:b11b39aea6be6764f84360fce6c82211a9db32a7c7de8fa6dd5397cf1d079c3b \
+ --hash=sha256:c6c7c2408b7048082932cf4e641fa3b8ca848259212f51c8c59c45aa7ac18f14 \
+ --hash=sha256:c6ec93afeb848a0845a18989da3beca3eec2c0f852322efe21af1931147d12cb \
+ --hash=sha256:cacd81e2d4b6f89c9f8a5b69b86490152ff39afc58a95af002a398273e5ce589 \
+ --hash=sha256:d402880b84df3bec6eab53cd0cf802cae6a2ef9537e70cf75e91618a3801c20c \
+ --hash=sha256:d51fca85f9f7ad0b65b4b9fe800406d0d77017d7270d31ec3fb1cc07358fdea0 \
+ --hash=sha256:d73f659398a0904e125280836ae6f88ba9b178b2fed6884f3b1f95b989d2c8da \
+ --hash=sha256:d78ab28a03c854a873787a0a42254a0ccb3cb133c672f645c9f9c8f3ae9d0800 \
+ --hash=sha256:da84c537cb8b97d153e9fb208c221c45605f73147bd4cadd23bdae915042aad6 \
+ --hash=sha256:dbc4c3217eee163fa3984fd1567632b48d6dfd29216da3ded3d7b844a8014a66 \
+ --hash=sha256:e12968fdfd5bb45ffdf6192a590bd8ddd3ba9e58360b29683c6bb71a7b41edca \
+ --hash=sha256:e1fd23e9d01591bab45546c089ae89d926917a66dceb3abcf01f6105d927e2cb \
+ --hash=sha256:e8134301d7e204c88ed7ab50028ba06c683000040ede1d617298611f9dc6240c \
+ --hash=sha256:eb8b141bb00fa977d9122636b16aa67d37fd40a3d8b52dd837e536d64b9a4d06 \
+ --hash=sha256:eca7e17a65f72a5133bdbec9ecf22401c62bcf4821361ef7811faee695799779 \
+ --hash=sha256:f317576606de89da6b7e0861cf6061f6146ead3528acabff9236458a6ba467f8 \
+ --hash=sha256:fd2a0fc506eccaaa7595b7e1418951f213cf8255be2600f1ea1b61e46a60c55f \
+ --hash=sha256:fe41b41505a5a33aeaed2a613dccaeaa74e0e3ead6dd6fd3a118fb471644fd6c
# via
# bokeh
# matplotlib
-cycler==0.11.0 \
- --hash=sha256:3a27e95f763a428a739d2add979fa7494c912a32c17c4c38c4d5f082cad165a3 \
- --hash=sha256:9c87405839a19696e837b3b818fed3f5f69f16f1eec1a1ad77e043dcea9c772f
+cryptography==43.0.1 \
+ --hash=sha256:014f58110f53237ace6a408b5beb6c427b64e084eb451ef25a28308270086494 \
+ --hash=sha256:1bbcce1a551e262dfbafb6e6252f1ae36a248e615ca44ba302df077a846a8806 \
+ --hash=sha256:203e92a75716d8cfb491dc47c79e17d0d9207ccffcbcb35f598fbe463ae3444d \
+ --hash=sha256:27e613d7077ac613e399270253259d9d53872aaf657471473ebfc9a52935c062 \
+ --hash=sha256:2bd51274dcd59f09dd952afb696bf9c61a7a49dfc764c04dd33ef7a6b502a1e2 \
+ --hash=sha256:38926c50cff6f533f8a2dae3d7f19541432610d114a70808f0926d5aaa7121e4 \
+ --hash=sha256:511f4273808ab590912a93ddb4e3914dfd8a388fed883361b02dea3791f292e1 \
+ --hash=sha256:58d4e9129985185a06d849aa6df265bdd5a74ca6e1b736a77959b498e0505b85 \
+ --hash=sha256:5b43d1ea6b378b54a1dc99dd8a2b5be47658fe9a7ce0a58ff0b55f4b43ef2b84 \
+ --hash=sha256:61ec41068b7b74268fa86e3e9e12b9f0c21fcf65434571dbb13d954bceb08042 \
+ --hash=sha256:666ae11966643886c2987b3b721899d250855718d6d9ce41b521252a17985f4d \
+ --hash=sha256:68aaecc4178e90719e95298515979814bda0cbada1256a4485414860bd7ab962 \
+ --hash=sha256:7c05650fe8023c5ed0d46793d4b7d7e6cd9c04e68eabe5b0aeea836e37bdcec2 \
+ --hash=sha256:80eda8b3e173f0f247f711eef62be51b599b5d425c429b5d4ca6a05e9e856baa \
+ --hash=sha256:8385d98f6a3bf8bb2d65a73e17ed87a3ba84f6991c155691c51112075f9ffc5d \
+ --hash=sha256:88cce104c36870d70c49c7c8fd22885875d950d9ee6ab54df2745f83ba0dc365 \
+ --hash=sha256:9d3cdb25fa98afdd3d0892d132b8d7139e2c087da1712041f6b762e4f807cc96 \
+ --hash=sha256:a575913fb06e05e6b4b814d7f7468c2c660e8bb16d8d5a1faf9b33ccc569dd47 \
+ --hash=sha256:ac119bb76b9faa00f48128b7f5679e1d8d437365c5d26f1c2c3f0da4ce1b553d \
+ --hash=sha256:c1332724be35d23a854994ff0b66530119500b6053d0bd3363265f7e5e77288d \
+ --hash=sha256:d03a475165f3134f773d1388aeb19c2d25ba88b6a9733c5c590b9ff7bbfa2e0c \
+ --hash=sha256:d75601ad10b059ec832e78823b348bfa1a59f6b8d545db3a24fd44362a1564cb \
+ --hash=sha256:de41fd81a41e53267cb020bb3a7212861da53a7d39f863585d13ea11049cf277 \
+ --hash=sha256:e710bf40870f4db63c3d7d929aa9e09e4e7ee219e703f949ec4073b4294f6172 \
+ --hash=sha256:ea25acb556320250756e53f9e20a4177515f012c9eaea17eb7587a8c4d8ae034 \
+ --hash=sha256:f98bf604c82c416bc829e490c700ca1553eafdf2912a91e23a79d97d9801372a \
+ --hash=sha256:fba1007b3ef89946dbbb515aeeb41e30203b004f0b4b00e5e16078b518563289
+ # via aim
+cycler==0.12.1 \
+ --hash=sha256:85cef7cff222d8644161529808465972e51340599459b8ac3ccbac5a854e0d30 \
+ --hash=sha256:88bb128f02ba341da8ef447245a9e138fae777f6a23943da4540077d3601eb1c
# via matplotlib
-fonttools==4.38.0 \
- --hash=sha256:2bb244009f9bf3fa100fc3ead6aeb99febe5985fa20afbfbaa2f8946c2fbdaf1 \
- --hash=sha256:820466f43c8be8c3009aef8b87e785014133508f0de64ec469e4efb643ae54fb
+decorator==5.1.1 \
+ --hash=sha256:637996211036b6385ef91435e4fae22989472f9d571faba8927ba8253acbc330 \
+ --hash=sha256:b8c3f85900b9dc423225913c5aace94729fe1fa9763b38939a95226f02d37186
+ # via tensorflow-probability
+dm-tree==0.1.8 \
+ --hash=sha256:054b461f8176f4bce7a21f7b1870f873a1ced3bdbe1282c816c550bb43c71fa6 \
+ --hash=sha256:09964470f76a5201aff2e8f9b26842976de7889300676f927930f6285e256760 \
+ --hash=sha256:0d3172394079a86c3a759179c65f64c48d1a42b89495fcf38976d11cc3bb952c \
+ --hash=sha256:0e9620ccf06393eb6b613b5e366469304622d4ea96ae6540b28a33840e6c89cf \
+ --hash=sha256:0fcaabbb14e7980377439e7140bd05552739ca5e515ecb3119f234acee4b9430 \
+ --hash=sha256:1607ce49aa42f010d1e5e616d92ce899d66835d4d8bea49679582435285515de \
+ --hash=sha256:181c35521d480d0365f39300542cb6cd7fd2b77351bb43d7acfda15aef63b317 \
+ --hash=sha256:1d7c26e431fc93cc7e0cba867eb000db6a05f6f2b25af11ac4e9dada88fc5bca \
+ --hash=sha256:1fe962015b2fe1282892b28ebe962faed53c7f98d942da9a4625cbf27baef913 \
+ --hash=sha256:250b692fb75f45f02e2f58fbef9ab338904ef334b90557565621fa251df267cf \
+ --hash=sha256:2869228d9c619074de501a3c10dc7f07c75422f8fab36ecdcb859b6f1b1ec3ef \
+ --hash=sha256:28c52cbf4f8b3dbd0beaedf44f69fa85eec5e9dede612e08035e06ada6ec9426 \
+ --hash=sha256:2f7915660f59c09068e428613c480150180df1060561fd0d1470684ae7007bd1 \
+ --hash=sha256:343a4a4ebaa127451ff971254a4be4084eb4bdc0b2513c32b46f6f728fd03f9e \
+ --hash=sha256:35cc164a79336bfcfafb47e5f297898359123bbd3330c1967f0c4994f9cf9f60 \
+ --hash=sha256:378cc8ad93c5fe3590f405a309980721f021c790ca1bdf9b15bb1d59daec57f5 \
+ --hash=sha256:39070ba268c0491af9fe7a58644d99e8b4f2cde6e5884ba3380bddc84ed43d5f \
+ --hash=sha256:435227cf3c5dc63f4de054cf3d00183790bd9ead4c3623138c74dde7f67f521b \
+ --hash=sha256:5483dca4d7eb1a0d65fe86d3b6a53ae717face83c1f17e0887b1a4a64ae5c410 \
+ --hash=sha256:694c3654cfd2a81552c08ec66bb5c4a3d48fa292b9a181880fb081c36c5b9134 \
+ --hash=sha256:75c5d528bb992981c20793b6b453e91560784215dffb8a5440ba999753c14ceb \
+ --hash=sha256:803bfc53b4659f447ac694dbd04235f94a73ef7c1fd1e0df7c84ac41e0bc963b \
+ --hash=sha256:81fce77f22a302d7a5968aebdf4efafef4def7ce96528719a354e6990dcd49c7 \
+ --hash=sha256:83b7764de0d855338abefc6e3ee9fe40d301668310aa3baea3f778ff051f4393 \
+ --hash=sha256:8c60a7eadab64c2278861f56bca320b2720f163dca9d7558103c3b77f2416571 \
+ --hash=sha256:8ed3564abed97c806db122c2d3e1a2b64c74a63debe9903aad795167cc301368 \
+ --hash=sha256:94d3f0826311f45ee19b75f5b48c99466e4218a0489e81c0f0167bda50cacf22 \
+ --hash=sha256:96a548a406a6fb15fe58f6a30a57ff2f2aafbf25f05afab00c8f5e5977b6c715 \
+ --hash=sha256:a5d819c38c03f0bb5b3b3703c60e4b170355a0fc6b5819325bf3d4ceb3ae7e80 \
+ --hash=sha256:ad16ceba90a56ec47cf45b21856d14962ac314787975ef786efb5e6e9ca75ec7 \
+ --hash=sha256:af4b3d372f2477dcd89a6e717e4a575ca35ccc20cc4454a8a4b6f8838a00672d \
+ --hash=sha256:b095ba4f8ca1ba19350fd53cf1f8f3eb0bd406aa28af64a6dfc86707b32a810a \
+ --hash=sha256:b9bd9b9ccb59409d33d51d84b7668010c04c2af7d4a371632874c1ca356cff3d \
+ --hash=sha256:b9f89a454e98806b44fe9d40ec9eee61f848388f7e79ac2371a55679bd5a3ac6 \
+ --hash=sha256:bb2d109f42190225112da899b9f3d46d0d5f26aef501c61e43529fe9322530b5 \
+ --hash=sha256:c0a94aba18a35457a1b5cd716fd7b46c5dafdc4cf7869b4bae665b91c4682a8e \
+ --hash=sha256:c5c8c12e3fda754ef6af94161bacdaeda816d941995fac415d6855c6c386af68 \
+ --hash=sha256:d1612fcaecd79023dbc6a6ae48d51a80beb5c385d6f3f6d71688e57bc8d07de8 \
+ --hash=sha256:d16e1f2a073604cfcc09f7131ae8d534674f43c3aef4c25742eae295bc60d04f \
+ --hash=sha256:d20f2faa3672b52e5013f4077117bfb99c4cfc0b445d3bde1584c34032b57436 \
+ --hash=sha256:d40fa4106ca6edc66760246a08f500ec0c85ef55c762fb4a363f6ee739ba02ee \
+ --hash=sha256:de287fabc464b8734be251e46e06aa9aa1001f34198da2b6ce07bd197172b9cb \
+ --hash=sha256:e4d714371bb08839e4e5e29024fc95832d9affe129825ef38836b143028bd144 \
+ --hash=sha256:ea9e59e0451e7d29aece402d9f908f2e2a80922bcde2ebfd5dcb07750fcbfee8 \
+ --hash=sha256:f7ac31b9aecccb2c6e1ab29706f6ded3eba0c2c69c770322c9c685929c3d6afb \
+ --hash=sha256:fa42a605d099ee7d41ba2b5fb75e21423951fd26e5d50583a00471238fb3021d
+ # via
+ # tensorflow-datasets
+ # tensorflow-probability
+etils[enp,epath,epy,etree]==1.5.2 \
+ --hash=sha256:6dc882d355e1e98a5d1a148d6323679dc47c9a5792939b9de72615aa4737eb0b \
+ --hash=sha256:ba6a3e1aff95c769130776aa176c11540637f5dd881f3b79172a5149b6b1c446
+ # via
+ # array-record
+ # clu
+ # optax
+ # orbax-checkpoint
+ # tensorflow-datasets
+exceptiongroup==1.2.2 \
+ --hash=sha256:3111b9d131c238bec2f8f516e123e14ba243563fb135d3fe885990585aa7795b \
+ --hash=sha256:47c2edf7c6738fafb49fd34290706d1a1a2f4d1c6df275526b62cbb4aa5393cc
+ # via anyio
+fastapi==0.115.0 \
+ --hash=sha256:17ea427674467486e997206a5ab25760f6b09e069f099b96f5b55a32fb6f1631 \
+ --hash=sha256:f93b4ca3529a8ebc6fc3fcf710e5efa8de3df9b41570958abf1d97d843138004
+ # via aim
+filelock==3.16.1 \
+ --hash=sha256:2082e5703d51fbf98ea75855d9d5527e33d8ff23099bec374a134febee6946b0 \
+ --hash=sha256:c249fbfcd5db47e5e2d6d62198e565475ee65e4831e2561c8e313fa7eb961435
+ # via aim
+flashbax==0.1.2 \
+ --hash=sha256:ac50b2580808ce63787da0ae240db14986e3404ade98a33335e6d7a5efe84859 \
+ --hash=sha256:b566ac5a78975b3e0a0a404a8844a26aa45e9cacfaad2829dcbcac2ffb3d5f7a
+ # via -r tools/python/requirements.txt
+flask==3.0.3 \
+ --hash=sha256:34e815dfaa43340d1d15a5c3a02b8476004037eb4840b34910c6e21679d288f3 \
+ --hash=sha256:ceb27b0af3823ea2737928a4d99d125a06175b8512c445cbd9a9ce200ef76842
+ # via -r tools/python/requirements.txt
+flatbuffers==24.3.25 \
+ --hash=sha256:8dbdec58f935f3765e4f7f3cf635ac3a77f83568138d6a2311f524ec96364812 \
+ --hash=sha256:de2ec5b203f21441716617f38443e0a8ebf3d25bf0d9c0bb0ce68fa00ad546a4
+ # via tensorflow
+flax==0.8.5 \
+ --hash=sha256:4a9cb7950ece54b0addaa73d77eba24e46138dbe783d01987be79d20ccb2b09b \
+ --hash=sha256:c96e46d1c48a300d010ebf5c4846f163bdd7acc6efff5ff2bfb1cb5b08aa65d8
+ # via
+ # -r tools/python/requirements.txt
+ # clu
+ # flashbax
+fonttools==4.53.1 \
+ --hash=sha256:02569e9a810f9d11f4ae82c391ebc6fb5730d95a0657d24d754ed7763fb2d122 \
+ --hash=sha256:0679a30b59d74b6242909945429dbddb08496935b82f91ea9bf6ad240ec23397 \
+ --hash=sha256:10f5e6c3510b79ea27bb1ebfcc67048cde9ec67afa87c7dd7efa5c700491ac7f \
+ --hash=sha256:2af40ae9cdcb204fc1d8f26b190aa16534fcd4f0df756268df674a270eab575d \
+ --hash=sha256:32f029c095ad66c425b0ee85553d0dc326d45d7059dbc227330fc29b43e8ba60 \
+ --hash=sha256:35250099b0cfb32d799fb5d6c651220a642fe2e3c7d2560490e6f1d3f9ae9169 \
+ --hash=sha256:3b3c8ebafbee8d9002bd8f1195d09ed2bd9ff134ddec37ee8f6a6375e6a4f0e8 \
+ --hash=sha256:4824c198f714ab5559c5be10fd1adf876712aa7989882a4ec887bf1ef3e00e31 \
+ --hash=sha256:5ff7e5e9bad94e3a70c5cd2fa27f20b9bb9385e10cddab567b85ce5d306ea923 \
+ --hash=sha256:651390c3b26b0c7d1f4407cad281ee7a5a85a31a110cbac5269de72a51551ba2 \
+ --hash=sha256:6e08f572625a1ee682115223eabebc4c6a2035a6917eac6f60350aba297ccadb \
+ --hash=sha256:6ed170b5e17da0264b9f6fae86073be3db15fa1bd74061c8331022bca6d09bab \
+ --hash=sha256:73379d3ffdeecb376640cd8ed03e9d2d0e568c9d1a4e9b16504a834ebadc2dfb \
+ --hash=sha256:75a157d8d26c06e64ace9df037ee93a4938a4606a38cb7ffaf6635e60e253b7a \
+ --hash=sha256:791b31ebbc05197d7aa096bbc7bd76d591f05905d2fd908bf103af4488e60670 \
+ --hash=sha256:7b6b35e52ddc8fb0db562133894e6ef5b4e54e1283dff606fda3eed938c36fc8 \
+ --hash=sha256:84ec3fb43befb54be490147b4a922b5314e16372a643004f182babee9f9c3407 \
+ --hash=sha256:8959a59de5af6d2bec27489e98ef25a397cfa1774b375d5787509c06659b3671 \
+ --hash=sha256:9dfdae43b7996af46ff9da520998a32b105c7f098aeea06b2226b30e74fbba88 \
+ --hash=sha256:9e6ceba2a01b448e36754983d376064730690401da1dd104ddb543519470a15f \
+ --hash=sha256:9efd176f874cb6402e607e4cc9b4a9cd584d82fc34a4b0c811970b32ba62501f \
+ --hash=sha256:a1c7c5aa18dd3b17995898b4a9b5929d69ef6ae2af5b96d585ff4005033d82f0 \
+ --hash=sha256:aae7bd54187e8bf7fd69f8ab87b2885253d3575163ad4d669a262fe97f0136cb \
+ --hash=sha256:b21952c092ffd827504de7e66b62aba26fdb5f9d1e435c52477e6486e9d128b2 \
+ --hash=sha256:b96cd370a61f4d083c9c0053bf634279b094308d52fdc2dd9a22d8372fdd590d \
+ --hash=sha256:becc5d7cb89c7b7afa8321b6bb3dbee0eec2b57855c90b3e9bf5fb816671fa7c \
+ --hash=sha256:bee32ea8765e859670c4447b0817514ca79054463b6b79784b08a8df3a4d78e3 \
+ --hash=sha256:c6e7170d675d12eac12ad1a981d90f118c06cf680b42a2d74c6c931e54b50719 \
+ --hash=sha256:c818c058404eb2bba05e728d38049438afd649e3c409796723dfc17cd3f08749 \
+ --hash=sha256:c8696544c964500aa9439efb6761947393b70b17ef4e82d73277413f291260a4 \
+ --hash=sha256:c9cd19cf4fe0595ebdd1d4915882b9440c3a6d30b008f3cc7587c1da7b95be5f \
+ --hash=sha256:d4d0096cb1ac7a77b3b41cd78c9b6bc4a400550e21dc7a92f2b5ab53ed74eb02 \
+ --hash=sha256:d92d3c2a1b39631a6131c2fa25b5406855f97969b068e7e08413325bc0afba58 \
+ --hash=sha256:da33440b1413bad53a8674393c5d29ce64d8c1a15ef8a77c642ffd900d07bfe1 \
+ --hash=sha256:e013aae589c1c12505da64a7d8d023e584987e51e62006e1bb30d72f26522c41 \
+ --hash=sha256:e128778a8e9bc11159ce5447f76766cefbd876f44bd79aff030287254e4752c4 \
+ --hash=sha256:e54f1bba2f655924c1138bbc7fa91abd61f45c68bd65ab5ed985942712864bbb \
+ --hash=sha256:e5b708073ea3d684235648786f5f6153a48dc8762cdfe5563c57e80787c29fbb \
+ --hash=sha256:e8bf06b94694251861ba7fdeea15c8ec0967f84c3d4143ae9daf42bbc7717fe3 \
+ --hash=sha256:f08df60fbd8d289152079a65da4e66a447efc1d5d5a4d3f299cdd39e3b2e4a7d \
+ --hash=sha256:f1f8758a2ad110bd6432203a344269f445a2907dc24ef6bccfd0ac4e14e0d71d \
+ --hash=sha256:f677ce218976496a587ab17140da141557beb91d2a5c1a14212c994093f2eae2
# via matplotlib
+fsspec==2024.6.1 \
+ --hash=sha256:3cb443f8bcd2efb31295a5b9fdb02aee81d8452c80d28f97a6d0959e6cee101e \
+ --hash=sha256:fad7d7e209dd4c1208e3bbfda706620e0da5142bebbd9c384afb95b07e798e49
+ # via etils
+gast==0.6.0 \
+ --hash=sha256:52b182313f7330389f72b069ba00f174cfe2a06411099547288839c6cbafbd54 \
+ --hash=sha256:88fc5300d32c7ac6ca7b515310862f71e6fdf2c029bbec7c66c0f5dd47b6b1fb
+ # via
+ # tensorflow
+ # tensorflow-probability
ghp-import==2.1.0 \
--hash=sha256:8337dd7b50877f163d4c0289bc1f1c7f127550241988d568c1db512c4324a619 \
--hash=sha256:9c535c4c61193c2df8871222567d7fd7e5014d835f97dc7b7439069e2413d343
@@ -139,21 +671,206 @@
--hash=sha256:88cee83dea8bddf73db7edbf5bd697237628389ef476c0a0ecad639c606189e5 \
--hash=sha256:b721edef6009eabc0b4d9f2619e153d2627a7b71a3657c8ed69f02ef7c78be97
# via -r tools/python/requirements.txt
-idna==3.4 \
- --hash=sha256:814f528e8dead7d329833b91c5faa87d60bf71824cd12a7530b5526063d02cb4 \
- --hash=sha256:90b77e79eaa3eba6de819a0c442c0b4ceefc341a7a2ab77d7562bf49f425c5c2
- # via requests
-importlib-metadata==5.1.0 \
- --hash=sha256:d5059f9f1e8e41f80e9c56c2ee58811450c31984dfa625329ffd7c0dad88a73b \
- --hash=sha256:d84d17e21670ec07990e1044a99efe8d615d860fd176fc29ef5c306068fda313
+google-pasta==0.2.0 \
+ --hash=sha256:4612951da876b1a10fe3960d7226f0c7682cf901e16ac06e473b267a5afa8954 \
+ --hash=sha256:b32482794a366b5366a32c92a9a9201b107821889935a02b3e51f6b432ea84ed \
+ --hash=sha256:c9f2c8dfc8f96d0d5808299920721be30c9eec37f2389f28904f454565c8a16e
+ # via tensorflow
+greenlet==3.1.1 \
+ --hash=sha256:0153404a4bb921f0ff1abeb5ce8a5131da56b953eda6e14b88dc6bbc04d2049e \
+ --hash=sha256:03a088b9de532cbfe2ba2034b2b85e82df37874681e8c470d6fb2f8c04d7e4b7 \
+ --hash=sha256:04b013dc07c96f83134b1e99888e7a79979f1a247e2a9f59697fa14b5862ed01 \
+ --hash=sha256:05175c27cb459dcfc05d026c4232f9de8913ed006d42713cb8a5137bd49375f1 \
+ --hash=sha256:09fc016b73c94e98e29af67ab7b9a879c307c6731a2c9da0db5a7d9b7edd1159 \
+ --hash=sha256:0bbae94a29c9e5c7e4a2b7f0aae5c17e8e90acbfd3bf6270eeba60c39fce3563 \
+ --hash=sha256:0fde093fb93f35ca72a556cf72c92ea3ebfda3d79fc35bb19fbe685853869a83 \
+ --hash=sha256:1443279c19fca463fc33e65ef2a935a5b09bb90f978beab37729e1c3c6c25fe9 \
+ --hash=sha256:1776fd7f989fc6b8d8c8cb8da1f6b82c5814957264d1f6cf818d475ec2bf6395 \
+ --hash=sha256:1d3755bcb2e02de341c55b4fca7a745a24a9e7212ac953f6b3a48d117d7257aa \
+ --hash=sha256:23f20bb60ae298d7d8656c6ec6db134bca379ecefadb0b19ce6f19d1f232a942 \
+ --hash=sha256:275f72decf9932639c1c6dd1013a1bc266438eb32710016a1c742df5da6e60a1 \
+ --hash=sha256:2846930c65b47d70b9d178e89c7e1a69c95c1f68ea5aa0a58646b7a96df12441 \
+ --hash=sha256:3319aa75e0e0639bc15ff54ca327e8dc7a6fe404003496e3c6925cd3142e0e22 \
+ --hash=sha256:346bed03fe47414091be4ad44786d1bd8bef0c3fcad6ed3dee074a032ab408a9 \
+ --hash=sha256:36b89d13c49216cadb828db8dfa6ce86bbbc476a82d3a6c397f0efae0525bdd0 \
+ --hash=sha256:37b9de5a96111fc15418819ab4c4432e4f3c2ede61e660b1e33971eba26ef9ba \
+ --hash=sha256:396979749bd95f018296af156201d6211240e7a23090f50a8d5d18c370084dc3 \
+ --hash=sha256:3b2813dc3de8c1ee3f924e4d4227999285fd335d1bcc0d2be6dc3f1f6a318ec1 \
+ --hash=sha256:411f015496fec93c1c8cd4e5238da364e1da7a124bcb293f085bf2860c32c6f6 \
+ --hash=sha256:47da355d8687fd65240c364c90a31569a133b7b60de111c255ef5b606f2ae291 \
+ --hash=sha256:48ca08c771c268a768087b408658e216133aecd835c0ded47ce955381105ba39 \
+ --hash=sha256:4afe7ea89de619adc868e087b4d2359282058479d7cfb94970adf4b55284574d \
+ --hash=sha256:4ce3ac6cdb6adf7946475d7ef31777c26d94bccc377e070a7986bd2d5c515467 \
+ --hash=sha256:4ead44c85f8ab905852d3de8d86f6f8baf77109f9da589cb4fa142bd3b57b475 \
+ --hash=sha256:54558ea205654b50c438029505def3834e80f0869a70fb15b871c29b4575ddef \
+ --hash=sha256:5e06afd14cbaf9e00899fae69b24a32f2196c19de08fcb9f4779dd4f004e5e7c \
+ --hash=sha256:62ee94988d6b4722ce0028644418d93a52429e977d742ca2ccbe1c4f4a792511 \
+ --hash=sha256:63e4844797b975b9af3a3fb8f7866ff08775f5426925e1e0bbcfe7932059a12c \
+ --hash=sha256:6510bf84a6b643dabba74d3049ead221257603a253d0a9873f55f6a59a65f822 \
+ --hash=sha256:667a9706c970cb552ede35aee17339a18e8f2a87a51fba2ed39ceeeb1004798a \
+ --hash=sha256:6ef9ea3f137e5711f0dbe5f9263e8c009b7069d8a1acea822bd5e9dae0ae49c8 \
+ --hash=sha256:7017b2be767b9d43cc31416aba48aab0d2309ee31b4dbf10a1d38fb7972bdf9d \
+ --hash=sha256:7124e16b4c55d417577c2077be379514321916d5790fa287c9ed6f23bd2ffd01 \
+ --hash=sha256:73aaad12ac0ff500f62cebed98d8789198ea0e6f233421059fa68a5aa7220145 \
+ --hash=sha256:77c386de38a60d1dfb8e55b8c1101d68c79dfdd25c7095d51fec2dd800892b80 \
+ --hash=sha256:7876452af029456b3f3549b696bb36a06db7c90747740c5302f74a9e9fa14b13 \
+ --hash=sha256:7939aa3ca7d2a1593596e7ac6d59391ff30281ef280d8632fa03d81f7c5f955e \
+ --hash=sha256:8320f64b777d00dd7ccdade271eaf0cad6636343293a25074cc5566160e4de7b \
+ --hash=sha256:85f3ff71e2e60bd4b4932a043fbbe0f499e263c628390b285cb599154a3b03b1 \
+ --hash=sha256:8b8b36671f10ba80e159378df9c4f15c14098c4fd73a36b9ad715f057272fbef \
+ --hash=sha256:93147c513fac16385d1036b7e5b102c7fbbdb163d556b791f0f11eada7ba65dc \
+ --hash=sha256:935e943ec47c4afab8965954bf49bfa639c05d4ccf9ef6e924188f762145c0ff \
+ --hash=sha256:94b6150a85e1b33b40b1464a3f9988dcc5251d6ed06842abff82e42632fac120 \
+ --hash=sha256:94ebba31df2aa506d7b14866fed00ac141a867e63143fe5bca82a8e503b36437 \
+ --hash=sha256:95ffcf719966dd7c453f908e208e14cde192e09fde6c7186c8f1896ef778d8cd \
+ --hash=sha256:98884ecf2ffb7d7fe6bd517e8eb99d31ff7855a840fa6d0d63cd07c037f6a981 \
+ --hash=sha256:99cfaa2110534e2cf3ba31a7abcac9d328d1d9f1b95beede58294a60348fba36 \
+ --hash=sha256:9e8f8c9cb53cdac7ba9793c276acd90168f416b9ce36799b9b885790f8ad6c0a \
+ --hash=sha256:a0dfc6c143b519113354e780a50381508139b07d2177cb6ad6a08278ec655798 \
+ --hash=sha256:b2795058c23988728eec1f36a4e5e4ebad22f8320c85f3587b539b9ac84128d7 \
+ --hash=sha256:b42703b1cf69f2aa1df7d1030b9d77d3e584a70755674d60e710f0af570f3761 \
+ --hash=sha256:b7cede291382a78f7bb5f04a529cb18e068dd29e0fb27376074b6d0317bf4dd0 \
+ --hash=sha256:b8a678974d1f3aa55f6cc34dc480169d58f2e6d8958895d68845fa4ab566509e \
+ --hash=sha256:b8da394b34370874b4572676f36acabac172602abf054cbc4ac910219f3340af \
+ --hash=sha256:c3a701fe5a9695b238503ce5bbe8218e03c3bcccf7e204e455e7462d770268aa \
+ --hash=sha256:c4aab7f6381f38a4b42f269057aee279ab0fc7bf2e929e3d4abfae97b682a12c \
+ --hash=sha256:ca9d0ff5ad43e785350894d97e13633a66e2b50000e8a183a50a88d834752d42 \
+ --hash=sha256:d0028e725ee18175c6e422797c407874da24381ce0690d6b9396c204c7f7276e \
+ --hash=sha256:d21e10da6ec19b457b82636209cbe2331ff4306b54d06fa04b7c138ba18c8a81 \
+ --hash=sha256:d5e975ca70269d66d17dd995dafc06f1b06e8cb1ec1e9ed54c1d1e4a7c4cf26e \
+ --hash=sha256:da7a9bff22ce038e19bf62c4dd1ec8391062878710ded0a845bcf47cc0200617 \
+ --hash=sha256:db32b5348615a04b82240cc67983cb315309e88d444a288934ee6ceaebcad6cc \
+ --hash=sha256:dcc62f31eae24de7f8dce72134c8651c58000d3b1868e01392baea7c32c247de \
+ --hash=sha256:dfc59d69fc48664bc693842bd57acfdd490acafda1ab52c7836e3fc75c90a111 \
+ --hash=sha256:e347b3bfcf985a05e8c0b7d462ba6f15b1ee1c909e2dcad795e49e91b152c383 \
+ --hash=sha256:e4d333e558953648ca09d64f13e6d8f0523fa705f51cae3f03b5983489958c70 \
+ --hash=sha256:ed10eac5830befbdd0c32f83e8aa6288361597550ba669b04c48f0f9a2c843c6 \
+ --hash=sha256:efc0f674aa41b92da8c49e0346318c6075d734994c3c4e4430b1c3f853e498e4 \
+ --hash=sha256:f1695e76146579f8c06c1509c7ce4dfe0706f49c6831a817ac04eebb2fd02011 \
+ --hash=sha256:f1d4aeb8891338e60d1ab6127af1fe45def5259def8094b9c7e34690c8858803 \
+ --hash=sha256:f406b22b7c9a9b4f8aa9d2ab13d6ae0ac3e85c9a809bd590ad53fed2bf70dc79 \
+ --hash=sha256:f6ff3b14f2df4c41660a7dec01045a045653998784bf8cfcb5a525bdffffbc8f
+ # via sqlalchemy
+grpcio==1.66.1 \
+ --hash=sha256:0e6c9b42ded5d02b6b1fea3a25f036a2236eeb75d0579bfd43c0018c88bf0a3e \
+ --hash=sha256:161d5c535c2bdf61b95080e7f0f017a1dfcb812bf54093e71e5562b16225b4ce \
+ --hash=sha256:17663598aadbedc3cacd7bbde432f541c8e07d2496564e22b214b22c7523dac8 \
+ --hash=sha256:1c17ebcec157cfb8dd445890a03e20caf6209a5bd4ac5b040ae9dbc59eef091d \
+ --hash=sha256:292a846b92cdcd40ecca46e694997dd6b9be6c4c01a94a0dfb3fcb75d20da858 \
+ --hash=sha256:2ca2559692d8e7e245d456877a85ee41525f3ed425aa97eb7a70fc9a79df91a0 \
+ --hash=sha256:307b1d538140f19ccbd3aed7a93d8f71103c5d525f3c96f8616111614b14bf2a \
+ --hash=sha256:30a1c2cf9390c894c90bbc70147f2372130ad189cffef161f0432d0157973f45 \
+ --hash=sha256:31a049daa428f928f21090403e5d18ea02670e3d5d172581670be006100db9ef \
+ --hash=sha256:35334f9c9745add3e357e3372756fd32d925bd52c41da97f4dfdafbde0bf0ee2 \
+ --hash=sha256:3750c5a00bd644c75f4507f77a804d0189d97a107eb1481945a0cf3af3e7a5ac \
+ --hash=sha256:3885f037eb11f1cacc41f207b705f38a44b69478086f40608959bf5ad85826dd \
+ --hash=sha256:4573608e23f7e091acfbe3e84ac2045680b69751d8d67685ffa193a4429fedb1 \
+ --hash=sha256:4825a3aa5648010842e1c9d35a082187746aa0cdbf1b7a2a930595a94fb10fce \
+ --hash=sha256:4877ba180591acdf127afe21ec1c7ff8a5ecf0fe2600f0d3c50e8c4a1cbc6492 \
+ --hash=sha256:48b0d92d45ce3be2084b92fb5bae2f64c208fea8ceed7fccf6a7b524d3c4942e \
+ --hash=sha256:4d813316d1a752be6f5c4360c49f55b06d4fe212d7df03253dfdae90c8a402bb \
+ --hash=sha256:5dd67ed9da78e5121efc5c510f0122a972216808d6de70953a740560c572eb44 \
+ --hash=sha256:6f914386e52cbdeb5d2a7ce3bf1fdfacbe9d818dd81b6099a05b741aaf3848bb \
+ --hash=sha256:7101db1bd4cd9b880294dec41a93fcdce465bdbb602cd8dc5bd2d6362b618759 \
+ --hash=sha256:7e06aa1f764ec8265b19d8f00140b8c4b6ca179a6dc67aa9413867c47e1fb04e \
+ --hash=sha256:84ca1be089fb4446490dd1135828bd42a7c7f8421e74fa581611f7afdf7ab761 \
+ --hash=sha256:8a1e224ce6f740dbb6b24c58f885422deebd7eb724aff0671a847f8951857c26 \
+ --hash=sha256:97ae7edd3f3f91480e48ede5d3e7d431ad6005bfdbd65c1b56913799ec79e791 \
+ --hash=sha256:9c9bebc6627873ec27a70fc800f6083a13c70b23a5564788754b9ee52c5aef6c \
+ --hash=sha256:a013c5fbb12bfb5f927444b477a26f1080755a931d5d362e6a9a720ca7dbae60 \
+ --hash=sha256:a66fe4dc35d2330c185cfbb42959f57ad36f257e0cc4557d11d9f0a3f14311df \
+ --hash=sha256:a92c4f58c01c77205df6ff999faa008540475c39b835277fb8883b11cada127a \
+ --hash=sha256:aa8ba945c96e73de29d25331b26f3e416e0c0f621e984a3ebdb2d0d0b596a3b3 \
+ --hash=sha256:b0aa03d240b5539648d996cc60438f128c7f46050989e35b25f5c18286c86734 \
+ --hash=sha256:b1b24c23d51a1e8790b25514157d43f0a4dce1ac12b3f0b8e9f66a5e2c4c132f \
+ --hash=sha256:b7ffb8ea674d68de4cac6f57d2498fef477cef582f1fa849e9f844863af50083 \
+ --hash=sha256:b9feb4e5ec8dc2d15709f4d5fc367794d69277f5d680baf1910fc9915c633524 \
+ --hash=sha256:bff2096bdba686019fb32d2dde45b95981f0d1490e054400f70fc9a8af34b49d \
+ --hash=sha256:c30aeceeaff11cd5ddbc348f37c58bcb96da8d5aa93fed78ab329de5f37a0d7a \
+ --hash=sha256:c9f80f9fad93a8cf71c7f161778ba47fd730d13a343a46258065c4deb4b550c0 \
+ --hash=sha256:cfd349de4158d797db2bd82d2020554a121674e98fbe6b15328456b3bf2495bb \
+ --hash=sha256:d0cd7050397b3609ea51727b1811e663ffda8bda39c6a5bb69525ef12414b503 \
+ --hash=sha256:d639c939ad7c440c7b2819a28d559179a4508783f7e5b991166f8d7a34b52815 \
+ --hash=sha256:e3ba04659e4fce609de2658fe4dbf7d6ed21987a94460f5f92df7579fd5d0e22 \
+ --hash=sha256:ecfe735e7a59e5a98208447293ff8580e9db1e890e232b8b292dc8bd15afc0d2 \
+ --hash=sha256:ef82d361ed5849d34cf09105d00b94b6728d289d6b9235513cb2fcc79f7c432c \
+ --hash=sha256:f03a5884c56256e08fd9e262e11b5cfacf1af96e2ce78dc095d2c41ccae2c80d \
+ --hash=sha256:f1fe60d0772831d96d263b53d83fb9a3d050a94b0e94b6d004a5ad111faa5b5b \
+ --hash=sha256:f517fd7259fe823ef3bd21e508b653d5492e706e9f0ef82c16ce3347a8a5620c \
+ --hash=sha256:fdb14bad0835914f325349ed34a51940bc2ad965142eb3090081593c6e347be9
# via
+ # tensorboard
+ # tensorflow
+h11==0.14.0 \
+ --hash=sha256:8f19fbbe99e72420ff35c00b27a34cb9937e902a8b810e2c88300c6f0a3b699d \
+ --hash=sha256:e3fe4ac4b851c468cc8363d500db52c2ead036020723024a109d37346efaa761
+ # via uvicorn
+h5py==3.11.0 \
+ --hash=sha256:083e0329ae534a264940d6513f47f5ada617da536d8dccbafc3026aefc33c90e \
+ --hash=sha256:1625fd24ad6cfc9c1ccd44a66dac2396e7ee74940776792772819fc69f3a3731 \
+ --hash=sha256:21dbdc5343f53b2e25404673c4f00a3335aef25521bd5fa8c707ec3833934892 \
+ --hash=sha256:52c416f8eb0daae39dabe71415cb531f95dce2d81e1f61a74537a50c63b28ab3 \
+ --hash=sha256:55106b04e2c83dfb73dc8732e9abad69d83a436b5b82b773481d95d17b9685e1 \
+ --hash=sha256:67462d0669f8f5459529de179f7771bd697389fcb3faab54d63bf788599a48ea \
+ --hash=sha256:6c4b760082626120031d7902cd983d8c1f424cdba2809f1067511ef283629d4b \
+ --hash=sha256:731839240c59ba219d4cb3bc5880d438248533366f102402cfa0621b71796b62 \
+ --hash=sha256:754c0c2e373d13d6309f408325343b642eb0f40f1a6ad21779cfa9502209e150 \
+ --hash=sha256:75bd7b3d93fbeee40860fd70cdc88df4464e06b70a5ad9ce1446f5f32eb84007 \
+ --hash=sha256:77b19a40788e3e362b54af4dcf9e6fde59ca016db2c61360aa30b47c7b7cef00 \
+ --hash=sha256:7b7e8f78072a2edec87c9836f25f34203fd492a4475709a18b417a33cfb21fa9 \
+ --hash=sha256:8ec9df3dd2018904c4cc06331951e274f3f3fd091e6d6cc350aaa90fa9b42a76 \
+ --hash=sha256:a76cae64080210389a571c7d13c94a1a6cf8cb75153044fd1f822a962c97aeab \
+ --hash=sha256:aa6ae84a14103e8dc19266ef4c3e5d7c00b68f21d07f2966f0ca7bdb6c2761fb \
+ --hash=sha256:bbd732a08187a9e2a6ecf9e8af713f1d68256ee0f7c8b652a32795670fb481ba \
+ --hash=sha256:c072655ad1d5fe9ef462445d3e77a8166cbfa5e599045f8aa3c19b75315f10e5 \
+ --hash=sha256:d9c944d364688f827dc889cf83f1fca311caf4fa50b19f009d1f2b525edd33a3 \
+ --hash=sha256:ef4e2f338fc763f50a8113890f455e1a70acd42a4d083370ceb80c463d803972 \
+ --hash=sha256:f3736fe21da2b7d8a13fe8fe415f1272d2a1ccdeff4849c1421d2fb30fd533bc \
+ --hash=sha256:f4e025e852754ca833401777c25888acb96889ee2c27e7e629a19aee288833f0
+ # via
+ # keras
+ # tensorflow
+humanize==4.10.0 \
+ --hash=sha256:06b6eb0293e4b85e8d385397c5868926820db32b9b654b932f57fa41c23c9978 \
+ --hash=sha256:39e7ccb96923e732b5c2e27aeaa3b10a8dfeeba3eb965ba7b74a3eb0e30040a6
+ # via orbax-checkpoint
+idna==3.8 \
+ --hash=sha256:050b4e5baadcd44d760cedbd2b8e639f2ff89bbc7a5730fcc662954303377aac \
+ --hash=sha256:d838c2c0ed6fced7693d5e8ab8e734d5f8fda53a039c0164afb0b82e771e3603
+ # via
+ # anyio
+ # requests
+importlib-metadata==8.4.0 \
+ --hash=sha256:66f342cc6ac9818fc6ff340576acd24d65ba0b3efabb2b4ac08b598965a4a2f1 \
+ --hash=sha256:9a547d3bc3608b025f93d403fdd1aae741c24fbb8314df4b155675742ce303c5
+ # via
+ # flask
# jax
# markdown
# mkdocs
+ # mkdocs-get-deps
+ # yapf
+importlib-resources==6.4.4 \
+ --hash=sha256:20600c8b7361938dc0bb2d5ec0297802e575df486f5a544fa414da65e13721f7 \
+ --hash=sha256:dda242603d1c9cd836c3368b1174ed74cb4049ecd209e7a1a0104620c18c5c11
+ # via
+ # etils
+ # matplotlib
+itsdangerous==2.2.0 \
+ --hash=sha256:c6242fc49e35958c8b15141343aa660db5fc54d4f13a1db01a3f5891b98700ef \
+ --hash=sha256:e0050c0b7da1eea53ffaf149c0cfbb5c6e2e2b69c4bef22c81fa6eb73e5f6173
+ # via flask
jax[cuda12]==0.4.30 \
--hash=sha256:289b30ae03b52f7f4baf6ef082a9f4e3e29c1080e22d13512c5ecf02d5f1a55b \
--hash=sha256:94d74b5b2db0d80672b61d83f1f63ebf99d2ab7398ec12b2ca0c9d1e97afe577
- # via -r tools/python/requirements.txt
+ # via
+ # -r tools/python/requirements.txt
+ # chex
+ # clu
+ # flashbax
+ # flax
+ # optax
+ # orbax-checkpoint
jax-cuda12-pjrt==0.4.30 \
--hash=sha256:895d0198ad99638fcaf976c47592e2a543eef79ea15fabd24a402d055390c328 \
--hash=sha256:c36fb1e0c236563bf3a87e70f4d1ab28a31d7cf5d722c9ede30c4172116e8bcb
@@ -189,181 +906,286 @@
--hash=sha256:e93eb0646b41ba213252b51b0b69096b9cd1d81a35ea85c9d06663b5d11efe45 \
--hash=sha256:ea3a00005faafbe3c18b178d3b534208b3b4027b2be6230227e7b87ce399fc29 \
--hash=sha256:f74a6b0e09df4b5e2ee399ebb9f0e01190e26e84ccb0a758fadb516415c07f18
- # via jax
-jinja2==3.1.2 \
- --hash=sha256:31351a702a408a9e7595a8fc6150fc3f43bb6bf7e319770cbc0db9df9437e852 \
- --hash=sha256:6088930bfe239f0e6710546ab9c19c9ef35e29792895fed6e6e31a023a182a61
+ # via
+ # chex
+ # clu
+ # flashbax
+ # jax
+ # optax
+ # orbax-checkpoint
+jaxtyping==0.2.34 \
+ --hash=sha256:2f81fb6d1586e497a6ea2d28c06dcab37b108a096cbb36ea3fe4fa2e1c1f32e5 \
+ --hash=sha256:eed9a3458ec8726c84ea5457ebde53c964f65d2c22c0ec40d0555ae3fed5bbaf
+ # via -r tools/python/requirements.txt
+jinja2==3.1.4 \
+ --hash=sha256:4a3aee7acbbe7303aede8e9648d13b8bf88a429282aa6122a993f0ac800cb369 \
+ --hash=sha256:bc5dd2abb727a5319567b7a813e6a2e7318c39f4f487cfe6c89c6f9c7d25197d
# via
# -r tools/python/requirements.txt
+ # aim
# bokeh
+ # flask
# mkdocs
-kiwisolver==1.4.4 \
- --hash=sha256:02f79693ec433cb4b5f51694e8477ae83b3205768a6fb48ffba60549080e295b \
- --hash=sha256:03baab2d6b4a54ddbb43bba1a3a2d1627e82d205c5cf8f4c924dc49284b87166 \
- --hash=sha256:1041feb4cda8708ce73bb4dcb9ce1ccf49d553bf87c3954bdfa46f0c3f77252c \
- --hash=sha256:10ee06759482c78bdb864f4109886dff7b8a56529bc1609d4f1112b93fe6423c \
- --hash=sha256:1d1573129aa0fd901076e2bfb4275a35f5b7aa60fbfb984499d661ec950320b0 \
- --hash=sha256:283dffbf061a4ec60391d51e6155e372a1f7a4f5b15d59c8505339454f8989e4 \
- --hash=sha256:28bc5b299f48150b5f822ce68624e445040595a4ac3d59251703779836eceff9 \
- --hash=sha256:2a66fdfb34e05b705620dd567f5a03f239a088d5a3f321e7b6ac3239d22aa286 \
- --hash=sha256:2e307eb9bd99801f82789b44bb45e9f541961831c7311521b13a6c85afc09767 \
- --hash=sha256:2e407cb4bd5a13984a6c2c0fe1845e4e41e96f183e5e5cd4d77a857d9693494c \
- --hash=sha256:2f5e60fabb7343a836360c4f0919b8cd0d6dbf08ad2ca6b9cf90bf0c76a3c4f6 \
- --hash=sha256:36dafec3d6d6088d34e2de6b85f9d8e2324eb734162fba59d2ba9ed7a2043d5b \
- --hash=sha256:3fe20f63c9ecee44560d0e7f116b3a747a5d7203376abeea292ab3152334d004 \
- --hash=sha256:41dae968a94b1ef1897cb322b39360a0812661dba7c682aa45098eb8e193dbdf \
- --hash=sha256:4bd472dbe5e136f96a4b18f295d159d7f26fd399136f5b17b08c4e5f498cd494 \
- --hash=sha256:4ea39b0ccc4f5d803e3337dd46bcce60b702be4d86fd0b3d7531ef10fd99a1ac \
- --hash=sha256:5853eb494c71e267912275e5586fe281444eb5e722de4e131cddf9d442615626 \
- --hash=sha256:5bce61af018b0cb2055e0e72e7d65290d822d3feee430b7b8203d8a855e78766 \
- --hash=sha256:6295ecd49304dcf3bfbfa45d9a081c96509e95f4b9d0eb7ee4ec0530c4a96514 \
- --hash=sha256:62ac9cc684da4cf1778d07a89bf5f81b35834cb96ca523d3a7fb32509380cbf6 \
- --hash=sha256:70e7c2e7b750585569564e2e5ca9845acfaa5da56ac46df68414f29fea97be9f \
- --hash=sha256:7577c1987baa3adc4b3c62c33bd1118c3ef5c8ddef36f0f2c950ae0b199e100d \
- --hash=sha256:75facbe9606748f43428fc91a43edb46c7ff68889b91fa31f53b58894503a191 \
- --hash=sha256:787518a6789009c159453da4d6b683f468ef7a65bbde796bcea803ccf191058d \
- --hash=sha256:78d6601aed50c74e0ef02f4204da1816147a6d3fbdc8b3872d263338a9052c51 \
- --hash=sha256:7c43e1e1206cd421cd92e6b3280d4385d41d7166b3ed577ac20444b6995a445f \
- --hash=sha256:81e38381b782cc7e1e46c4e14cd997ee6040768101aefc8fa3c24a4cc58e98f8 \
- --hash=sha256:841293b17ad704d70c578f1f0013c890e219952169ce8a24ebc063eecf775454 \
- --hash=sha256:872b8ca05c40d309ed13eb2e582cab0c5a05e81e987ab9c521bf05ad1d5cf5cb \
- --hash=sha256:877272cf6b4b7e94c9614f9b10140e198d2186363728ed0f701c6eee1baec1da \
- --hash=sha256:8c808594c88a025d4e322d5bb549282c93c8e1ba71b790f539567932722d7bd8 \
- --hash=sha256:8ed58b8acf29798b036d347791141767ccf65eee7f26bde03a71c944449e53de \
- --hash=sha256:91672bacaa030f92fc2f43b620d7b337fd9a5af28b0d6ed3f77afc43c4a64b5a \
- --hash=sha256:968f44fdbf6dd757d12920d63b566eeb4d5b395fd2d00d29d7ef00a00582aac9 \
- --hash=sha256:9f85003f5dfa867e86d53fac6f7e6f30c045673fa27b603c397753bebadc3008 \
- --hash=sha256:a553dadda40fef6bfa1456dc4be49b113aa92c2a9a9e8711e955618cd69622e3 \
- --hash=sha256:a68b62a02953b9841730db7797422f983935aeefceb1679f0fc85cbfbd311c32 \
- --hash=sha256:abbe9fa13da955feb8202e215c4018f4bb57469b1b78c7a4c5c7b93001699938 \
- --hash=sha256:ad881edc7ccb9d65b0224f4e4d05a1e85cf62d73aab798943df6d48ab0cd79a1 \
- --hash=sha256:b1792d939ec70abe76f5054d3f36ed5656021dcad1322d1cc996d4e54165cef9 \
- --hash=sha256:b428ef021242344340460fa4c9185d0b1f66fbdbfecc6c63eff4b7c29fad429d \
- --hash=sha256:b533558eae785e33e8c148a8d9921692a9fe5aa516efbdff8606e7d87b9d5824 \
- --hash=sha256:ba59c92039ec0a66103b1d5fe588fa546373587a7d68f5c96f743c3396afc04b \
- --hash=sha256:bc8d3bd6c72b2dd9decf16ce70e20abcb3274ba01b4e1c96031e0c4067d1e7cd \
- --hash=sha256:bc9db8a3efb3e403e4ecc6cd9489ea2bac94244f80c78e27c31dcc00d2790ac2 \
- --hash=sha256:bf7d9fce9bcc4752ca4a1b80aabd38f6d19009ea5cbda0e0856983cf6d0023f5 \
- --hash=sha256:c2dbb44c3f7e6c4d3487b31037b1bdbf424d97687c1747ce4ff2895795c9bf69 \
- --hash=sha256:c79ebe8f3676a4c6630fd3f777f3cfecf9289666c84e775a67d1d358578dc2e3 \
- --hash=sha256:c97528e64cb9ebeff9701e7938653a9951922f2a38bd847787d4a8e498cc83ae \
- --hash=sha256:d0611a0a2a518464c05ddd5a3a1a0e856ccc10e67079bb17f265ad19ab3c7597 \
- --hash=sha256:d06adcfa62a4431d404c31216f0f8ac97397d799cd53800e9d3efc2fbb3cf14e \
- --hash=sha256:d41997519fcba4a1e46eb4a2fe31bc12f0ff957b2b81bac28db24744f333e955 \
- --hash=sha256:d5b61785a9ce44e5a4b880272baa7cf6c8f48a5180c3e81c59553ba0cb0821ca \
- --hash=sha256:da152d8cdcab0e56e4f45eb08b9aea6455845ec83172092f09b0e077ece2cf7a \
- --hash=sha256:da7e547706e69e45d95e116e6939488d62174e033b763ab1496b4c29b76fabea \
- --hash=sha256:db5283d90da4174865d520e7366801a93777201e91e79bacbac6e6927cbceede \
- --hash=sha256:db608a6757adabb32f1cfe6066e39b3706d8c3aa69bbc353a5b61edad36a5cb4 \
- --hash=sha256:e0ea21f66820452a3f5d1655f8704a60d66ba1191359b96541eaf457710a5fc6 \
- --hash=sha256:e7da3fec7408813a7cebc9e4ec55afed2d0fd65c4754bc376bf03498d4e92686 \
- --hash=sha256:e92a513161077b53447160b9bd8f522edfbed4bd9759e4c18ab05d7ef7e49408 \
- --hash=sha256:ecb1fa0db7bf4cff9dac752abb19505a233c7f16684c5826d1f11ebd9472b871 \
- --hash=sha256:efda5fc8cc1c61e4f639b8067d118e742b812c930f708e6667a5ce0d13499e29 \
- --hash=sha256:f0a1dbdb5ecbef0d34eb77e56fcb3e95bbd7e50835d9782a45df81cc46949750 \
- --hash=sha256:f0a71d85ecdd570ded8ac3d1c0f480842f49a40beb423bb8014539a9f32a5897 \
- --hash=sha256:f4f270de01dd3e129a72efad823da90cc4d6aafb64c410c9033aba70db9f1ff0 \
- --hash=sha256:f6cb459eea32a4e2cf18ba5fcece2dbdf496384413bc1bae15583f19e567f3b2 \
- --hash=sha256:f8ad8285b01b0d4695102546b342b493b3ccc6781fc28c8c6a1bb63e95d22f09 \
- --hash=sha256:f9f39e2f049db33a908319cf46624a569b36983c7c78318e9726a4cb8923b26c
+jmespath==1.0.1 \
+ --hash=sha256:02e2e4cc71b5bcab88332eebf907519190dd9e6e82107fa7f83b1003a6252980 \
+ --hash=sha256:90261b206d6defd58fdd5e85f478bf633a2901798906be2ad389150c5c60edbe
+ # via
+ # boto3
+ # botocore
+keras==3.5.0 \
+ --hash=sha256:53ae4f9472ec9d9c6941c82a3fda86969724ace3b7630a94ba0a1f17ba1065c3 \
+ --hash=sha256:d37a3c623935713473ceb25241b52bce9d1e0ff5b36e5d0f6f47ed55f8500c9a
+ # via tensorflow
+kiwisolver==1.4.6 \
+ --hash=sha256:0081f85f0222620563409d4804c6567a930a45dafbe9674c7913fde131653992 \
+ --hash=sha256:00af95204100bc1d0f26e1ed52ec77d6e3da5c9b845c88d31875c164e4ba6c0c \
+ --hash=sha256:0632248f5a06a2e4134637628de7300b923d242a30926a1bbf7cc4e487dc0bb8 \
+ --hash=sha256:0d048002e15b9583ddff6ef4a27bd7f94fff830473856e82f311071b5cca9ade \
+ --hash=sha256:0d9a5af0c3cad547b59a2605d1af95c79c69c6a3aaf908be9677094ca6ba6dfa \
+ --hash=sha256:10a09a3e4213c2806bcfd2eb4edb756c557973d2cacf06873b18a247fce897da \
+ --hash=sha256:11b0fdacd87bfe02c4f293ac38b2caf736591253687dce4d489a780a4bf2c39e \
+ --hash=sha256:140f376c22b5148453acff768cff19c34ebbd593126617018732ea1d9ce65547 \
+ --hash=sha256:159a2ed7a89b51fcb9766562626f7d9fc411ed5f8b365413bc5ea2d4a8b81a2c \
+ --hash=sha256:160b983a1bca62d2274c886ddffc3168e0d6a1ae54d54556229f5bd57a4295e4 \
+ --hash=sha256:182b3eed63f8f79623bba26f1ac75e6c94463c98b70828029db8fe2d230b7ba0 \
+ --hash=sha256:19fa65a9e422eeb3b1d50073eb54e2e8c83821632b735d9d6af0ce1fcf42adea \
+ --hash=sha256:1f401784df70ea2870e4e10adade66b5b06cb2c151bc2a8a414a1d10554e9a81 \
+ --hash=sha256:204039c59e6160f1227c2a33153d0738c93c171dbcc5b632c653f7a7abd08dc9 \
+ --hash=sha256:212a903a4f90aa6bdbd0709b28df4a337687839dd7cf7030bb288ef756f338e4 \
+ --hash=sha256:261ca5e3a0b3fd3f6bf794122e0f80c76f5b5bb8055508a9d8a8869b5e7e8bef \
+ --hash=sha256:2cfbcd3a4b6193dd89dd005fbc5db8115a9f204727446562992f9f7fed217b3a \
+ --hash=sha256:2e33395cca1a27102beed4baf4e97490fcbb2c245626bddb940eafcfe697bf4a \
+ --hash=sha256:2f6668678a6b9488a7f8a6320e1b1c6396d179a976472dbc08d1600d04119511 \
+ --hash=sha256:300443d53ed971a0dd35249f5012a3c3c95004da2e3f5877ed3cb784228d67bd \
+ --hash=sha256:331b9d9f408e874ecf34bd79b79df8e099f0b1b351b8844609c1bfdc8d2d45b2 \
+ --hash=sha256:33422cbf4ea20cd42945a7ad6b04bc50da9630a5b42854e139944ffde3ba926f \
+ --hash=sha256:34105f4460ba50fc18a16a8e77a5122f7affe075628763fda748ad0ec534c3ee \
+ --hash=sha256:3aa8e43fbc847c26e17e50befac4de2336e223093263aa5b66c9c2030697b911 \
+ --hash=sha256:3b852c7f0ed9a2fd339c228829bca0964233ed45de50aae3e87b72ca37d177f8 \
+ --hash=sha256:3cda29d601445e6aa11f80d90a9b8c2ae501650c55d7ad29829bd44499c9e7e0 \
+ --hash=sha256:43e9bc95d7e9e6f7975f2f481db40738796ea718bf55e22c32eb8e242ed418fc \
+ --hash=sha256:45a5cb5abad1ad9c265eed7e058fefafeb7964565b93b397ba2f480faec8d674 \
+ --hash=sha256:4ccbc596114d32bb5d2ff74eb1785ab1b2d5bc56e7e54662ef335b333f427548 \
+ --hash=sha256:4cf699500d5d88a5424a4a26dfdcada6aa3a1917431e459c88c38dadd6a300d7 \
+ --hash=sha256:50ab1fedf86f3951a9e90a64edd15f598860ed60cd3664259756f097d527b5ae \
+ --hash=sha256:50c9c6c42bb6ca231626d1182b9128e89c5ce3c64456f811ff0280deb42d7bfe \
+ --hash=sha256:5a69366fb349c2be904ac13063e3b6bcae76ed1c826fcbc646f43135b45abb68 \
+ --hash=sha256:67b72c9cbd78ec8666af40747b80bf309f160701084e7cf492a02464e470ee29 \
+ --hash=sha256:683ffef2c51fdc54112dc610d06b59b88c21e23fb669b905da6d5bec80da1bde \
+ --hash=sha256:773f2d87825779ab69196dfcf63e9d91043273421c6128c8d4ed82bc6316068f \
+ --hash=sha256:7802ac87e8efd05f4ed6b82dfe4749cd4f38140c198a7d392ebbb3ab5fb38bd6 \
+ --hash=sha256:788cbf99738f18ae8a27b9d4d7314502b4b917005cfdacd1d6a59038332ae24d \
+ --hash=sha256:78a708e8371675e73208fa61b0985031e911584ad377593226c5974eaf0c2e2e \
+ --hash=sha256:7d42dbf8229d4c09632e46c83aeaf1dce6125925088704421c57c483dc9db304 \
+ --hash=sha256:7de63234cf06d3a0d218d5c6e907f6ceed72a9d369a8c561d1a161ffafd2fa95 \
+ --hash=sha256:7e3012902606eba35014f725dbd2aab3a28a276cb6872fb21bb27c0ee384a554 \
+ --hash=sha256:7e52b2568c47fb4f54d17576954e02b1de156c85152f87283a99db9670fd18c0 \
+ --hash=sha256:827425185329b813b40bbc176e0757282c558d6efab3c9f681f629c737e08a6e \
+ --hash=sha256:872c1323f29f0822000e47acac9a0b6ed2af843a20b27c85fa0fdc906f98140f \
+ --hash=sha256:89748381d0251d829cffeec03a5c2710812dc133a085a4f52be0996c291e721a \
+ --hash=sha256:8ec27e296790903e2a3484a1d93a8324d0cd660394842e0cf2a3657060ad8edc \
+ --hash=sha256:9739f60317af3ebb15372a61907a71ba71e9cc3c21239d4e39051ecf51928d98 \
+ --hash=sha256:979df7e9334f6a3694ee9be8d42817e519ef6d155a16499714d082cf41296852 \
+ --hash=sha256:9a59519a485ef60d17af17d93f70679a9e41372f3b777c27103b4ce13ece4e40 \
+ --hash=sha256:9f338d9724cc2b2ea49e8f3af3a6733f5191cf85801db5b137350dc021e16dad \
+ --hash=sha256:a05655320567b9c83b95c1b45339d01ce6373ff2e2d64f643fee2ba2432f035e \
+ --hash=sha256:a40af4800335cab9dfc3b8cb300384ef14e7740f21142c66d7b3f57228c4a290 \
+ --hash=sha256:a62379eee430b1c477bb0a0bf6858a57c7c0dad9cee8b3144a5cb5d366c66a54 \
+ --hash=sha256:a7d04968b6015583968e62eca184c5104cbdc02666fd5cc7a4b535f9846968fd \
+ --hash=sha256:a8188c27be2e590c519e747d885511204c3e01f2ec77006843a204af6d22ab9c \
+ --hash=sha256:a9be95d086578b3ada61a4621c0e7ee5f456820bfdccc3329061fdeae1e31179 \
+ --hash=sha256:ab480d087f10270ff24b06247e41eff901a452b890bfd708d8b7eb58bb01b212 \
+ --hash=sha256:ab93f58afe3a02922a343189404f24ed885564e6316649790240124b95ef1d6e \
+ --hash=sha256:acdb63f64219a374f7f9bb6c560a435545511364b24757819332f86da03894b9 \
+ --hash=sha256:ace86489e7951bd26329a589198d3875c3d48380f889c69d3eb254b506a80101 \
+ --hash=sha256:ad4410b6aca71bcfba185d92a3094114914b4ddd9d61d5b7b91047cb273a077b \
+ --hash=sha256:b19761c8c613b6d04c44f1a4797a144b44136f17ec009ccfb025e17b5698140c \
+ --hash=sha256:b474a369ebe8c2cd02df20997b94cd566edc708f38dce18e66385766dcef5f3c \
+ --hash=sha256:b747105ddb84ce77a41fbc9485df366519526d1f7f4a096ca02570bf082a70c3 \
+ --hash=sha256:b9dbf4091b04e1037c9c75ca67e71a348d145c4fac7e1bb3de2e3fe6f13df150 \
+ --hash=sha256:bc523ab49257fd7bbe00e23aff6924624a5da1ce924e4b3e39530049298779da \
+ --hash=sha256:c0d4811a031ff5194d9b45c15090d674cbf9890461a5028c4475f7b3202a5b1d \
+ --hash=sha256:c14338ac087b9a8db1db1b7d74ff91c0a2b1c93f6f1ab4942af15f1938449acf \
+ --hash=sha256:c3420b5179fb732a899a0dfbfdcbc221712d850b5772b082415658466e887e55 \
+ --hash=sha256:cb30165f71b7b3378668346e220c81d590593a3a1ff76428a53780310df03f35 \
+ --hash=sha256:cc09aff78d1eb3b4c63d31eba1db6da5b4d580cf65596562038b6c8ec5806a17 \
+ --hash=sha256:ccff4e5ec806db412aceec89b8e7a83a56ff93c5c615c725e7784d90c5a556c4 \
+ --hash=sha256:ce5efe545eea86f52ec5a1185e5052815ea86778e8268bad71fa46433f7c0bef \
+ --hash=sha256:d047def01426d15d5dde1fb9ba4e1d8ed7218069e73f00e0994d050913b2c3f4 \
+ --hash=sha256:dbc985766bf20141ce64baecc39fb9fedbce094b2b8de1bb62676b79328988e4 \
+ --hash=sha256:dbfa70f983f8a2ea69a3f72c4f04aaa1a152a246c4933e9d5d9c30da95815a9b \
+ --hash=sha256:dcb6a2bade6292f2b5b19225a4330af49f855edeed6e3c17240df905696a1494 \
+ --hash=sha256:df2a4a7cc2e01991e039a792457751b601bdf30143ab5f23f9a1e58f20c875f4 \
+ --hash=sha256:e033139b0a5981e30c1518b97ae4b20b4172e82ed49f09180d02640bde0ae831 \
+ --hash=sha256:e99b97d69499a7414572c906fbc7ca312519f2e17999730129f6c4492786e953 \
+ --hash=sha256:ee7289430ded484cc2eff9d8ffcce58ed7fe2c26919321dbc0580322a49e0120 \
+ --hash=sha256:ef452cf166271827939e907b23a1bda423329663a93a644d4a7be8f7bbb431ed \
+ --hash=sha256:f0b17c30a50ce5345469f206708adb5946917d59c900e53af7108da2a0c4b56f \
+ --hash=sha256:f1942a155c737a7c3835a957897f0cc9ebc0085b7a75d934d86aecb1b27b8873 \
+ --hash=sha256:f2ceaa6d0450623d108956647ef19a1a28c7e07880f1171c932477308d44d80b \
+ --hash=sha256:f464403e391724f8e7dff188d3fb77a85bd1273b3fdba182e6671abcc44434f8 \
+ --hash=sha256:f51a061d280300d33d37ebcfd02d5b480004e5bb5092e80ccabcdec8b7b1be9c \
+ --hash=sha256:f5a987f740e1c9964e614acb87ba1f014b4be760a341effc8dc789913d1840e6 \
+ --hash=sha256:f94771988da902b475f78e85cf63c5c94392773b4a6494234d87c1b363b2fbc5 \
+ --hash=sha256:fa61478e1356df92566ca46fe4165d0a36b9e336ee7fe7e71b923267fc5283aa \
+ --hash=sha256:fb55ba22ebebc537c2f13ffe3ad83ff1529be360ee36192bb61f330af3a785a5 \
+ --hash=sha256:fdeb0c875a8df911cf026f2ee7043d63d59768e58864835d5c5c27020f251fd2
# via matplotlib
-markdown==3.3.7 \
- --hash=sha256:cbb516f16218e643d8e0a95b309f77eb118cb138d39a4f27851e6a63581db874 \
- --hash=sha256:f5da449a6e1c989a4cea2631aa8ee67caa5a2ef855d551c88f9e309f4634c621
- # via mkdocs
-markupsafe==2.1.1 \
- --hash=sha256:0212a68688482dc52b2d45013df70d169f542b7394fc744c02a57374a4207003 \
- --hash=sha256:089cf3dbf0cd6c100f02945abeb18484bd1ee57a079aefd52cffd17fba910b88 \
- --hash=sha256:10c1bfff05d95783da83491be968e8fe789263689c02724e0c691933c52994f5 \
- --hash=sha256:33b74d289bd2f5e527beadcaa3f401e0df0a89927c1559c8566c066fa4248ab7 \
- --hash=sha256:3799351e2336dc91ea70b034983ee71cf2f9533cdff7c14c90ea126bfd95d65a \
- --hash=sha256:3ce11ee3f23f79dbd06fb3d63e2f6af7b12db1d46932fe7bd8afa259a5996603 \
- --hash=sha256:421be9fbf0ffe9ffd7a378aafebbf6f4602d564d34be190fc19a193232fd12b1 \
- --hash=sha256:43093fb83d8343aac0b1baa75516da6092f58f41200907ef92448ecab8825135 \
- --hash=sha256:46d00d6cfecdde84d40e572d63735ef81423ad31184100411e6e3388d405e247 \
- --hash=sha256:4a33dea2b688b3190ee12bd7cfa29d39c9ed176bda40bfa11099a3ce5d3a7ac6 \
- --hash=sha256:4b9fe39a2ccc108a4accc2676e77da025ce383c108593d65cc909add5c3bd601 \
- --hash=sha256:56442863ed2b06d19c37f94d999035e15ee982988920e12a5b4ba29b62ad1f77 \
- --hash=sha256:671cd1187ed5e62818414afe79ed29da836dde67166a9fac6d435873c44fdd02 \
- --hash=sha256:694deca8d702d5db21ec83983ce0bb4b26a578e71fbdbd4fdcd387daa90e4d5e \
- --hash=sha256:6a074d34ee7a5ce3effbc526b7083ec9731bb3cbf921bbe1d3005d4d2bdb3a63 \
- --hash=sha256:6d0072fea50feec76a4c418096652f2c3238eaa014b2f94aeb1d56a66b41403f \
- --hash=sha256:6fbf47b5d3728c6aea2abb0589b5d30459e369baa772e0f37a0320185e87c980 \
- --hash=sha256:7f91197cc9e48f989d12e4e6fbc46495c446636dfc81b9ccf50bb0ec74b91d4b \
- --hash=sha256:86b1f75c4e7c2ac2ccdaec2b9022845dbb81880ca318bb7a0a01fbf7813e3812 \
- --hash=sha256:8dc1c72a69aa7e082593c4a203dcf94ddb74bb5c8a731e4e1eb68d031e8498ff \
- --hash=sha256:8e3dcf21f367459434c18e71b2a9532d96547aef8a871872a5bd69a715c15f96 \
- --hash=sha256:8e576a51ad59e4bfaac456023a78f6b5e6e7651dcd383bcc3e18d06f9b55d6d1 \
- --hash=sha256:96e37a3dc86e80bf81758c152fe66dbf60ed5eca3d26305edf01892257049925 \
- --hash=sha256:97a68e6ada378df82bc9f16b800ab77cbf4b2fada0081794318520138c088e4a \
- --hash=sha256:99a2a507ed3ac881b975a2976d59f38c19386d128e7a9a18b7df6fff1fd4c1d6 \
- --hash=sha256:a49907dd8420c5685cfa064a1335b6754b74541bbb3706c259c02ed65b644b3e \
- --hash=sha256:b09bf97215625a311f669476f44b8b318b075847b49316d3e28c08e41a7a573f \
- --hash=sha256:b7bd98b796e2b6553da7225aeb61f447f80a1ca64f41d83612e6139ca5213aa4 \
- --hash=sha256:b87db4360013327109564f0e591bd2a3b318547bcef31b468a92ee504d07ae4f \
- --hash=sha256:bcb3ed405ed3222f9904899563d6fc492ff75cce56cba05e32eff40e6acbeaa3 \
- --hash=sha256:d4306c36ca495956b6d568d276ac11fdd9c30a36f1b6eb928070dc5360b22e1c \
- --hash=sha256:d5ee4f386140395a2c818d149221149c54849dfcfcb9f1debfe07a8b8bd63f9a \
- --hash=sha256:dda30ba7e87fbbb7eab1ec9f58678558fd9a6b8b853530e176eabd064da81417 \
- --hash=sha256:e04e26803c9c3851c931eac40c695602c6295b8d432cbe78609649ad9bd2da8a \
- --hash=sha256:e1c0b87e09fa55a220f058d1d49d3fb8df88fbfab58558f1198e08c1e1de842a \
- --hash=sha256:e72591e9ecd94d7feb70c1cbd7be7b3ebea3f548870aa91e2732960fa4d57a37 \
- --hash=sha256:e8c843bbcda3a2f1e3c2ab25913c80a3c5376cd00c6e8c4a86a89a28c8dc5452 \
- --hash=sha256:efc1913fd2ca4f334418481c7e595c00aad186563bbc1ec76067848c7ca0a933 \
- --hash=sha256:f121a1420d4e173a5d96e47e9a0c0dcff965afdf1626d28de1460815f7c4ee7a \
- --hash=sha256:fc7b548b17d238737688817ab67deebb30e8073c95749d55538ed473130ec0c7
- # via jinja2
-matplotlib==3.6.2 \
- --hash=sha256:0844523dfaaff566e39dbfa74e6f6dc42e92f7a365ce80929c5030b84caa563a \
- --hash=sha256:0eda9d1b43f265da91fb9ae10d6922b5a986e2234470a524e6b18f14095b20d2 \
- --hash=sha256:168093410b99f647ba61361b208f7b0d64dde1172b5b1796d765cd243cadb501 \
- --hash=sha256:1836f366272b1557a613f8265db220eb8dd883202bbbabe01bad5a4eadfd0c95 \
- --hash=sha256:19d61ee6414c44a04addbe33005ab1f87539d9f395e25afcbe9a3c50ce77c65c \
- --hash=sha256:252957e208c23db72ca9918cb33e160c7833faebf295aaedb43f5b083832a267 \
- --hash=sha256:32d29c8c26362169c80c5718ce367e8c64f4dd068a424e7110df1dd2ed7bd428 \
- --hash=sha256:380d48c15ec41102a2b70858ab1dedfa33eb77b2c0982cb65a200ae67a48e9cb \
- --hash=sha256:3964934731fd7a289a91d315919cf757f293969a4244941ab10513d2351b4e83 \
- --hash=sha256:3cef89888a466228fc4e4b2954e740ce8e9afde7c4315fdd18caa1b8de58ca17 \
- --hash=sha256:4426c74761790bff46e3d906c14c7aab727543293eed5a924300a952e1a3a3c1 \
- --hash=sha256:5024b8ed83d7f8809982d095d8ab0b179bebc07616a9713f86d30cf4944acb73 \
- --hash=sha256:52c2bdd7cd0bf9d5ccdf9c1816568fd4ccd51a4d82419cc5480f548981b47dd0 \
- --hash=sha256:54fa9fe27f5466b86126ff38123261188bed568c1019e4716af01f97a12fe812 \
- --hash=sha256:5ba73aa3aca35d2981e0b31230d58abb7b5d7ca104e543ae49709208d8ce706a \
- --hash=sha256:5e16dcaecffd55b955aa5e2b8a804379789c15987e8ebd2f32f01398a81e975b \
- --hash=sha256:5ecfc6559132116dedfc482d0ad9df8a89dc5909eebffd22f3deb684132d002f \
- --hash=sha256:74153008bd24366cf099d1f1e83808d179d618c4e32edb0d489d526523a94d9f \
- --hash=sha256:78ec3c3412cf277e6252764ee4acbdbec6920cc87ad65862272aaa0e24381eee \
- --hash=sha256:795ad83940732b45d39b82571f87af0081c120feff2b12e748d96bb191169e33 \
- --hash=sha256:7f716b6af94dc1b6b97c46401774472f0867e44595990fe80a8ba390f7a0a028 \
- --hash=sha256:83dc89c5fd728fdb03b76f122f43b4dcee8c61f1489e232d9ad0f58020523e1c \
- --hash=sha256:8a0ae37576ed444fe853709bdceb2be4c7df6f7acae17b8378765bd28e61b3ae \
- --hash=sha256:8a8dbe2cb7f33ff54b16bb5c500673502a35f18ac1ed48625e997d40c922f9cc \
- --hash=sha256:8a9d899953c722b9afd7e88dbefd8fb276c686c3116a43c577cfabf636180558 \
- --hash=sha256:8d0068e40837c1d0df6e3abf1cdc9a34a6d2611d90e29610fa1d2455aeb4e2e5 \
- --hash=sha256:9347cc6822f38db2b1d1ce992f375289670e595a2d1c15961aacbe0977407dfc \
- --hash=sha256:9f335e5625feb90e323d7e3868ec337f7b9ad88b5d633f876e3b778813021dab \
- --hash=sha256:b03fd10a1709d0101c054883b550f7c4c5e974f751e2680318759af005964990 \
- --hash=sha256:b0ca2c60d3966dfd6608f5f8c49b8a0fcf76de6654f2eda55fc6ef038d5a6f27 \
- --hash=sha256:b2604c6450f9dd2c42e223b1f5dca9643a23cfecc9fde4a94bb38e0d2693b136 \
- --hash=sha256:ca0e7a658fbafcddcaefaa07ba8dae9384be2343468a8e011061791588d839fa \
- --hash=sha256:d0e9ac04065a814d4cf2c6791a2ad563f739ae3ae830d716d54245c2b96fead6 \
- --hash=sha256:d50e8c1e571ee39b5dfbc295c11ad65988879f68009dd281a6e1edbc2ff6c18c \
- --hash=sha256:d840adcad7354be6f2ec28d0706528b0026e4c3934cc6566b84eac18633eab1b \
- --hash=sha256:e0bbee6c2a5bf2a0017a9b5e397babb88f230e6f07c3cdff4a4c4bc75ed7c617 \
- --hash=sha256:e5afe0a7ea0e3a7a257907060bee6724a6002b7eec55d0db16fd32409795f3e1 \
- --hash=sha256:e68be81cd8c22b029924b6d0ee814c337c0e706b8d88495a617319e5dd5441c3 \
- --hash=sha256:ec9be0f4826cdb3a3a517509dcc5f87f370251b76362051ab59e42b6b765f8c4 \
- --hash=sha256:f04f97797df35e442ed09f529ad1235d1f1c0f30878e2fe09a2676b71a8801e0 \
- --hash=sha256:f41e57ad63d336fe50d3a67bb8eaa26c09f6dda6a59f76777a99b8ccd8e26aec
+libclang==18.1.1 \
+ --hash=sha256:0b2e143f0fac830156feb56f9231ff8338c20aecfe72b4ffe96f19e5a1dbb69a \
+ --hash=sha256:3f0e1f49f04d3cd198985fea0511576b0aee16f9ff0e0f0cad7f9c57ec3c20e8 \
+ --hash=sha256:4dd2d3b82fab35e2bf9ca717d7b63ac990a3519c7e312f19fa8e86dcc712f7fb \
+ --hash=sha256:54dda940a4a0491a9d1532bf071ea3ef26e6dbaf03b5000ed94dd7174e8f9592 \
+ --hash=sha256:69f8eb8f65c279e765ffd28aaa7e9e364c776c17618af8bff22a8df58677ff4f \
+ --hash=sha256:6f14c3f194704e5d09769108f03185fce7acaf1d1ae4bbb2f30a72c2400cb7c5 \
+ --hash=sha256:83ce5045d101b669ac38e6da8e58765f12da2d3aafb3b9b98d88b286a60964d8 \
+ --hash=sha256:a1214966d08d73d971287fc3ead8dfaf82eb07fb197680d8b3859dbbbbf78250 \
+ --hash=sha256:c533091d8a3bbf7460a00cb6c1a71da93bffe148f172c7d03b1c31fbf8aa2a0b \
+ --hash=sha256:cf4a99b05376513717ab5d82a0db832c56ccea4fd61a69dbb7bccf2dfb207dbe
+ # via tensorflow
+mako==1.3.5 \
+ --hash=sha256:260f1dbc3a519453a9c856dedfe4beb4e50bd5a26d96386cb6c80856556bb91a \
+ --hash=sha256:48dbc20568c1d276a2698b36d968fa76161bf127194907ea6fc594fa81f943bc
+ # via alembic
+markdown==3.7 \
+ --hash=sha256:2ae2471477cfd02dbbf038d5d9bc226d40def84b4fe2986e49b59b6b472bbed2 \
+ --hash=sha256:7eb6df5690b81a1d7942992c97fad2938e956e79df20cbc6186e9c3a77b1c803
+ # via
+ # mkdocs
+ # tensorboard
+markdown-it-py==3.0.0 \
+ --hash=sha256:355216845c60bd96232cd8d8c40e8f9765cc86f46880e43a8fd22dc1a1a8cab1 \
+ --hash=sha256:e3f60a94fa066dc52ec76661e37c851cb232d92f9886b15cb560aaada2df8feb
+ # via rich
+markupsafe==2.1.5 \
+ --hash=sha256:00e046b6dd71aa03a41079792f8473dc494d564611a8f89bbbd7cb93295ebdcf \
+ --hash=sha256:075202fa5b72c86ad32dc7d0b56024ebdbcf2048c0ba09f1cde31bfdd57bcfff \
+ --hash=sha256:0e397ac966fdf721b2c528cf028494e86172b4feba51d65f81ffd65c63798f3f \
+ --hash=sha256:17b950fccb810b3293638215058e432159d2b71005c74371d784862b7e4683f3 \
+ --hash=sha256:1f3fbcb7ef1f16e48246f704ab79d79da8a46891e2da03f8783a5b6fa41a9532 \
+ --hash=sha256:2174c595a0d73a3080ca3257b40096db99799265e1c27cc5a610743acd86d62f \
+ --hash=sha256:2b7c57a4dfc4f16f7142221afe5ba4e093e09e728ca65c51f5620c9aaeb9a617 \
+ --hash=sha256:2d2d793e36e230fd32babe143b04cec8a8b3eb8a3122d2aceb4a371e6b09b8df \
+ --hash=sha256:30b600cf0a7ac9234b2638fbc0fb6158ba5bdcdf46aeb631ead21248b9affbc4 \
+ --hash=sha256:397081c1a0bfb5124355710fe79478cdbeb39626492b15d399526ae53422b906 \
+ --hash=sha256:3a57fdd7ce31c7ff06cdfbf31dafa96cc533c21e443d57f5b1ecc6cdc668ec7f \
+ --hash=sha256:3c6b973f22eb18a789b1460b4b91bf04ae3f0c4234a0a6aa6b0a92f6f7b951d4 \
+ --hash=sha256:3e53af139f8579a6d5f7b76549125f0d94d7e630761a2111bc431fd820e163b8 \
+ --hash=sha256:4096e9de5c6fdf43fb4f04c26fb114f61ef0bf2e5604b6ee3019d51b69e8c371 \
+ --hash=sha256:4275d846e41ecefa46e2015117a9f491e57a71ddd59bbead77e904dc02b1bed2 \
+ --hash=sha256:4c31f53cdae6ecfa91a77820e8b151dba54ab528ba65dfd235c80b086d68a465 \
+ --hash=sha256:4f11aa001c540f62c6166c7726f71f7573b52c68c31f014c25cc7901deea0b52 \
+ --hash=sha256:5049256f536511ee3f7e1b3f87d1d1209d327e818e6ae1365e8653d7e3abb6a6 \
+ --hash=sha256:58c98fee265677f63a4385256a6d7683ab1832f3ddd1e66fe948d5880c21a169 \
+ --hash=sha256:598e3276b64aff0e7b3451b72e94fa3c238d452e7ddcd893c3ab324717456bad \
+ --hash=sha256:5b7b716f97b52c5a14bffdf688f971b2d5ef4029127f1ad7a513973cfd818df2 \
+ --hash=sha256:5dedb4db619ba5a2787a94d877bc8ffc0566f92a01c0ef214865e54ecc9ee5e0 \
+ --hash=sha256:619bc166c4f2de5caa5a633b8b7326fbe98e0ccbfacabd87268a2b15ff73a029 \
+ --hash=sha256:629ddd2ca402ae6dbedfceeba9c46d5f7b2a61d9749597d4307f943ef198fc1f \
+ --hash=sha256:656f7526c69fac7f600bd1f400991cc282b417d17539a1b228617081106feb4a \
+ --hash=sha256:6ec585f69cec0aa07d945b20805be741395e28ac1627333b1c5b0105962ffced \
+ --hash=sha256:72b6be590cc35924b02c78ef34b467da4ba07e4e0f0454a2c5907f473fc50ce5 \
+ --hash=sha256:7502934a33b54030eaf1194c21c692a534196063db72176b0c4028e140f8f32c \
+ --hash=sha256:7a68b554d356a91cce1236aa7682dc01df0edba8d043fd1ce607c49dd3c1edcf \
+ --hash=sha256:7b2e5a267c855eea6b4283940daa6e88a285f5f2a67f2220203786dfa59b37e9 \
+ --hash=sha256:823b65d8706e32ad2df51ed89496147a42a2a6e01c13cfb6ffb8b1e92bc910bb \
+ --hash=sha256:8590b4ae07a35970728874632fed7bd57b26b0102df2d2b233b6d9d82f6c62ad \
+ --hash=sha256:8dd717634f5a044f860435c1d8c16a270ddf0ef8588d4887037c5028b859b0c3 \
+ --hash=sha256:8dec4936e9c3100156f8a2dc89c4b88d5c435175ff03413b443469c7c8c5f4d1 \
+ --hash=sha256:97cafb1f3cbcd3fd2b6fbfb99ae11cdb14deea0736fc2b0952ee177f2b813a46 \
+ --hash=sha256:a17a92de5231666cfbe003f0e4b9b3a7ae3afb1ec2845aadc2bacc93ff85febc \
+ --hash=sha256:a549b9c31bec33820e885335b451286e2969a2d9e24879f83fe904a5ce59d70a \
+ --hash=sha256:ac07bad82163452a6884fe8fa0963fb98c2346ba78d779ec06bd7a6262132aee \
+ --hash=sha256:ae2ad8ae6ebee9d2d94b17fb62763125f3f374c25618198f40cbb8b525411900 \
+ --hash=sha256:b91c037585eba9095565a3556f611e3cbfaa42ca1e865f7b8015fe5c7336d5a5 \
+ --hash=sha256:bc1667f8b83f48511b94671e0e441401371dfd0f0a795c7daa4a3cd1dde55bea \
+ --hash=sha256:bec0a414d016ac1a18862a519e54b2fd0fc8bbfd6890376898a6c0891dd82e9f \
+ --hash=sha256:bf50cd79a75d181c9181df03572cdce0fbb75cc353bc350712073108cba98de5 \
+ --hash=sha256:bff1b4290a66b490a2f4719358c0cdcd9bafb6b8f061e45c7a2460866bf50c2e \
+ --hash=sha256:c061bb86a71b42465156a3ee7bd58c8c2ceacdbeb95d05a99893e08b8467359a \
+ --hash=sha256:c8b29db45f8fe46ad280a7294f5c3ec36dbac9491f2d1c17345be8e69cc5928f \
+ --hash=sha256:ce409136744f6521e39fd8e2a24c53fa18ad67aa5bc7c2cf83645cce5b5c4e50 \
+ --hash=sha256:d050b3361367a06d752db6ead6e7edeb0009be66bc3bae0ee9d97fb326badc2a \
+ --hash=sha256:d283d37a890ba4c1ae73ffadf8046435c76e7bc2247bbb63c00bd1a709c6544b \
+ --hash=sha256:d9fad5155d72433c921b782e58892377c44bd6252b5af2f67f16b194987338a4 \
+ --hash=sha256:daa4ee5a243f0f20d528d939d06670a298dd39b1ad5f8a72a4275124a7819eff \
+ --hash=sha256:db0b55e0f3cc0be60c1f19efdde9a637c32740486004f20d1cff53c3c0ece4d2 \
+ --hash=sha256:e61659ba32cf2cf1481e575d0462554625196a1f2fc06a1c777d3f48e8865d46 \
+ --hash=sha256:ea3d8a3d18833cf4304cd2fc9cbb1efe188ca9b5efef2bdac7adc20594a0e46b \
+ --hash=sha256:ec6a563cff360b50eed26f13adc43e61bc0c04d94b8be985e6fb24b81f6dcfdf \
+ --hash=sha256:f5dfb42c4604dddc8e4305050aa6deb084540643ed5804d7455b5df8fe16f5e5 \
+ --hash=sha256:fa173ec60341d6bb97a89f5ea19c85c5643c1e7dedebc22f5181eb73573142c5 \
+ --hash=sha256:fa9db3f79de01457b03d4f01b34cf91bc0048eb2c3846ff26f66687c2f6d16ab \
+ --hash=sha256:fce659a462a1be54d2ffcacea5e3ba2d74daa74f30f5f143fe0c58636e355fdd \
+ --hash=sha256:ffee1f21e5ef0d712f9033568f8344d5da8cc2869dbd08d87c84656e6a2d2f68
+ # via
+ # jinja2
+ # mako
+ # mkdocs
+ # werkzeug
+matplotlib==3.9.2 \
+ --hash=sha256:039082812cacd6c6bec8e17a9c1e6baca230d4116d522e81e1f63a74d01d2e21 \
+ --hash=sha256:03ba9c1299c920964e8d3857ba27173b4dbb51ca4bab47ffc2c2ba0eb5e2cbc5 \
+ --hash=sha256:050598c2b29e0b9832cde72bcf97627bf00262adbc4a54e2b856426bb2ef0697 \
+ --hash=sha256:18128cc08f0d3cfff10b76baa2f296fc28c4607368a8402de61bb3f2eb33c7d9 \
+ --hash=sha256:1cd93b91ab47a3616b4d3c42b52f8363b88ca021e340804c6ab2536344fad9ca \
+ --hash=sha256:1d94ff717eb2bd0b58fe66380bd8b14ac35f48a98e7c6765117fe67fb7684e64 \
+ --hash=sha256:306c8dfc73239f0e72ac50e5a9cf19cc4e8e331dd0c54f5e69ca8758550f1e1e \
+ --hash=sha256:37e51dd1c2db16ede9cfd7b5cabdfc818b2c6397c83f8b10e0e797501c963a03 \
+ --hash=sha256:3fd595f34aa8a55b7fc8bf9ebea8aa665a84c82d275190a61118d33fbc82ccae \
+ --hash=sha256:4876d7d40219e8ae8bb70f9263bcbe5714415acfdf781086601211335e24f8aa \
+ --hash=sha256:5413401594cfaff0052f9d8b1aafc6d305b4bd7c4331dccd18f561ff7e1d3bd3 \
+ --hash=sha256:5816b1e1fe8c192cbc013f8f3e3368ac56fbecf02fb41b8f8559303f24c5015e \
+ --hash=sha256:65aacf95b62272d568044531e41de26285d54aec8cb859031f511f84bd8b495a \
+ --hash=sha256:6758baae2ed64f2331d4fd19be38b7b4eae3ecec210049a26b6a4f3ae1c85dcc \
+ --hash=sha256:6d1ce5ed2aefcdce11904fc5bbea7d9c21fff3d5f543841edf3dea84451a09ea \
+ --hash=sha256:6d9f07a80deab4bb0b82858a9e9ad53d1382fd122be8cde11080f4e7dfedb38b \
+ --hash=sha256:7741f26a58a240f43bee74965c4882b6c93df3e7eb3de160126d8c8f53a6ae6e \
+ --hash=sha256:8912ef7c2362f7193b5819d17dae8629b34a95c58603d781329712ada83f9447 \
+ --hash=sha256:909645cce2dc28b735674ce0931a4ac94e12f5b13f6bb0b5a5e65e7cea2c192b \
+ --hash=sha256:96ab43906269ca64a6366934106fa01534454a69e471b7bf3d79083981aaab92 \
+ --hash=sha256:9d78bbc0cbc891ad55b4f39a48c22182e9bdaea7fc0e5dbd364f49f729ca1bbb \
+ --hash=sha256:ab68d50c06938ef28681073327795c5db99bb4666214d2d5f880ed11aeaded66 \
+ --hash=sha256:ac43031375a65c3196bee99f6001e7fa5bdfb00ddf43379d3c0609bdca042df9 \
+ --hash=sha256:ae82a14dab96fbfad7965403c643cafe6515e386de723e498cf3eeb1e0b70cc7 \
+ --hash=sha256:b2696efdc08648536efd4e1601b5fd491fd47f4db97a5fbfd175549a7365c1b2 \
+ --hash=sha256:b82c5045cebcecd8496a4d694d43f9cc84aeeb49fe2133e036b207abe73f4d30 \
+ --hash=sha256:be0fc24a5e4531ae4d8e858a1a548c1fe33b176bb13eff7f9d0d38ce5112a27d \
+ --hash=sha256:bf81de2926c2db243c9b2cbc3917619a0fc85796c6ba4e58f541df814bbf83c7 \
+ --hash=sha256:c375cc72229614632c87355366bdf2570c2dac01ac66b8ad048d2dabadf2d0d4 \
+ --hash=sha256:c797dac8bb9c7a3fd3382b16fe8f215b4cf0f22adccea36f1545a6d7be310b41 \
+ --hash=sha256:cef2a73d06601437be399908cf13aee74e86932a5ccc6ccdf173408ebc5f6bb2 \
+ --hash=sha256:d52a3b618cb1cbb769ce2ee1dcdb333c3ab6e823944e9a2d36e37253815f9556 \
+ --hash=sha256:d719465db13267bcef19ea8954a971db03b9f48b4647e3860e4bc8e6ed86610f \
+ --hash=sha256:d8dd059447824eec055e829258ab092b56bb0579fc3164fa09c64f3acd478772 \
+ --hash=sha256:dbe196377a8248972f5cede786d4c5508ed5f5ca4a1e09b44bda889958b33f8c \
+ --hash=sha256:e0830e188029c14e891fadd99702fd90d317df294c3298aad682739c5533721a \
+ --hash=sha256:f053c40f94bc51bc03832a41b4f153d83f2062d88c72b5e79997072594e97e51 \
+ --hash=sha256:f32c7410c7f246838a77d6d1eff0c0f87f3cb0e7c4247aebea71a6d5a68cab49 \
+ --hash=sha256:f6ee45bc4245533111ced13f1f2cace1e7f89d1c793390392a80c139d6cf0e6c \
+ --hash=sha256:f7c0410f181a531ec4e93bbc27692f2c71a15c2da16766f5ba9761e7ae518413
# via -r tools/python/requirements.txt
+mdurl==0.1.2 \
+ --hash=sha256:84008a41e51615a49fc9966191ff91509e3c40b939176e643fd50a5c2196b8f8 \
+ --hash=sha256:bb413d29f5eea38f31dd4754dd7377d4465116fb207585f97bf925588687c1ba
+ # via markdown-it-py
mergedeep==1.3.4 \
--hash=sha256:0096d52e9dad9939c3d975a774666af186eda617e6ca84df4c94dec30004f2a8 \
--hash=sha256:70775750742b25c0d8f36c55aed03d24c3384d17c951b3175d898bd778ef0307
- # via mkdocs
-mkdocs==1.4.2 \
- --hash=sha256:8947af423a6d0facf41ea1195b8e1e8c85ad94ac95ae307fe11232e0424b11c5 \
- --hash=sha256:c8856a832c1e56702577023cd64cc5f84948280c1c0fcc6af4cd39006ea6aa8c
+ # via
+ # mkdocs
+ # mkdocs-get-deps
+mkdocs==1.6.1 \
+ --hash=sha256:7b432f01d928c084353ab39c57282f29f92136665bdd6abf7c1ec8d822ef86f2 \
+ --hash=sha256:db91759624d1647f3f34aa0c3f327dd2601beae39a366d6e064c03468d35c20e
# via -r tools/python/requirements.txt
+mkdocs-get-deps==0.2.0 \
+ --hash=sha256:162b3d129c7fad9b19abfdcb9c1458a651628e4b1dea628ac68790fb3061c60c \
+ --hash=sha256:2bf11d0b133e77a0dd036abeeb06dec8775e46efa526dc70667d8863eefc6134
+ # via mkdocs
+ml-collections==0.1.1 \
+ --hash=sha256:3fefcc72ec433aa1e5d32307a3e474bbb67f405be814ea52a2166bfc9dbe68cc
+ # via clu
ml-dtypes==0.4.0 \
--hash=sha256:03e7cda6ef164eed0abb31df69d2c00c3a5ab3e2610b6d4c42183a43329c72a5 \
--hash=sha256:2bb83fd064db43e67e67d021e547698af4c8d5c6190f2e9b1c53c09f6ff5531d \
@@ -385,57 +1207,157 @@
# via
# jax
# jaxlib
+ # keras
+ # tensorflow
+ # tensorstore
mpmath==1.3.0 \
--hash=sha256:7a28eb2a9774d00c7bc92411c19a89209d5da7c4c9a9e227be8330a23a25b91f \
--hash=sha256:a0b2b9fe80bbcd81a6647ff13108738cfb482d481d826cc0e02f5b35e5c88d2c
# via sympy
-numpy==1.25.2 \
- --hash=sha256:0d60fbae8e0019865fc4784745814cff1c421df5afee233db6d88ab4f14655a2 \
- --hash=sha256:1a1329e26f46230bf77b02cc19e900db9b52f398d6722ca853349a782d4cff55 \
- --hash=sha256:1b9735c27cea5d995496f46a8b1cd7b408b3f34b6d50459d9ac8fe3a20cc17bf \
- --hash=sha256:2792d23d62ec51e50ce4d4b7d73de8f67a2fd3ea710dcbc8563a51a03fb07b01 \
- --hash=sha256:3e0746410e73384e70d286f93abf2520035250aad8c5714240b0492a7302fdca \
- --hash=sha256:4c3abc71e8b6edba80a01a52e66d83c5d14433cbcd26a40c329ec7ed09f37901 \
- --hash=sha256:5883c06bb92f2e6c8181df7b39971a5fb436288db58b5a1c3967702d4278691d \
- --hash=sha256:5c97325a0ba6f9d041feb9390924614b60b99209a71a69c876f71052521d42a4 \
- --hash=sha256:60e7f0f7f6d0eee8364b9a6304c2845b9c491ac706048c7e8cf47b83123b8dbf \
- --hash=sha256:76b4115d42a7dfc5d485d358728cdd8719be33cc5ec6ec08632a5d6fca2ed380 \
- --hash=sha256:7dc869c0c75988e1c693d0e2d5b26034644399dd929bc049db55395b1379e044 \
- --hash=sha256:834b386f2b8210dca38c71a6e0f4fd6922f7d3fcff935dbe3a570945acb1b545 \
- --hash=sha256:8b77775f4b7df768967a7c8b3567e309f617dd5e99aeb886fa14dc1a0791141f \
- --hash=sha256:90319e4f002795ccfc9050110bbbaa16c944b1c37c0baeea43c5fb881693ae1f \
- --hash=sha256:b79e513d7aac42ae918db3ad1341a015488530d0bb2a6abcbdd10a3a829ccfd3 \
- --hash=sha256:bb33d5a1cf360304754913a350edda36d5b8c5331a8237268c48f91253c3a364 \
- --hash=sha256:bec1e7213c7cb00d67093247f8c4db156fd03075f49876957dca4711306d39c9 \
- --hash=sha256:c5462d19336db4560041517dbb7759c21d181a67cb01b36ca109b2ae37d32418 \
- --hash=sha256:c5652ea24d33585ea39eb6a6a15dac87a1206a692719ff45d53c5282e66d4a8f \
- --hash=sha256:d7806500e4f5bdd04095e849265e55de20d8cc4b661b038957354327f6d9b295 \
- --hash=sha256:db3ccc4e37a6873045580d413fe79b68e47a681af8db2e046f1dacfa11f86eb3 \
- --hash=sha256:dfe4a913e29b418d096e696ddd422d8a5d13ffba4ea91f9f60440a3b759b0187 \
- --hash=sha256:eb942bfb6f84df5ce05dbf4b46673ffed0d3da59f13635ea9b926af3deb76926 \
- --hash=sha256:f08f2e037bba04e707eebf4bc934f1972a315c883a9e0ebfa8a7756eabf9e357 \
- --hash=sha256:fd608e19c8d7c55021dffd43bfe5492fab8cc105cc8986f813f8c3c048b38760
+msgpack==1.0.8 \
+ --hash=sha256:00e073efcba9ea99db5acef3959efa45b52bc67b61b00823d2a1a6944bf45982 \
+ --hash=sha256:0726c282d188e204281ebd8de31724b7d749adebc086873a59efb8cf7ae27df3 \
+ --hash=sha256:0ceea77719d45c839fd73abcb190b8390412a890df2f83fb8cf49b2a4b5c2f40 \
+ --hash=sha256:114be227f5213ef8b215c22dde19532f5da9652e56e8ce969bf0a26d7c419fee \
+ --hash=sha256:13577ec9e247f8741c84d06b9ece5f654920d8365a4b636ce0e44f15e07ec693 \
+ --hash=sha256:1876b0b653a808fcd50123b953af170c535027bf1d053b59790eebb0aeb38950 \
+ --hash=sha256:1ab0bbcd4d1f7b6991ee7c753655b481c50084294218de69365f8f1970d4c151 \
+ --hash=sha256:1cce488457370ffd1f953846f82323cb6b2ad2190987cd4d70b2713e17268d24 \
+ --hash=sha256:26ee97a8261e6e35885c2ecd2fd4a6d38252246f94a2aec23665a4e66d066305 \
+ --hash=sha256:3528807cbbb7f315bb81959d5961855e7ba52aa60a3097151cb21956fbc7502b \
+ --hash=sha256:374a8e88ddab84b9ada695d255679fb99c53513c0a51778796fcf0944d6c789c \
+ --hash=sha256:376081f471a2ef24828b83a641a02c575d6103a3ad7fd7dade5486cad10ea659 \
+ --hash=sha256:3923a1778f7e5ef31865893fdca12a8d7dc03a44b33e2a5f3295416314c09f5d \
+ --hash=sha256:4916727e31c28be8beaf11cf117d6f6f188dcc36daae4e851fee88646f5b6b18 \
+ --hash=sha256:493c5c5e44b06d6c9268ce21b302c9ca055c1fd3484c25ba41d34476c76ee746 \
+ --hash=sha256:505fe3d03856ac7d215dbe005414bc28505d26f0c128906037e66d98c4e95868 \
+ --hash=sha256:5845fdf5e5d5b78a49b826fcdc0eb2e2aa7191980e3d2cfd2a30303a74f212e2 \
+ --hash=sha256:5c330eace3dd100bdb54b5653b966de7f51c26ec4a7d4e87132d9b4f738220ba \
+ --hash=sha256:5dbf059fb4b7c240c873c1245ee112505be27497e90f7c6591261c7d3c3a8228 \
+ --hash=sha256:5e390971d082dba073c05dbd56322427d3280b7cc8b53484c9377adfbae67dc2 \
+ --hash=sha256:5fbb160554e319f7b22ecf530a80a3ff496d38e8e07ae763b9e82fadfe96f273 \
+ --hash=sha256:64d0fcd436c5683fdd7c907eeae5e2cbb5eb872fafbc03a43609d7941840995c \
+ --hash=sha256:69284049d07fce531c17404fcba2bb1df472bc2dcdac642ae71a2d079d950653 \
+ --hash=sha256:6a0e76621f6e1f908ae52860bdcb58e1ca85231a9b0545e64509c931dd34275a \
+ --hash=sha256:73ee792784d48aa338bba28063e19a27e8d989344f34aad14ea6e1b9bd83f596 \
+ --hash=sha256:74398a4cf19de42e1498368c36eed45d9528f5fd0155241e82c4082b7e16cffd \
+ --hash=sha256:7938111ed1358f536daf311be244f34df7bf3cdedb3ed883787aca97778b28d8 \
+ --hash=sha256:82d92c773fbc6942a7a8b520d22c11cfc8fd83bba86116bfcf962c2f5c2ecdaa \
+ --hash=sha256:83b5c044f3eff2a6534768ccfd50425939e7a8b5cf9a7261c385de1e20dcfc85 \
+ --hash=sha256:8db8e423192303ed77cff4dce3a4b88dbfaf43979d280181558af5e2c3c71afc \
+ --hash=sha256:9517004e21664f2b5a5fd6333b0731b9cf0817403a941b393d89a2f1dc2bd836 \
+ --hash=sha256:95c02b0e27e706e48d0e5426d1710ca78e0f0628d6e89d5b5a5b91a5f12274f3 \
+ --hash=sha256:99881222f4a8c2f641f25703963a5cefb076adffd959e0558dc9f803a52d6a58 \
+ --hash=sha256:9ee32dcb8e531adae1f1ca568822e9b3a738369b3b686d1477cbc643c4a9c128 \
+ --hash=sha256:a22e47578b30a3e199ab067a4d43d790249b3c0587d9a771921f86250c8435db \
+ --hash=sha256:b5505774ea2a73a86ea176e8a9a4a7c8bf5d521050f0f6f8426afe798689243f \
+ --hash=sha256:bd739c9251d01e0279ce729e37b39d49a08c0420d3fee7f2a4968c0576678f77 \
+ --hash=sha256:d16a786905034e7e34098634b184a7d81f91d4c3d246edc6bd7aefb2fd8ea6ad \
+ --hash=sha256:d3420522057ebab1728b21ad473aa950026d07cb09da41103f8e597dfbfaeb13 \
+ --hash=sha256:d56fd9f1f1cdc8227d7b7918f55091349741904d9520c65f0139a9755952c9e8 \
+ --hash=sha256:d661dc4785affa9d0edfdd1e59ec056a58b3dbb9f196fa43587f3ddac654ac7b \
+ --hash=sha256:dfe1f0f0ed5785c187144c46a292b8c34c1295c01da12e10ccddfc16def4448a \
+ --hash=sha256:e1dd7839443592d00e96db831eddb4111a2a81a46b028f0facd60a09ebbdd543 \
+ --hash=sha256:e2872993e209f7ed04d963e4b4fbae72d034844ec66bc4ca403329db2074377b \
+ --hash=sha256:e2f879ab92ce502a1e65fce390eab619774dda6a6ff719718069ac94084098ce \
+ --hash=sha256:e3aa7e51d738e0ec0afbed661261513b38b3014754c9459508399baf14ae0c9d \
+ --hash=sha256:e532dbd6ddfe13946de050d7474e3f5fb6ec774fbb1a188aaf469b08cf04189a \
+ --hash=sha256:e6b7842518a63a9f17107eb176320960ec095a8ee3b4420b5f688e24bf50c53c \
+ --hash=sha256:e75753aeda0ddc4c28dce4c32ba2f6ec30b1b02f6c0b14e547841ba5b24f753f \
+ --hash=sha256:eadb9f826c138e6cf3c49d6f8de88225a3c0ab181a9b4ba792e006e5292d150e \
+ --hash=sha256:ed59dd52075f8fc91da6053b12e8c89e37aa043f8986efd89e61fae69dc1b011 \
+ --hash=sha256:ef254a06bcea461e65ff0373d8a0dd1ed3aa004af48839f002a0c994a6f72d04 \
+ --hash=sha256:f3709997b228685fe53e8c433e2df9f0cdb5f4542bd5114ed17ac3c0129b0480 \
+ --hash=sha256:f51bab98d52739c50c56658cc303f190785f9a2cd97b823357e7aeae54c8f68a \
+ --hash=sha256:f9904e24646570539a8950400602d66d2b2c492b9010ea7e965025cb71d0c86d \
+ --hash=sha256:f9af38a89b6a5c04b7d18c492c8ccf2aee7048aff1ce8437c4683bb5a1df893d
+ # via
+ # flax
+ # orbax-checkpoint
+namex==0.0.8 \
+ --hash=sha256:32a50f6c565c0bb10aa76298c959507abdc0e850efe085dc38f3440fcb3aa90b \
+ --hash=sha256:7ddb6c2bb0e753a311b7590f84f6da659dd0c05e65cb89d519d54c0a250c0487
+ # via keras
+nest-asyncio==1.6.0 \
+ --hash=sha256:6f172d5449aca15afd6c646851f4e31e02c598d553a667e38cafa997cfec55fe \
+ --hash=sha256:87af6efd6b5e897c81050477ef65c62e2b2f35d51703cae01aff2905b1852e1c
+ # via orbax-checkpoint
+numpy==1.26.4 \
+ --hash=sha256:03a8c78d01d9781b28a6989f6fa1bb2c4f2d51201cf99d3dd875df6fbd96b23b \
+ --hash=sha256:08beddf13648eb95f8d867350f6a018a4be2e5ad54c8d8caed89ebca558b2818 \
+ --hash=sha256:1af303d6b2210eb850fcf03064d364652b7120803a0b872f5211f5234b399f20 \
+ --hash=sha256:1dda2e7b4ec9dd512f84935c5f126c8bd8b9f2fc001e9f54af255e8c5f16b0e0 \
+ --hash=sha256:2a02aba9ed12e4ac4eb3ea9421c420301a0c6460d9830d74a9df87efa4912010 \
+ --hash=sha256:2e4ee3380d6de9c9ec04745830fd9e2eccb3e6cf790d39d7b98ffd19b0dd754a \
+ --hash=sha256:3373d5d70a5fe74a2c1bb6d2cfd9609ecf686d47a2d7b1d37a8f3b6bf6003aea \
+ --hash=sha256:47711010ad8555514b434df65f7d7b076bb8261df1ca9bb78f53d3b2db02e95c \
+ --hash=sha256:4c66707fabe114439db9068ee468c26bbdf909cac0fb58686a42a24de1760c71 \
+ --hash=sha256:50193e430acfc1346175fcbdaa28ffec49947a06918b7b92130744e81e640110 \
+ --hash=sha256:52b8b60467cd7dd1e9ed082188b4e6bb35aa5cdd01777621a1658910745b90be \
+ --hash=sha256:60dedbb91afcbfdc9bc0b1f3f402804070deed7392c23eb7a7f07fa857868e8a \
+ --hash=sha256:62b8e4b1e28009ef2846b4c7852046736bab361f7aeadeb6a5b89ebec3c7055a \
+ --hash=sha256:666dbfb6ec68962c033a450943ded891bed2d54e6755e35e5835d63f4f6931d5 \
+ --hash=sha256:675d61ffbfa78604709862923189bad94014bef562cc35cf61d3a07bba02a7ed \
+ --hash=sha256:679b0076f67ecc0138fd2ede3a8fd196dddc2ad3254069bcb9faf9a79b1cebcd \
+ --hash=sha256:7349ab0fa0c429c82442a27a9673fc802ffdb7c7775fad780226cb234965e53c \
+ --hash=sha256:7ab55401287bfec946ced39700c053796e7cc0e3acbef09993a9ad2adba6ca6e \
+ --hash=sha256:7e50d0a0cc3189f9cb0aeb3a6a6af18c16f59f004b866cd2be1c14b36134a4a0 \
+ --hash=sha256:95a7476c59002f2f6c590b9b7b998306fba6a5aa646b1e22ddfeaf8f78c3a29c \
+ --hash=sha256:96ff0b2ad353d8f990b63294c8986f1ec3cb19d749234014f4e7eb0112ceba5a \
+ --hash=sha256:9fad7dcb1aac3c7f0584a5a8133e3a43eeb2fe127f47e3632d43d677c66c102b \
+ --hash=sha256:9ff0f4f29c51e2803569d7a51c2304de5554655a60c5d776e35b4a41413830d0 \
+ --hash=sha256:a354325ee03388678242a4d7ebcd08b5c727033fcff3b2f536aea978e15ee9e6 \
+ --hash=sha256:a4abb4f9001ad2858e7ac189089c42178fcce737e4169dc61321660f1a96c7d2 \
+ --hash=sha256:ab47dbe5cc8210f55aa58e4805fe224dac469cde56b9f731a4c098b91917159a \
+ --hash=sha256:afedb719a9dcfc7eaf2287b839d8198e06dcd4cb5d276a3df279231138e83d30 \
+ --hash=sha256:b3ce300f3644fb06443ee2222c2201dd3a89ea6040541412b8fa189341847218 \
+ --hash=sha256:b97fe8060236edf3662adfc2c633f56a08ae30560c56310562cb4f95500022d5 \
+ --hash=sha256:bfe25acf8b437eb2a8b2d49d443800a5f18508cd811fea3181723922a8a82b07 \
+ --hash=sha256:cd25bcecc4974d09257ffcd1f098ee778f7834c3ad767fe5db785be9a4aa9cb2 \
+ --hash=sha256:d209d8969599b27ad20994c8e41936ee0964e6da07478d6c35016bc386b66ad4 \
+ --hash=sha256:d5241e0a80d808d70546c697135da2c613f30e28251ff8307eb72ba696945764 \
+ --hash=sha256:edd8b5fe47dab091176d21bb6de568acdd906d1887a4584a15a9a96a1dca06ef \
+ --hash=sha256:f870204a840a60da0b12273ef34f7051e98c3b5961b61b0c2c1be6dfd64fbcd3 \
+ --hash=sha256:ffa75af20b44f8dba823498024771d5ac50620e6915abac414251bd971b4529f
# via
# -r tools/python/requirements.txt
+ # aim
# bokeh
# casadi
+ # chex
+ # clu
# contourpy
+ # etils
+ # flashbax
+ # flax
+ # h5py
# jax
# jaxlib
+ # keras
# matplotlib
# ml-dtypes
# opencv-python
# opt-einsum
+ # optax
+ # orbax-checkpoint
# osqp
# pandas
# qdldl
# scipy
# shapely
+ # tensorboard
+ # tensorflow
+ # tensorflow-datasets
+ # tensorflow-probability
+ # tensorstore
nvidia-cublas-cu12==12.6.1.4 \
--hash=sha256:5dd125ece5469dbdceebe2e9536ad8fc4abd38aa394a7ace42fc8a930a1e81e3 \
--hash=sha256:5e5d384583d72ac364064ced3dd92a5caa59a8a57568595c9f82e83d255b2481 \
--hash=sha256:c25ab29026a265d46c1063b5fb3cb9440f5f2eb88041c6b7c6711bcb3361789f
- # via jax-cuda12-plugin
+ # via
+ # jax-cuda12-plugin
+ # nvidia-cudnn-cu12
+ # nvidia-cusolver-cu12
nvidia-cuda-cupti-cu12==12.6.68 \
--hash=sha256:13408a021727de6473d138a0c5e8080b23437f761508e2b11d2530fed24f4ea0 \
--hash=sha256:5ad6a1fcfcb42c8628f7e547079575116d428d0cb3b4fab98362e08a9ea0b842 \
@@ -470,7 +1392,9 @@
--hash=sha256:76030755020d3a969b40273f43b8c496c4e122ee2a01fd724cf1398421bcadd8 \
--hash=sha256:bfa07cb86edfd6112dbead189c182a924fd9cb3e48ae117b1ac4cd3084078bc0 \
--hash=sha256:c9d0ff7870672b1e0c7ffc1e47e9b87b51e38ad32ae39e05f08fc68933983a80
- # via jax-cuda12-plugin
+ # via
+ # jax-cuda12-plugin
+ # nvidia-cusolver-cu12
nvidia-nccl-cu12==2.22.3 \
--hash=sha256:f9f5e03c00269dee2cd1aa57019f9a024478a74ae6e9b32d5341c849fe6f6302
# via jax-cuda12-plugin
@@ -478,54 +1402,155 @@
--hash=sha256:125a6c2a44e96386dda634e13d944e60b07a0402d391a070e8fb4104b34ea1ab \
--hash=sha256:a55744c98d70317c5e23db14866a8cc2b733f7324509e941fc96276f9f37801d \
--hash=sha256:b3fd0779845f68b92063ab1393abab1ed0a23412fc520df79a8190d098b5cd6b
- # via jax-cuda12-plugin
-opencv-python==4.6.0.66 \
- --hash=sha256:0dc82a3d8630c099d2f3ac1b1aabee164e8188db54a786abb7a4e27eba309440 \
- --hash=sha256:5af8ba35a4fcb8913ffb86e92403e9a656a4bff4a645d196987468f0f8947875 \
- --hash=sha256:6e32af22e3202748bd233ed8f538741876191863882eba44e332d1a34993165b \
- --hash=sha256:c5bfae41ad4031e66bb10ec4a0a2ffd3e514d092652781e8b1ac98d1b59f1158 \
- --hash=sha256:dbdc84a9b4ea2cbae33861652d25093944b9959279200b7ae0badd32439f74de \
- --hash=sha256:e6e448b62afc95c5b58f97e87ef84699e6607fe5c58730a03301c52496005cae \
- --hash=sha256:f482e78de6e7b0b060ff994ffd859bddc3f7f382bb2019ef157b0ea8ca8712f5
+ # via
+ # jax-cuda12-plugin
+ # nvidia-cufft-cu12
+ # nvidia-cusolver-cu12
+ # nvidia-cusparse-cu12
+opencv-python==4.10.0.84 \
+ --hash=sha256:09a332b50488e2dda866a6c5573ee192fe3583239fb26ff2f7f9ceb0bc119ea6 \
+ --hash=sha256:2db02bb7e50b703f0a2d50c50ced72e95c574e1e5a0bb35a8a86d0b35c98c236 \
+ --hash=sha256:32dbbd94c26f611dc5cc6979e6b7aa1f55a64d6b463cc1dcd3c95505a63e48fe \
+ --hash=sha256:71e575744f1d23f79741450254660442785f45a0797212852ee5199ef12eed98 \
+ --hash=sha256:72d234e4582e9658ffea8e9cae5b63d488ad06994ef12d81dc303b17472f3526 \
+ --hash=sha256:9ace140fc6d647fbe1c692bcb2abce768973491222c067c131d80957c595b71f \
+ --hash=sha256:fc182f8f4cda51b45f01c64e4cbedfc2f00aff799debebc305d8d0210c43f251
# via -r tools/python/requirements.txt
opt-einsum==3.3.0 \
--hash=sha256:2455e59e3947d3c275477df7f5205b30635e266fe6dc300e3d9f9646bfcea147 \
--hash=sha256:59f6475f77bbc37dcf7cd748519c0ec60722e91e63ca114e68821c0c54a46549
- # via jax
-osqp==0.6.2.post8 \
- --hash=sha256:02175818a0b1715ae0aab88a23678a44b269587af0ef655457042ca69a45eddd \
- --hash=sha256:0a6e36151d088a9196b24fffc6b1d3a8bf79dcf9e7a5bd5f9c76c9ee1e019edf \
- --hash=sha256:1d635a321686d15aaf2d91b05f41f736333d6adb0639bc14fc1c22b2cfce9c80 \
- --hash=sha256:1ecbd173c21805b64a0b736d051312241a84327759526505578f83f7dcc81c66 \
- --hash=sha256:22724b3ac4eaf17582e3ff35cb6660c026e71138f27fc21dbae4f1dc60904c64 \
- --hash=sha256:23d6bae4a3612f60d5f652d0e5fa4b2ead507cabfff5d930d822057ae6ed6677 \
- --hash=sha256:2cc3a966afc4c6ef29dbeb92c59aec7479451149bb77f5c318767433da2c1863 \
- --hash=sha256:2d39020616c8b4fd9b3ec11f96bd3d68f366ab161323ecb9c1f9c7024eda2d28 \
- --hash=sha256:2f8647e63bba38f57161d80dda251c06c290bb99e4767cc58a37727ee3c8b912 \
- --hash=sha256:470c07e7dd06588576155133ae9aea62077dbaa4310aa8e387e879403de42369 \
- --hash=sha256:497a2fb0d14d20185eaa32aa5f98374fe9a57df09ed0aedb2c27c37d0aa54afa \
- --hash=sha256:52daa25502056aa1643e2d23ee230a7fe1c399e1a8b35a7b5dd2b77c7b356007 \
- --hash=sha256:58b38557b0a6181dff8f557244758b955ff27384a1f67b83d75e51fd34c9e842 \
- --hash=sha256:6a009c100eaaf93e9b2b790af61e209090d2a60b629893e21052d7216e572bbe \
- --hash=sha256:7f888eaa54bac0261cadb145b3bcf8b2da9109cbf53fc4fdbdc6c6f6c04e2bb9 \
- --hash=sha256:866f1bc2386b15393a68d379447808bbf3c8b2a126b0fc0669b27fcf3985b86c \
- --hash=sha256:8d4920fb588d861d0d92874cb5b4435db16fe1e36a986d30638106afe374c1a8 \
- --hash=sha256:ac9c6aaebe56eae33d7545564148a8fab1d71117cbbe0eedbd2c658bc3455df9 \
- --hash=sha256:b30e7a2f49103622fdad9ed9c127c47afae01f5a8a6994d04803d3d5deadab4e \
- --hash=sha256:bd956b7af9d524aed60ab41ec47b20519aede28538dea8f3188ad9056c4c0b01 \
- --hash=sha256:c9705647d7e6171b3baaa68b0c159c43ea69cba22fbdbd8f79f86ae404a3d96f \
- --hash=sha256:dd4b2ee44ec08253bcafb4d8a45c7d8278caa0bc13ac7ed24aa35249da7f1d2a \
- --hash=sha256:dea8085760268971985bb3366bf4d5fb2e8291d7013c47e6178abb964cf05b86 \
- --hash=sha256:e2475e1417e0ff86b5cd363d9dc2796d54f2a42f67a95fc527eb2ed15df6a1ac \
- --hash=sha256:f30b405ec0e6a2acf52f59e04f1c258480be172f64c2d37c24adcbf2ac400548
- # via -r tools/python/requirements.txt
-packaging==21.3 \
- --hash=sha256:dd47c42927d89ab911e606518907cc2d3a1f38bbd026385970643f9c5b8ecfeb \
- --hash=sha256:ef103e05f519cdc783ae24ea4e2e0f508a9c99b2d4969652eed6a2e1ea5bd522
# via
+ # jax
+ # tensorflow
+optax==0.2.3 \
+ --hash=sha256:083e603dcd731d7e74d99f71c12f77937dd53f79001b4c09c290e4f47dd2e94f \
+ --hash=sha256:ec7ab925440b0c5a512e1f24fba0fb3e7d760a7fd5d2496d7a691e9d37da01d9
+ # via
+ # -r tools/python/requirements.txt
+ # flax
+optree==0.12.1 \
+ --hash=sha256:06d6ef39b3ef9920d6cdb6d3d1d2804a37092d24dc406c4cb9b46cd6c9a44e89 \
+ --hash=sha256:154738def491199d3fbcd919437315728e0a1caeaf4ec06688c76ef9d56e5ed6 \
+ --hash=sha256:1b2fe5c04c218698a53ed2d4b7372f1989df8cf0a61d616e6f384770d8a5fb1c \
+ --hash=sha256:1d76905bced5cf569d23dc4890341fae2fa257cce58a492a1603afcdc5969ae7 \
+ --hash=sha256:1f8baf0ad6b58843d24fa8caf079cf1f0c33cc3658263cff960b5c1d0cc53bc8 \
+ --hash=sha256:23afe4aae42336bdf8cf4fba35c56593405bf8f8e163627f722205b3bf0d9310 \
+ --hash=sha256:24d74a9d97d7bdbdbb30356850f204950c39ab8fad7f273ed29d1feda19060b2 \
+ --hash=sha256:27ae426745931ae1c2ccd7a78b27f9b7402167e0600fa62e2ef1cd58727e7b94 \
+ --hash=sha256:2a1a9905d2d917d5aff775283e0a59be2c6b529a219241c248d50b3ad51c6cce \
+ --hash=sha256:2d4d8e024b841f99907b2340fee7ac9994fbe300383a9af6c93578d12861a969 \
+ --hash=sha256:2de1297b2bf019379ab86103e31caa97c8a08628f0c8b58cd7709f9048c589eb \
+ --hash=sha256:349aafac463642979f7fe7ca3aa9e2fa8a5a0f81ef7af6946a075b797673e600 \
+ --hash=sha256:35ca77b810cf5959e6930d56534ecbecc4300f5e5fa14b977030265c1c8eab6c \
+ --hash=sha256:3e323744d083bd8b4648c9ff2383f01bfbc33098656d56fdd984b2263ef905f3 \
+ --hash=sha256:404cf2decd8fb6a1a8f6fef623c98873cdf7ae086aeb8909d104cd321d829ba0 \
+ --hash=sha256:409ef6f3656299923d722509849d83607bb3e5c621dcfe6aa90ace85665e9b54 \
+ --hash=sha256:411a21eca034ddb98eb80e6c4bf552fc46b8d8ab7c4d250446d74d31a251a684 \
+ --hash=sha256:42025da0bac19cc6de756fe64511f15baffb3fa7d8402e54aab035c02903eb5c \
+ --hash=sha256:47db001a224382493ae7a8df16e7a9668e971fc129970d137995421aa6b06f8f \
+ --hash=sha256:4b32f39988bfe6e76eeefb335da529e614145f7f1dfa8583fbc4aca8a72f504b \
+ --hash=sha256:4ee926120887404e92877c99714b960bc29f572e8db69fd2e934022d80452f91 \
+ --hash=sha256:50893bd088bdb3e2f07ee481dafd848b483bea1a19cc978f2309139314e5bc7d \
+ --hash=sha256:509bddd38dae8c4e8d6b988f514b7a9fe803ca916b11af67b40520f0b1eeeaef \
+ --hash=sha256:562036d3de15204ed1a88d9fc262a7e1c20964d22ef132069e20dbd88215f983 \
+ --hash=sha256:5bfe3d3e47e10b528f9324d446c871bfad7d0be8c2bd2a2fbc3ddf1600ae8558 \
+ --hash=sha256:5c2f2e0e3978558bc8f7df8c5a999674097dd0dc71363210783eb8d7a6da8ef9 \
+ --hash=sha256:5f24b0a8b181a90a778cadc942a79336d29f0c164704d58cd20989bf7d0bea1c \
+ --hash=sha256:606983f4696d81128e205a1c34d0c9f3fe6ae12f6c26ed5e8ab3722d6f378ec2 \
+ --hash=sha256:62d232a344c14b8e94fdd6de1acf2c0b05954b05d6bb346bddb13c38be37dc09 \
+ --hash=sha256:646842f8a2de2caaacc32a8c91f8031a93eda145ac9c915bb0fd2ad5249c14b7 \
+ --hash=sha256:6d90fb28d52725352858013cafe34d98d90ab1bb86b5d8dc29d420e9bbc5706b \
+ --hash=sha256:76a2240e7482355966a73c6c701e3d1f148420a77849c78d175d3b08bf06ff36 \
+ --hash=sha256:7a71dd58522cd6258b61b639092ac7a2631d881f039ef968b31dfd555e513591 \
+ --hash=sha256:7e79eedd9406c59d542482768e490795dc6b6f1a014c7852d29d9fd61749bf94 \
+ --hash=sha256:80e0d4eba4a65d4c6f2002ed949142a40933b8185523894659c26c34693c4086 \
+ --hash=sha256:8513d6dd71807abb1037a5b5bc66b45c21afb42e9c90961fa5e762cea3943ab2 \
+ --hash=sha256:88d01ce6f78f209cad8dc4cf2d3222d7056cac93612abfd6beb40ab43a131769 \
+ --hash=sha256:9280452c11da0872ec57be5d8f153207d6303b3cbf26115b2bf6d2b8157a5343 \
+ --hash=sha256:9c473988b2d8fd7edc3958e6c7cb1d3f92afb7bcaff53b76a8f41cf4f3a24709 \
+ --hash=sha256:a11e58d7c0a71a48d74ca0a6715f4c0932c6f9409ba93d600e3326df4cf778ae \
+ --hash=sha256:a49d3cfec1a51463b63e11c889bb00207c4e040016833cd202871ad946116925 \
+ --hash=sha256:a55a79c1c72f73259532e4cbe9ff65bed9663064747db02591fb4714fe742d2e \
+ --hash=sha256:a67842cd1c5c83d74863872f06fe6ed64e44279c0378267a9805567fe3c38591 \
+ --hash=sha256:aadb26d68f1d7871507f84846d8844aa94f47402d5277ce19cfe5102bb5df9e9 \
+ --hash=sha256:afa0051335c6032ee4dfc212952dcfb3b23fe59bcd70f56d25a214e7585cd62c \
+ --hash=sha256:b1ca00bdfe4da8068c2773b7ac4c8c96d3f61b8d21eba6a8642dab23ee631b0d \
+ --hash=sha256:b43c09cf9dd28aed2efc163f4bb4808d7fad54250812960bf349399ba6972e16 \
+ --hash=sha256:b890ba0a21049addf589c314c85e98a68d3dfc84e3954491e9ce60f60cb7b0e7 \
+ --hash=sha256:ba6aed8b9684c5804a5e2d6b246c3b4a68bab793b6829d369ba1c53734852a0c \
+ --hash=sha256:bd207b43e71fb3f8c315e2e4a5444f48317b2108889e96279d5426bca730a47e \
+ --hash=sha256:c987931bd31d0f28cbff28925a875639170534a36ce178a40020aca0769d9549 \
+ --hash=sha256:ce7cb233e87a2dc127b8ec82bd61f098e6ff1e57d0a09dc110a17b38bfd73034 \
+ --hash=sha256:cefd4f4c7596cdd4c95dca431bc41284a43ebd7056e739480f157789aa34579d \
+ --hash=sha256:d0950ee245db2c40824362def1efc15621a6492419628cec1fac0061818420f7 \
+ --hash=sha256:d313303a1ce36ea55c3a96fc375c5cc64a9ab814ab2677ce64e4a7d755a9b1d0 \
+ --hash=sha256:d913122454d0e3f10dc25a1b598eaf588d225372f41ece3ad4d508bddd363e4d \
+ --hash=sha256:da37e6cc669a9840844722edb3f8dd5b4f07e99b0e8c9196089cb49af70c7b75 \
+ --hash=sha256:e124f30daf79d51b1bbbda7e74d01e637fa47aff4aa64cb082b88057535daa64 \
+ --hash=sha256:e2027217c3acaf44e5f5aabe01ba0cbf33066f3f6df870881ddf597965f80db0 \
+ --hash=sha256:e20b5569369a5f1e8faa2604799b91a1941fe17b5de8afc84c8c23ff66d8e585 \
+ --hash=sha256:e8046cbbcd5f7494ba7c6811e44a6d2867216f2bdb7cef980a9a62e31d39270c \
+ --hash=sha256:eb968d3cc1db8944f220f1a67c9db043b86b47ace90ce3cfd23f3e6500baeb65 \
+ --hash=sha256:efffa3814ab8e3aaf7bf88495e4b6d263de9689d6f02dfa4490f8f64736806ac \
+ --hash=sha256:f0460f025bf1c08f2c008b5e3628d849fcb5810345222e57879cd248fec7f9f7 \
+ --hash=sha256:f65a31d7cfab2fed2bc29ab6eabcf4205dec6e0ee3cfb7006336c4f76d78fb0e \
+ --hash=sha256:f6b98b80b1259e9817aca701beba616ce33e43e856e7d644f7e0f582b8e45565 \
+ --hash=sha256:fc1ec38d1ec43bb8358ab058c3220a70b7bfb56f2bb625f41cb09d117a0d6150 \
+ --hash=sha256:fd3ead0c64d22d692284d96c27d5091e682b002ffe5a52afacc9f1fcc8ae3180
+ # via keras
+orbax-checkpoint==0.6.1 \
+ --hash=sha256:0d41fa2c38e2fa7e84ebefa974f87f6fed152f3130af188e7911b5a42d2dc067 \
+ --hash=sha256:f7fcb1ef528cee294ea244e769eaee17de2379c68a00d6df4c3a463e5cf716a1
+ # via flax
+osqp==0.6.7.post1 \
+ --hash=sha256:117c30affdab60f5872d758c5ad82f5deb029b4fa84fea54bd04b8e7d884c5f6 \
+ --hash=sha256:1466ab570c268c070bf3199f3daf071d0a05edb3d26d44d761d209dd3e210fd6 \
+ --hash=sha256:14d221c049c2f1495a91d6683a3b0319f23d0c3e81b3aa5102e4b377ca002980 \
+ --hash=sha256:1647cf184fd29b1984267fbefe747e12c2a62aa862145af9548cd5f4611acd3c \
+ --hash=sha256:1bdfd9b13c4dfe6e4c5c3b89007b1ec4264a8bab6af87bc780a860ea38469e65 \
+ --hash=sha256:1cdbb56533954497228a086b3f6b7cfd68d44b18b74558d866ed24763e0f089a \
+ --hash=sha256:20bf96fbf7d51abb95ab75e20508e37b1217cb467fc9cc9f73a584fbf1d5fc88 \
+ --hash=sha256:39c170af5371e0eb9c96b814a65f18c79689e1b45d844bb88b0c025026f22db2 \
+ --hash=sha256:44ae75ed6a5c6aba415b8d11963cec2b9ac4d7f1897067e9e095b60e81136022 \
+ --hash=sha256:554aa10dca8481978b4d334e28201f24ed18f294c5a84350ce2022a8b78f4d72 \
+ --hash=sha256:5eb4dd5cc8f7cf1b8196572e7b952158b0f9c3e844e5adba397dd1757236fb86 \
+ --hash=sha256:7082c852edc9afc63ba7b073bb2e559093b4df4eb24efff7b2f898241a83071c \
+ --hash=sha256:85c278e833659ef79af9621cdf16acb220b8347c0dfad9c0a39b6319fb718e0f \
+ --hash=sha256:86ca79f1ae9b99bc0eb75adf8a372765c4e6e55480f1d9d504fca25e8afd923a \
+ --hash=sha256:8d8073ca5bbfdca0707a680ae43e1d2e24c26985eb8a4167bd8886b6e5f5e462 \
+ --hash=sha256:8e153385dad35e0e5b28a3ef593ec65d28eb180b3f65711b35b9113ebba6ef7c \
+ --hash=sha256:8f4980f2ad0814898396a3ea522f46d199a3412bd3b191065d4ba6837e9cc4c1 \
+ --hash=sha256:98fdee4065b9f65c37f63532ba8e11e7efddce3eb9a8b62961bf1a9b62105e0a \
+ --hash=sha256:a3b1cc48d69150c6dd25cbd7a250425d075365094bfd093f24fab8bdf23bf66b \
+ --hash=sha256:a5a41a9765be0ef1817ebfdcff10018f792e5452a5af3f2864ea44d7cb22e663 \
+ --hash=sha256:ab6e42c8af7c82f5b4b4b989a623151dca98e7bd6c131454edc8cf5cde2b3aa9 \
+ --hash=sha256:ad149ac44adc2afc7627fa711daaf36ac7e87c723f90fca0e0db9f5b2634c374 \
+ --hash=sha256:b0bd72d95d6b97ab8273cdd08c1304dfeb6071e038a0b2d34fa2aebd16cfbec5 \
+ --hash=sha256:b80e7e6c582fd9c0b1b6e8490482682d53f0c1268ee37b35e6bceac32df0aa56 \
+ --hash=sha256:c35a68c26e57f4b6d04fba9e995b7d4c75f34f9b3aaca86f72cd71ce92da8a79 \
+ --hash=sha256:d01d6b03628b851107671d7c785df147acea6865f090290a04e38ed250d8b829 \
+ --hash=sha256:d01f38e1eef93932987ec71d4e6bd99498a66ac84542a5d32fe61b6588a18200 \
+ --hash=sha256:de48f0343c58430074e42a4f4a965e045c67bf5723f951cc27f33e68d9e9d507 \
+ --hash=sha256:e1102ffb0debe74ae1c4e6afb45309a7bcf309c2a731916ea529d8ac823321c0 \
+ --hash=sha256:e37b23b794c4d229d44fb97424c760ed6bdf1ec1723466cfb4b952c9a37d56fc \
+ --hash=sha256:e99469b7986f9042925d3082cd6d02cdf012a32483603b64a713f0275de413bb \
+ --hash=sha256:ed3c98cb31296368a72145875ceab3fb3e3497fdb820a185bf6b9ee39a3d5762 \
+ --hash=sha256:f9f104c9710d8e51cded15ac9b2b9bc77bc265e70c891c671c1935e4b85b0810 \
+ --hash=sha256:fd56c7e82a6af11d96a549bb07d224359bcd148d4aae9180b8944d20eecd461b
+ # via -r tools/python/requirements.txt
+packaging==24.1 \
+ --hash=sha256:026ed72c8ed3fcce5bf8950572258698927fd1dbda10a5e981cdf0ac37f4f002 \
+ --hash=sha256:5b8f2217dbdbd2f7f384c41c628544e6d52f2d0f53c6d0c3ea61aa5d1d7ff124
+ # via
+ # aim
# bokeh
+ # clu
+ # keras
# matplotlib
# mkdocs
+ # plotly
+ # tensorboard
+ # tensorflow
pandas==2.2.2 \
--hash=sha256:001910ad31abc7bf06f49dcc903755d2f7f3a9186c0c040b827e522e9cef0863 \
--hash=sha256:0ca6377b8fca51815f382bd0b697a0814c8bda55115678cbc94c30aacbb6eff2 \
@@ -557,101 +1582,295 @@
--hash=sha256:e9b79011ff7a0f4b1d6da6a61aa1aa604fb312d6647de5bad20013682d1429ce \
--hash=sha256:eee3a87076c0756de40b05c5e9a6069c035ba43e8dd71c379e68cab2c20f16ad
# via bokeh
-pillow==9.3.0 \
- --hash=sha256:03150abd92771742d4a8cd6f2fa6246d847dcd2e332a18d0c15cc75bf6703040 \
- --hash=sha256:073adb2ae23431d3b9bcbcff3fe698b62ed47211d0716b067385538a1b0f28b8 \
- --hash=sha256:0b07fffc13f474264c336298d1b4ce01d9c5a011415b79d4ee5527bb69ae6f65 \
- --hash=sha256:0b7257127d646ff8676ec8a15520013a698d1fdc48bc2a79ba4e53df792526f2 \
- --hash=sha256:12ce4932caf2ddf3e41d17fc9c02d67126935a44b86df6a206cf0d7161548627 \
- --hash=sha256:15c42fb9dea42465dfd902fb0ecf584b8848ceb28b41ee2b58f866411be33f07 \
- --hash=sha256:18498994b29e1cf86d505edcb7edbe814d133d2232d256db8c7a8ceb34d18cef \
- --hash=sha256:1c7c8ae3864846fc95f4611c78129301e203aaa2af813b703c55d10cc1628535 \
- --hash=sha256:22b012ea2d065fd163ca096f4e37e47cd8b59cf4b0fd47bfca6abb93df70b34c \
- --hash=sha256:276a5ca930c913f714e372b2591a22c4bd3b81a418c0f6635ba832daec1cbcfc \
- --hash=sha256:2e0918e03aa0c72ea56edbb00d4d664294815aa11291a11504a377ea018330d3 \
- --hash=sha256:3033fbe1feb1b59394615a1cafaee85e49d01b51d54de0cbf6aa8e64182518a1 \
- --hash=sha256:3168434d303babf495d4ba58fc22d6604f6e2afb97adc6a423e917dab828939c \
- --hash=sha256:32a44128c4bdca7f31de5be641187367fe2a450ad83b833ef78910397db491aa \
- --hash=sha256:3dd6caf940756101205dffc5367babf288a30043d35f80936f9bfb37f8355b32 \
- --hash=sha256:40e1ce476a7804b0fb74bcfa80b0a2206ea6a882938eaba917f7a0f004b42502 \
- --hash=sha256:41e0051336807468be450d52b8edd12ac60bebaa97fe10c8b660f116e50b30e4 \
- --hash=sha256:4390e9ce199fc1951fcfa65795f239a8a4944117b5935a9317fb320e7767b40f \
- --hash=sha256:502526a2cbfa431d9fc2a079bdd9061a2397b842bb6bc4239bb176da00993812 \
- --hash=sha256:51e0e543a33ed92db9f5ef69a0356e0b1a7a6b6a71b80df99f1d181ae5875636 \
- --hash=sha256:57751894f6618fd4308ed8e0c36c333e2f5469744c34729a27532b3db106ee20 \
- --hash=sha256:5d77adcd56a42d00cc1be30843d3426aa4e660cab4a61021dc84467123f7a00c \
- --hash=sha256:655a83b0058ba47c7c52e4e2df5ecf484c1b0b0349805896dd350cbc416bdd91 \
- --hash=sha256:68943d632f1f9e3dce98908e873b3a090f6cba1cbb1b892a9e8d97c938871fbe \
- --hash=sha256:6c738585d7a9961d8c2821a1eb3dcb978d14e238be3d70f0a706f7fa9316946b \
- --hash=sha256:73bd195e43f3fadecfc50c682f5055ec32ee2c933243cafbfdec69ab1aa87cad \
- --hash=sha256:772a91fc0e03eaf922c63badeca75e91baa80fe2f5f87bdaed4280662aad25c9 \
- --hash=sha256:77ec3e7be99629898c9a6d24a09de089fa5356ee408cdffffe62d67bb75fdd72 \
- --hash=sha256:7db8b751ad307d7cf238f02101e8e36a128a6cb199326e867d1398067381bff4 \
- --hash=sha256:801ec82e4188e935c7f5e22e006d01611d6b41661bba9fe45b60e7ac1a8f84de \
- --hash=sha256:82409ffe29d70fd733ff3c1025a602abb3e67405d41b9403b00b01debc4c9a29 \
- --hash=sha256:828989c45c245518065a110434246c44a56a8b2b2f6347d1409c787e6e4651ee \
- --hash=sha256:829f97c8e258593b9daa80638aee3789b7df9da5cf1336035016d76f03b8860c \
- --hash=sha256:871b72c3643e516db4ecf20efe735deb27fe30ca17800e661d769faab45a18d7 \
- --hash=sha256:89dca0ce00a2b49024df6325925555d406b14aa3efc2f752dbb5940c52c56b11 \
- --hash=sha256:90fb88843d3902fe7c9586d439d1e8c05258f41da473952aa8b328d8b907498c \
- --hash=sha256:97aabc5c50312afa5e0a2b07c17d4ac5e865b250986f8afe2b02d772567a380c \
- --hash=sha256:9aaa107275d8527e9d6e7670b64aabaaa36e5b6bd71a1015ddd21da0d4e06448 \
- --hash=sha256:9f47eabcd2ded7698106b05c2c338672d16a6f2a485e74481f524e2a23c2794b \
- --hash=sha256:a0a06a052c5f37b4ed81c613a455a81f9a3a69429b4fd7bb913c3fa98abefc20 \
- --hash=sha256:ab388aaa3f6ce52ac1cb8e122c4bd46657c15905904b3120a6248b5b8b0bc228 \
- --hash=sha256:ad58d27a5b0262c0c19b47d54c5802db9b34d38bbf886665b626aff83c74bacd \
- --hash=sha256:ae5331c23ce118c53b172fa64a4c037eb83c9165aba3a7ba9ddd3ec9fa64a699 \
- --hash=sha256:af0372acb5d3598f36ec0914deed2a63f6bcdb7b606da04dc19a88d31bf0c05b \
- --hash=sha256:afa4107d1b306cdf8953edde0534562607fe8811b6c4d9a486298ad31de733b2 \
- --hash=sha256:b03ae6f1a1878233ac620c98f3459f79fd77c7e3c2b20d460284e1fb370557d4 \
- --hash=sha256:b0915e734b33a474d76c28e07292f196cdf2a590a0d25bcc06e64e545f2d146c \
- --hash=sha256:b4012d06c846dc2b80651b120e2cdd787b013deb39c09f407727ba90015c684f \
- --hash=sha256:b472b5ea442148d1c3e2209f20f1e0bb0eb556538690fa70b5e1f79fa0ba8dc2 \
- --hash=sha256:b59430236b8e58840a0dfb4099a0e8717ffb779c952426a69ae435ca1f57210c \
- --hash=sha256:b90f7616ea170e92820775ed47e136208e04c967271c9ef615b6fbd08d9af0e3 \
- --hash=sha256:b9a65733d103311331875c1dca05cb4606997fd33d6acfed695b1232ba1df193 \
- --hash=sha256:bac18ab8d2d1e6b4ce25e3424f709aceef668347db8637c2296bcf41acb7cf48 \
- --hash=sha256:bca31dd6014cb8b0b2db1e46081b0ca7d936f856da3b39744aef499db5d84d02 \
- --hash=sha256:be55f8457cd1eac957af0c3f5ece7bc3f033f89b114ef30f710882717670b2a8 \
- --hash=sha256:c7025dce65566eb6e89f56c9509d4f628fddcedb131d9465cacd3d8bac337e7e \
- --hash=sha256:c935a22a557a560108d780f9a0fc426dd7459940dc54faa49d83249c8d3e760f \
- --hash=sha256:dbb8e7f2abee51cef77673be97760abff1674ed32847ce04b4af90f610144c7b \
- --hash=sha256:e6ea6b856a74d560d9326c0f5895ef8050126acfdc7ca08ad703eb0081e82b74 \
- --hash=sha256:ebf2029c1f464c59b8bdbe5143c79fa2045a581ac53679733d3a91d400ff9efb \
- --hash=sha256:f1ff2ee69f10f13a9596480335f406dd1f70c3650349e2be67ca3139280cade0
+pathspec==0.12.1 \
+ --hash=sha256:a0d503e138a4c123b27490a4f7beda6a01c6f288df0e4a8b79c7eb0dc7b4cc08 \
+ --hash=sha256:a482d51503a1ab33b1c67a6c3813a26953dbdc71c31dacaef9a838c4e29f5712
+ # via mkdocs
+pillow==10.4.0 \
+ --hash=sha256:02a2be69f9c9b8c1e97cf2713e789d4e398c751ecfd9967c18d0ce304efbf885 \
+ --hash=sha256:030abdbe43ee02e0de642aee345efa443740aa4d828bfe8e2eb11922ea6a21ea \
+ --hash=sha256:06b2f7898047ae93fad74467ec3d28fe84f7831370e3c258afa533f81ef7f3df \
+ --hash=sha256:0755ffd4a0c6f267cccbae2e9903d95477ca2f77c4fcf3a3a09570001856c8a5 \
+ --hash=sha256:0a9ec697746f268507404647e531e92889890a087e03681a3606d9b920fbee3c \
+ --hash=sha256:0ae24a547e8b711ccaaf99c9ae3cd975470e1a30caa80a6aaee9a2f19c05701d \
+ --hash=sha256:134ace6dc392116566980ee7436477d844520a26a4b1bd4053f6f47d096997fd \
+ --hash=sha256:166c1cd4d24309b30d61f79f4a9114b7b2313d7450912277855ff5dfd7cd4a06 \
+ --hash=sha256:1b5dea9831a90e9d0721ec417a80d4cbd7022093ac38a568db2dd78363b00908 \
+ --hash=sha256:1d846aea995ad352d4bdcc847535bd56e0fd88d36829d2c90be880ef1ee4668a \
+ --hash=sha256:1ef61f5dd14c300786318482456481463b9d6b91ebe5ef12f405afbba77ed0be \
+ --hash=sha256:297e388da6e248c98bc4a02e018966af0c5f92dfacf5a5ca22fa01cb3179bca0 \
+ --hash=sha256:298478fe4f77a4408895605f3482b6cc6222c018b2ce565c2b6b9c354ac3229b \
+ --hash=sha256:29dbdc4207642ea6aad70fbde1a9338753d33fb23ed6956e706936706f52dd80 \
+ --hash=sha256:2db98790afc70118bd0255c2eeb465e9767ecf1f3c25f9a1abb8ffc8cfd1fe0a \
+ --hash=sha256:32cda9e3d601a52baccb2856b8ea1fc213c90b340c542dcef77140dfa3278a9e \
+ --hash=sha256:37fb69d905be665f68f28a8bba3c6d3223c8efe1edf14cc4cfa06c241f8c81d9 \
+ --hash=sha256:416d3a5d0e8cfe4f27f574362435bc9bae57f679a7158e0096ad2beb427b8696 \
+ --hash=sha256:43efea75eb06b95d1631cb784aa40156177bf9dd5b4b03ff38979e048258bc6b \
+ --hash=sha256:4b35b21b819ac1dbd1233317adeecd63495f6babf21b7b2512d244ff6c6ce309 \
+ --hash=sha256:4d9667937cfa347525b319ae34375c37b9ee6b525440f3ef48542fcf66f2731e \
+ --hash=sha256:5161eef006d335e46895297f642341111945e2c1c899eb406882a6c61a4357ab \
+ --hash=sha256:543f3dc61c18dafb755773efc89aae60d06b6596a63914107f75459cf984164d \
+ --hash=sha256:551d3fd6e9dc15e4c1eb6fc4ba2b39c0c7933fa113b220057a34f4bb3268a060 \
+ --hash=sha256:59291fb29317122398786c2d44427bbd1a6d7ff54017075b22be9d21aa59bd8d \
+ --hash=sha256:5b001114dd152cfd6b23befeb28d7aee43553e2402c9f159807bf55f33af8a8d \
+ --hash=sha256:5b4815f2e65b30f5fbae9dfffa8636d992d49705723fe86a3661806e069352d4 \
+ --hash=sha256:5dc6761a6efc781e6a1544206f22c80c3af4c8cf461206d46a1e6006e4429ff3 \
+ --hash=sha256:5e84b6cc6a4a3d76c153a6b19270b3526a5a8ed6b09501d3af891daa2a9de7d6 \
+ --hash=sha256:6209bb41dc692ddfee4942517c19ee81b86c864b626dbfca272ec0f7cff5d9fb \
+ --hash=sha256:673655af3eadf4df6b5457033f086e90299fdd7a47983a13827acf7459c15d94 \
+ --hash=sha256:6c762a5b0997f5659a5ef2266abc1d8851ad7749ad9a6a5506eb23d314e4f46b \
+ --hash=sha256:7086cc1d5eebb91ad24ded9f58bec6c688e9f0ed7eb3dbbf1e4800280a896496 \
+ --hash=sha256:73664fe514b34c8f02452ffb73b7a92c6774e39a647087f83d67f010eb9a0cf0 \
+ --hash=sha256:76a911dfe51a36041f2e756b00f96ed84677cdeb75d25c767f296c1c1eda1319 \
+ --hash=sha256:780c072c2e11c9b2c7ca37f9a2ee8ba66f44367ac3e5c7832afcfe5104fd6d1b \
+ --hash=sha256:7928ecbf1ece13956b95d9cbcfc77137652b02763ba384d9ab508099a2eca856 \
+ --hash=sha256:7970285ab628a3779aecc35823296a7869f889b8329c16ad5a71e4901a3dc4ef \
+ --hash=sha256:7a8d4bade9952ea9a77d0c3e49cbd8b2890a399422258a77f357b9cc9be8d680 \
+ --hash=sha256:7c1ee6f42250df403c5f103cbd2768a28fe1a0ea1f0f03fe151c8741e1469c8b \
+ --hash=sha256:7dfecdbad5c301d7b5bde160150b4db4c659cee2b69589705b6f8a0c509d9f42 \
+ --hash=sha256:812f7342b0eee081eaec84d91423d1b4650bb9828eb53d8511bcef8ce5aecf1e \
+ --hash=sha256:866b6942a92f56300012f5fbac71f2d610312ee65e22f1aa2609e491284e5597 \
+ --hash=sha256:86dcb5a1eb778d8b25659d5e4341269e8590ad6b4e8b44d9f4b07f8d136c414a \
+ --hash=sha256:87dd88ded2e6d74d31e1e0a99a726a6765cda32d00ba72dc37f0651f306daaa8 \
+ --hash=sha256:8bc1a764ed8c957a2e9cacf97c8b2b053b70307cf2996aafd70e91a082e70df3 \
+ --hash=sha256:8d4d5063501b6dd4024b8ac2f04962d661222d120381272deea52e3fc52d3736 \
+ --hash=sha256:8f0aef4ef59694b12cadee839e2ba6afeab89c0f39a3adc02ed51d109117b8da \
+ --hash=sha256:930044bb7679ab003b14023138b50181899da3f25de50e9dbee23b61b4de2126 \
+ --hash=sha256:950be4d8ba92aca4b2bb0741285a46bfae3ca699ef913ec8416c1b78eadd64cd \
+ --hash=sha256:961a7293b2457b405967af9c77dcaa43cc1a8cd50d23c532e62d48ab6cdd56f5 \
+ --hash=sha256:9b885f89040bb8c4a1573566bbb2f44f5c505ef6e74cec7ab9068c900047f04b \
+ --hash=sha256:9f4727572e2918acaa9077c919cbbeb73bd2b3ebcfe033b72f858fc9fbef0026 \
+ --hash=sha256:a02364621fe369e06200d4a16558e056fe2805d3468350df3aef21e00d26214b \
+ --hash=sha256:a985e028fc183bf12a77a8bbf36318db4238a3ded7fa9df1b9a133f1cb79f8fc \
+ --hash=sha256:ac1452d2fbe4978c2eec89fb5a23b8387aba707ac72810d9490118817d9c0b46 \
+ --hash=sha256:b15e02e9bb4c21e39876698abf233c8c579127986f8207200bc8a8f6bb27acf2 \
+ --hash=sha256:b2724fdb354a868ddf9a880cb84d102da914e99119211ef7ecbdc613b8c96b3c \
+ --hash=sha256:bbc527b519bd3aa9d7f429d152fea69f9ad37c95f0b02aebddff592688998abe \
+ --hash=sha256:bcd5e41a859bf2e84fdc42f4edb7d9aba0a13d29a2abadccafad99de3feff984 \
+ --hash=sha256:bd2880a07482090a3bcb01f4265f1936a903d70bc740bfcb1fd4e8a2ffe5cf5a \
+ --hash=sha256:bee197b30783295d2eb680b311af15a20a8b24024a19c3a26431ff83eb8d1f70 \
+ --hash=sha256:bf2342ac639c4cf38799a44950bbc2dfcb685f052b9e262f446482afaf4bffca \
+ --hash=sha256:c76e5786951e72ed3686e122d14c5d7012f16c8303a674d18cdcd6d89557fc5b \
+ --hash=sha256:cbed61494057c0f83b83eb3a310f0bf774b09513307c434d4366ed64f4128a91 \
+ --hash=sha256:cfdd747216947628af7b259d274771d84db2268ca062dd5faf373639d00113a3 \
+ --hash=sha256:d7480af14364494365e89d6fddc510a13e5a2c3584cb19ef65415ca57252fb84 \
+ --hash=sha256:dbc6ae66518ab3c5847659e9988c3b60dc94ffb48ef9168656e0019a93dbf8a1 \
+ --hash=sha256:dc3e2db6ba09ffd7d02ae9141cfa0ae23393ee7687248d46a7507b75d610f4f5 \
+ --hash=sha256:dfe91cb65544a1321e631e696759491ae04a2ea11d36715eca01ce07284738be \
+ --hash=sha256:e4d49b85c4348ea0b31ea63bc75a9f3857869174e2bf17e7aba02945cd218e6f \
+ --hash=sha256:e4db64794ccdf6cb83a59d73405f63adbe2a1887012e308828596100a0b2f6cc \
+ --hash=sha256:e553cad5179a66ba15bb18b353a19020e73a7921296a7979c4a2b7f6a5cd57f9 \
+ --hash=sha256:e88d5e6ad0d026fba7bdab8c3f225a69f063f116462c49892b0149e21b6c0a0e \
+ --hash=sha256:ecd85a8d3e79cd7158dec1c9e5808e821feea088e2f69a974db5edf84dc53141 \
+ --hash=sha256:f5b92f4d70791b4a67157321c4e8225d60b119c5cc9aee8ecf153aace4aad4ef \
+ --hash=sha256:f5f0c3e969c8f12dd2bb7e0b15d5c468b51e5017e01e2e867335c81903046a22 \
+ --hash=sha256:f7baece4ce06bade126fb84b8af1c33439a76d8a6fd818970215e0560ca28c27 \
+ --hash=sha256:ff25afb18123cea58a591ea0244b92eb1e61a1fd497bf6d6384f09bc3262ec3e \
+ --hash=sha256:ff337c552345e95702c5fde3158acb0625111017d0e5f24bf3acdb9cc16b90d1
# via
+ # aim
# bokeh
# matplotlib
pkginfo==1.11.1 \
--hash=sha256:2e0dca1cf4c8e39644eed32408ea9966ee15e0d324c62ba899a393b3c6b467aa \
--hash=sha256:bfa76a714fdfc18a045fcd684dbfc3816b603d9d075febef17cb6582bea29573
# via -r tools/python/requirements.txt
-pycairo==1.22.0 \
- --hash=sha256:007ae728c56b9a0962d8c5513ae967a4fceff03e022940383c20f4f3d4c48dbe \
- --hash=sha256:00c8a6b92c5075ee3be7ea1d33f676d259f11f92cad7e37077dd193437c8c27c \
- --hash=sha256:356c9fc665e8522f497b6cbe026ad8decacbb04c93e13fd5d145956433f3d471 \
- --hash=sha256:47aed13e950345c8248f77c8a51bff52188bef7afd3d5169584e0eddc21ba341 \
- --hash=sha256:5a62cf1d2c6339028709a600d83c0c24111feedeef3cf977bca333fbb94a79c8 \
- --hash=sha256:62ce5e8c97eeee70170ba9a74845a0ded4bde9b7f1701d88957cbadf8cb1ccd6 \
- --hash=sha256:9fbe26b3fbe85fde063070e543b4a5f3609569ca8f79680867cecb837d5be29c \
- --hash=sha256:b34517abdf619d4c7f0274f012b398d9b03bab7adc3efd2912bf36be3f911f3f \
- --hash=sha256:b85807ec65a8b7966aca7aa41c39016b72515d6401a874a4b52c314471b31865 \
- --hash=sha256:e31a5b70664c425f4d1b71ba8aaf259920de6937a9490132ffabadad2a89764f \
- --hash=sha256:e81189414c11340134bffa6dcb06a378976cb87a6742f39aaefc79cb27612250
+platformdirs==4.2.2 \
+ --hash=sha256:2d7a1657e36a80ea911db832a8a6ece5ee53d8de21edd5cc5879af6530b1bfee \
+ --hash=sha256:38b7b51f512eed9e84a22788b4bce1de17c0adb134d6becb09836e37d8654cd3
+ # via
+ # mkdocs-get-deps
+ # yapf
+plotly==5.24.1 \
+ --hash=sha256:dbc8ac8339d248a4bcc36e08a5659bacfe1b079390b8953533f4eb22169b4bae \
+ --hash=sha256:f67073a1e637eb0dc3e46324d9d51e2fe76e9727c892dde64ddf1e1b51f29089
+ # via -r tools/python/requirements.txt
+promise==2.3 \
+ --hash=sha256:dfd18337c523ba4b6a58801c164c1904a9d4d1b1747c7d5dbf45b693a49d93d0
+ # via tensorflow-datasets
+protobuf==3.20.3 \
+ --hash=sha256:03038ac1cfbc41aa21f6afcbcd357281d7521b4157926f30ebecc8d4ea59dcb7 \
+ --hash=sha256:28545383d61f55b57cf4df63eebd9827754fd2dc25f80c5253f9184235db242c \
+ --hash=sha256:2e3427429c9cffebf259491be0af70189607f365c2f41c7c3764af6f337105f2 \
+ --hash=sha256:398a9e0c3eaceb34ec1aee71894ca3299605fa8e761544934378bbc6c97de23b \
+ --hash=sha256:44246bab5dd4b7fbd3c0c80b6f16686808fab0e4aca819ade6e8d294a29c7050 \
+ --hash=sha256:447d43819997825d4e71bf5769d869b968ce96848b6479397e29fc24c4a5dfe9 \
+ --hash=sha256:67a3598f0a2dcbc58d02dd1928544e7d88f764b47d4a286202913f0b2801c2e7 \
+ --hash=sha256:74480f79a023f90dc6e18febbf7b8bac7508420f2006fabd512013c0c238f454 \
+ --hash=sha256:819559cafa1a373b7096a482b504ae8a857c89593cf3a25af743ac9ecbd23480 \
+ --hash=sha256:899dc660cd599d7352d6f10d83c95df430a38b410c1b66b407a6b29265d66469 \
+ --hash=sha256:8c0c984a1b8fef4086329ff8dd19ac77576b384079247c770f29cc8ce3afa06c \
+ --hash=sha256:9aae4406ea63d825636cc11ffb34ad3379335803216ee3a856787bcf5ccc751e \
+ --hash=sha256:a7ca6d488aa8ff7f329d4c545b2dbad8ac31464f1d8b1c87ad1346717731e4db \
+ --hash=sha256:b6cc7ba72a8850621bfec987cb72623e703b7fe2b9127a161ce61e61558ad905 \
+ --hash=sha256:bf01b5720be110540be4286e791db73f84a2b721072a3711efff6c324cdf074b \
+ --hash=sha256:c02ce36ec760252242a33967d51c289fd0e1c0e6e5cc9397e2279177716add86 \
+ --hash=sha256:d9e4432ff660d67d775c66ac42a67cf2453c27cb4d738fc22cb53b5d84c135d4 \
+ --hash=sha256:daa564862dd0d39c00f8086f88700fdbe8bc717e993a21e90711acfed02f2402 \
+ --hash=sha256:de78575669dddf6099a8a0f46a27e82a1783c557ccc38ee620ed8cc96d3be7d7 \
+ --hash=sha256:e64857f395505ebf3d2569935506ae0dfc4a15cb80dc25261176c784662cdcc4 \
+ --hash=sha256:f4bd856d702e5b0d96a00ec6b307b0f51c1982c2bf9c0052cf9019e9a544ba99 \
+ --hash=sha256:f4c42102bc82a51108e449cbb32b19b180022941c727bac0cfd50170341f16ee
+ # via
+ # orbax-checkpoint
+ # tensorboard
+ # tensorflow
+ # tensorflow-datasets
+ # tensorflow-metadata
+psutil==6.0.0 \
+ --hash=sha256:02b69001f44cc73c1c5279d02b30a817e339ceb258ad75997325e0e6169d8b35 \
+ --hash=sha256:1287c2b95f1c0a364d23bc6f2ea2365a8d4d9b726a3be7294296ff7ba97c17f0 \
+ --hash=sha256:1e7c870afcb7d91fdea2b37c24aeb08f98b6d67257a5cb0a8bc3ac68d0f1a68c \
+ --hash=sha256:21f1fb635deccd510f69f485b87433460a603919b45e2a324ad65b0cc74f8fb1 \
+ --hash=sha256:33ea5e1c975250a720b3a6609c490db40dae5d83a4eb315170c4fe0d8b1f34b3 \
+ --hash=sha256:34859b8d8f423b86e4385ff3665d3f4d94be3cdf48221fbe476e883514fdb71c \
+ --hash=sha256:5fd9a97c8e94059b0ef54a7d4baf13b405011176c3b6ff257c247cae0d560ecd \
+ --hash=sha256:6ec7588fb3ddaec7344a825afe298db83fe01bfaaab39155fa84cf1c0d6b13c3 \
+ --hash=sha256:6ed2440ada7ef7d0d608f20ad89a04ec47d2d3ab7190896cd62ca5fc4fe08bf0 \
+ --hash=sha256:8faae4f310b6d969fa26ca0545338b21f73c6b15db7c4a8d934a5482faa818f2 \
+ --hash=sha256:a021da3e881cd935e64a3d0a20983bda0bb4cf80e4f74fa9bfcb1bc5785360c6 \
+ --hash=sha256:a495580d6bae27291324fe60cea0b5a7c23fa36a7cd35035a16d93bdcf076b9d \
+ --hash=sha256:a9a3dbfb4de4f18174528d87cc352d1f788b7496991cca33c6996f40c9e3c92c \
+ --hash=sha256:c588a7e9b1173b6e866756dde596fd4cad94f9399daf99ad8c3258b3cb2b47a0 \
+ --hash=sha256:e2e8d0054fc88153ca0544f5c4d554d42e33df2e009c4ff42284ac9ebdef4132 \
+ --hash=sha256:fc8c9510cde0146432bbdb433322861ee8c3efbf8589865c8bf8d21cb30c4d14 \
+ --hash=sha256:ffe7fc9b6b36beadc8c322f84e1caff51e8703b88eee1da46d1e3a6ae11b4fd0
+ # via
+ # aim
+ # tensorflow-datasets
+pycairo==1.26.1 \
+ --hash=sha256:067191315c3b4d09cad1ec57cdb8fc1d72e2574e89389c268a94f22d4fa98b5f \
+ --hash=sha256:22e1db531d4ed3167a98f0ea165bfa2a30df9d6eb22361c38158c031065999a4 \
+ --hash=sha256:27357994d277b3fd10a45e9ef58f80a4cb5e3291fe76c5edd58d2d06335eb8e7 \
+ --hash=sha256:27ec7b42c58af35dc11352881262dce4254378b0f11be0959d1c13edb4539d2c \
+ --hash=sha256:36131a726f568b2dbc5e78ff50fbaa379e69db00614d46d66b1e4289caf9b1ce \
+ --hash=sha256:5577b51543ea4c283c15f436d891e9eaf6fd43fe74882adb032fba2c271f3fe9 \
+ --hash=sha256:56a29623aa7b4adbde5024c61ff001455b5a3def79e512742ea45ab36c3fe24b \
+ --hash=sha256:5cc1808e9e30ccd0f4d84ba7700db5aab5673f8b6b901760369ebb88a0823436 \
+ --hash=sha256:7a307111de345304ed8eadd7f81ebd7fb1fc711224aa314a4e8e33af7dfa3d27 \
+ --hash=sha256:8d2889e03a095de5da9e68a589b691a3ada09d60ef18b5fc1b1b99f2a7794297 \
+ --hash=sha256:a11b999ce55b798dbf13516ab038e0ce8b6ec299b208d7c4e767a6f7e68e8430 \
+ --hash=sha256:acfc76924ed668d8fea50f6cc6097b9a57ef6cd3dc3f2fa20814380d639a6dd2 \
+ --hash=sha256:b93b9e3072826a346f1f79cb1becc403d1ba4a3971cad61d144db0fe6dcb6be8 \
+ --hash=sha256:ce049930e294c29b53c68dcaab3df97cc5de7eb1d3d8e8a9f5c77e7164cd6e85 \
+ --hash=sha256:e68300d1c2196d1d34de3432885ae9ff78e10426fa16f765742a11c6f8fe0a71
# via pygobject
+pycparser==2.22 \
+ --hash=sha256:491c8be9c040f5390f5bf44a5b07752bd07f56edf992381b05c701439eec10f6 \
+ --hash=sha256:c3702b6d3dd8c7abc1afa565d7e63d53a1d0bd86cdc24edd75470f4de499cfcc
+ # via cffi
+pydantic==2.9.2 \
+ --hash=sha256:d155cef71265d1e9807ed1c32b4c8deec042a44a50a4188b25ac67ecd81a9c0f \
+ --hash=sha256:f048cec7b26778210e28a0459867920654d48e5e62db0958433636cde4254f12
+ # via fastapi
+pydantic-core==2.23.4 \
+ --hash=sha256:0a7df63886be5e270da67e0966cf4afbae86069501d35c8c1b3b6c168f42cb36 \
+ --hash=sha256:0cb3da3fd1b6a5d0279a01877713dbda118a2a4fc6f0d821a57da2e464793f05 \
+ --hash=sha256:0dbd8dbed2085ed23b5c04afa29d8fd2771674223135dc9bc937f3c09284d071 \
+ --hash=sha256:0dff76e0602ca7d4cdaacc1ac4c005e0ce0dcfe095d5b5259163a80d3a10d327 \
+ --hash=sha256:1278e0d324f6908e872730c9102b0112477a7f7cf88b308e4fc36ce1bdb6d58c \
+ --hash=sha256:128585782e5bfa515c590ccee4b727fb76925dd04a98864182b22e89a4e6ed36 \
+ --hash=sha256:1498bec4c05c9c787bde9125cfdcc63a41004ff167f495063191b863399b1a29 \
+ --hash=sha256:19442362866a753485ba5e4be408964644dd6a09123d9416c54cd49171f50744 \
+ --hash=sha256:1b84d168f6c48fabd1f2027a3d1bdfe62f92cade1fb273a5d68e621da0e44e6d \
+ --hash=sha256:1e90d2e3bd2c3863d48525d297cd143fe541be8bbf6f579504b9712cb6b643ec \
+ --hash=sha256:20152074317d9bed6b7a95ade3b7d6054845d70584216160860425f4fbd5ee9e \
+ --hash=sha256:216f9b2d7713eb98cb83c80b9c794de1f6b7e3145eef40400c62e86cee5f4e1e \
+ --hash=sha256:233710f069d251feb12a56da21e14cca67994eab08362207785cf8c598e74577 \
+ --hash=sha256:255a8ef062cbf6674450e668482456abac99a5583bbafb73f9ad469540a3a232 \
+ --hash=sha256:2584f7cf844ac4d970fba483a717dbe10c1c1c96a969bf65d61ffe94df1b2863 \
+ --hash=sha256:2971bb5ffe72cc0f555c13e19b23c85b654dd2a8f7ab493c262071377bfce9f6 \
+ --hash=sha256:29d2c342c4bc01b88402d60189f3df065fb0dda3654744d5a165a5288a657368 \
+ --hash=sha256:2e203fdf807ac7e12ab59ca2bfcabb38c7cf0b33c41efeb00f8e5da1d86af480 \
+ --hash=sha256:33e3d65a85a2a4a0dc3b092b938a4062b1a05f3a9abde65ea93b233bca0e03f2 \
+ --hash=sha256:374a5e5049eda9e0a44c696c7ade3ff355f06b1fe0bb945ea3cac2bc336478a2 \
+ --hash=sha256:37b0fe330e4a58d3c58b24d91d1eb102aeec675a3db4c292ec3928ecd892a9a6 \
+ --hash=sha256:3d5639516376dce1940ea36edf408c554475369f5da2abd45d44621cb616f769 \
+ --hash=sha256:42c6dcb030aefb668a2b7009c85b27f90e51e6a3b4d5c9bc4c57631292015b0d \
+ --hash=sha256:4a7cd62e831afe623fbb7aabbb4fe583212115b3ef38a9f6b71869ba644624a2 \
+ --hash=sha256:4ba762ed58e8d68657fc1281e9bb72e1c3e79cc5d464be146e260c541ec12d84 \
+ --hash=sha256:4fc714bdbfb534f94034efaa6eadd74e5b93c8fa6315565a222f7b6f42ca1166 \
+ --hash=sha256:4ffa2ebd4c8530079140dd2d7f794a9d9a73cbb8e9d59ffe24c63436efa8f271 \
+ --hash=sha256:5a1504ad17ba4210df3a045132a7baeeba5a200e930f57512ee02909fc5c4cb5 \
+ --hash=sha256:5c364564d17da23db1106787675fc7af45f2f7b58b4173bfdd105564e132e6fb \
+ --hash=sha256:5e11661ce0fd30a6790e8bcdf263b9ec5988e95e63cf901972107efc49218b13 \
+ --hash=sha256:5f54b118ce5de9ac21c363d9b3caa6c800341e8c47a508787e5868c6b79c9323 \
+ --hash=sha256:5f5ff8d839f4566a474a969508fe1c5e59c31c80d9e140566f9a37bba7b8d556 \
+ --hash=sha256:61817945f2fe7d166e75fbfb28004034b48e44878177fc54d81688e7b85a3665 \
+ --hash=sha256:624e278a7d29b6445e4e813af92af37820fafb6dcc55c012c834f9e26f9aaaef \
+ --hash=sha256:63e46b3169866bd62849936de036f901a9356e36376079b05efa83caeaa02ceb \
+ --hash=sha256:6531b7ca5f951d663c339002e91aaebda765ec7d61b7d1e3991051906ddde119 \
+ --hash=sha256:68665f4c17edcceecc112dfed5dbe6f92261fb9d6054b47d01bf6371a6196126 \
+ --hash=sha256:696dd8d674d6ce621ab9d45b205df149399e4bb9aa34102c970b721554828510 \
+ --hash=sha256:6f783e0ec4803c787bcea93e13e9932edab72068f68ecffdf86a99fd5918878b \
+ --hash=sha256:723314c1d51722ab28bfcd5240d858512ffd3116449c557a1336cbe3919beb87 \
+ --hash=sha256:74b9127ffea03643e998e0c5ad9bd3811d3dac8c676e47db17b0ee7c3c3bf35f \
+ --hash=sha256:7530e201d10d7d14abce4fb54cfe5b94a0aefc87da539d0346a484ead376c3cc \
+ --hash=sha256:77733e3892bb0a7fa797826361ce8a9184d25c8dffaec60b7ffe928153680ba8 \
+ --hash=sha256:78ddaaa81421a29574a682b3179d4cf9e6d405a09b99d93ddcf7e5239c742e21 \
+ --hash=sha256:7c9129eb40958b3d4500fa2467e6a83356b3b61bfff1b414c7361d9220f9ae8f \
+ --hash=sha256:7d32706badfe136888bdea71c0def994644e09fff0bfe47441deaed8e96fdbc6 \
+ --hash=sha256:81965a16b675b35e1d09dd14df53f190f9129c0202356ed44ab2728b1c905658 \
+ --hash=sha256:8394d940e5d400d04cad4f75c0598665cbb81aecefaca82ca85bd28264af7f9b \
+ --hash=sha256:86d2f57d3e1379a9525c5ab067b27dbb8a0642fb5d454e17a9ac434f9ce523e3 \
+ --hash=sha256:883a91b5dd7d26492ff2f04f40fbb652de40fcc0afe07e8129e8ae779c2110eb \
+ --hash=sha256:88ad334a15b32a791ea935af224b9de1bf99bcd62fabf745d5f3442199d86d59 \
+ --hash=sha256:9261d3ce84fa1d38ed649c3638feefeae23d32ba9182963e465d58d62203bd24 \
+ --hash=sha256:97df63000f4fea395b2824da80e169731088656d1818a11b95f3b173747b6cd9 \
+ --hash=sha256:98d134c954828488b153d88ba1f34e14259284f256180ce659e8d83e9c05eaa3 \
+ --hash=sha256:996a38a83508c54c78a5f41456b0103c30508fed9abcad0a59b876d7398f25fd \
+ --hash=sha256:9a5bce9d23aac8f0cf0836ecfc033896aa8443b501c58d0602dbfd5bd5b37753 \
+ --hash=sha256:9a6b5099eeec78827553827f4c6b8615978bb4b6a88e5d9b93eddf8bb6790f55 \
+ --hash=sha256:9d18368b137c6295db49ce7218b1a9ba15c5bc254c96d7c9f9e924a9bc7825ad \
+ --hash=sha256:a4fa4fc04dff799089689f4fd502ce7d59de529fc2f40a2c8836886c03e0175a \
+ --hash=sha256:a5c7ba8ffb6d6f8f2ab08743be203654bb1aaa8c9dcb09f82ddd34eadb695605 \
+ --hash=sha256:aea443fffa9fbe3af1a9ba721a87f926fe548d32cab71d188a6ede77d0ff244e \
+ --hash=sha256:b10bd51f823d891193d4717448fab065733958bdb6a6b351967bd349d48d5c9b \
+ --hash=sha256:ba1a0996f6c2773bd83e63f18914c1de3c9dd26d55f4ac302a7efe93fb8e7433 \
+ --hash=sha256:bb2802e667b7051a1bebbfe93684841cc9351004e2badbd6411bf357ab8d5ac8 \
+ --hash=sha256:cfdd16ab5e59fc31b5e906d1a3f666571abc367598e3e02c83403acabc092e07 \
+ --hash=sha256:d06b0c8da4f16d1d1e352134427cb194a0a6e19ad5db9161bf32b2113409e728 \
+ --hash=sha256:d0776dea117cf5272382634bd2a5c1b6eb16767c223c6a5317cd3e2a757c61a0 \
+ --hash=sha256:d18ca8148bebe1b0a382a27a8ee60350091a6ddaf475fa05ef50dc35b5df6327 \
+ --hash=sha256:d4488a93b071c04dc20f5cecc3631fc78b9789dd72483ba15d423b5b3689b555 \
+ --hash=sha256:d5f7a395a8cf1621939692dba2a6b6a830efa6b3cee787d82c7de1ad2930de64 \
+ --hash=sha256:d7a80d21d613eec45e3d41eb22f8f94ddc758a6c4720842dc74c0581f54993d6 \
+ --hash=sha256:d97683ddee4723ae8c95d1eddac7c192e8c552da0c73a925a89fa8649bf13eea \
+ --hash=sha256:dcedcd19a557e182628afa1d553c3895a9f825b936415d0dbd3cd0bbcfd29b4b \
+ --hash=sha256:de6d1d1b9e5101508cb37ab0d972357cac5235f5c6533d1071964c47139257df \
+ --hash=sha256:df49e7a0861a8c36d089c1ed57d308623d60416dab2647a4a17fe050ba85de0e \
+ --hash=sha256:df933278128ea1cd77772673c73954e53a1c95a4fdf41eef97c2b779271bd0bd \
+ --hash=sha256:e08277a400de01bc72436a0ccd02bdf596631411f592ad985dcee21445bd0068 \
+ --hash=sha256:e38e63e6f3d1cec5a27e0afe90a085af8b6806ee208b33030e65b6516353f1a3 \
+ --hash=sha256:e55541f756f9b3ee346b840103f32779c695a19826a4c442b7954550a0972040 \
+ --hash=sha256:ec4e55f79b1c4ffb2eecd8a0cfba9955a2588497d96851f4c8f99aa4a1d39b12 \
+ --hash=sha256:ed1a53de42fbe34853ba90513cea21673481cd81ed1be739f7f2efb931b24916 \
+ --hash=sha256:ed541d70698978a20eb63d8c5d72f2cc6d7079d9d90f6b50bad07826f1320f5f \
+ --hash=sha256:f09e2ff1f17c2b51f2bc76d1cc33da96298f0a036a137f5440ab3ec5360b624f \
+ --hash=sha256:f220b0eea5965dec25480b6333c788fb72ce5f9129e8759ef876a1d805d00801 \
+ --hash=sha256:f3e0da4ebaef65158d4dfd7d3678aad692f7666877df0002b8a522cdf088f231 \
+ --hash=sha256:f455ee30a9d61d3e1a15abd5068827773d6e4dc513e795f380cdd59932c782d5 \
+ --hash=sha256:f5ef8f42bec47f21d07668a043f077d507e5bf4e668d5c6dfe6aaba89de1a5b8 \
+ --hash=sha256:f69a8e0b033b747bb3e36a44e7732f0c99f7edd5cea723d45bc0d6e95377ffee \
+ --hash=sha256:ff02b6d461a6de369f07ec15e465a88895f3223eb75073ffea56b84d9331f607
+ # via pydantic
+pygments==2.18.0 \
+ --hash=sha256:786ff802f32e91311bff3889f6e9a86e81505fe99f2735bb6d60ae0c5004f199 \
+ --hash=sha256:b8e6aca0523f3ab76fee51799c488e38782ac06eafcf95e7ba832985c8e7b13a
+ # via rich
pygobject==3.42.2 \
--hash=sha256:21524cef33100c8fd59dc135948b703d79d303e368ce71fa60521cc971cd8aa7
# via -r tools/python/requirements.txt
-pyparsing==3.0.9 \
- --hash=sha256:2b020ecf7d21b687f219b71ecad3631f644a47f01403fa1d1036b0c6416d70fb \
- --hash=sha256:5026bae9a10eeaefb61dab2f09052b9f4307d44aee4eda64b309723d8d206bbc
+pyparsing==3.1.4 \
+ --hash=sha256:a6a7ee4235a3f944aa1fa2249307708f893fe5717dc603503c6c7969c070fb7c \
+ --hash=sha256:f86ec8d1a83f11977c9a6ea7598e8c27fc5cddfa5b07ea2241edbbde1d7bc032
+ # via matplotlib
+python-dateutil==2.9.0.post0 \
+ --hash=sha256:37dd54208da7e1cd875388217d5e00ebd4179249f90fb72437e91a35459a0ad3 \
+ --hash=sha256:a8b2bc7bffae282281c8140a97d3aa9c14da0b136dfe83f850eea9a5f7470427
# via
- # matplotlib
- # packaging
-python-dateutil==2.8.2 \
- --hash=sha256:0123cacc1627ae19ddf3c27a5de5bd67ee4586fbdd6440d9748f8abb483d3e86 \
- --hash=sha256:961d03dc3453ebbc59dbdea9e4e11c5651520a876d0f4db161e8674aae935da9
- # via
+ # aim
+ # botocore
# ghp-import
# matplotlib
# pandas
@@ -663,222 +1882,687 @@
pytz==2024.1 \
--hash=sha256:2a29735ea9c18baf14b448846bde5a48030ed267578472d8955cd0e7443a9812 \
--hash=sha256:328171f4e3623139da4983451950b28e95ac706e13f3f2630a879749e7a8b319
- # via pandas
-pyyaml==6.0 \
- --hash=sha256:01b45c0191e6d66c470b6cf1b9531a771a83c1c4208272ead47a3ae4f2f603bf \
- --hash=sha256:0283c35a6a9fbf047493e3a0ce8d79ef5030852c51e9d911a27badfde0605293 \
- --hash=sha256:055d937d65826939cb044fc8c9b08889e8c743fdc6a32b33e2390f66013e449b \
- --hash=sha256:07751360502caac1c067a8132d150cf3d61339af5691fe9e87803040dbc5db57 \
- --hash=sha256:0b4624f379dab24d3725ffde76559cff63d9ec94e1736b556dacdfebe5ab6d4b \
- --hash=sha256:0ce82d761c532fe4ec3f87fc45688bdd3a4c1dc5e0b4a19814b9009a29baefd4 \
- --hash=sha256:1e4747bc279b4f613a09eb64bba2ba602d8a6664c6ce6396a4d0cd413a50ce07 \
- --hash=sha256:213c60cd50106436cc818accf5baa1aba61c0189ff610f64f4a3e8c6726218ba \
- --hash=sha256:231710d57adfd809ef5d34183b8ed1eeae3f76459c18fb4a0b373ad56bedcdd9 \
- --hash=sha256:277a0ef2981ca40581a47093e9e2d13b3f1fbbeffae064c1d21bfceba2030287 \
- --hash=sha256:2cd5df3de48857ed0544b34e2d40e9fac445930039f3cfe4bcc592a1f836d513 \
- --hash=sha256:40527857252b61eacd1d9af500c3337ba8deb8fc298940291486c465c8b46ec0 \
- --hash=sha256:432557aa2c09802be39460360ddffd48156e30721f5e8d917f01d31694216782 \
- --hash=sha256:473f9edb243cb1935ab5a084eb238d842fb8f404ed2193a915d1784b5a6b5fc0 \
- --hash=sha256:48c346915c114f5fdb3ead70312bd042a953a8ce5c7106d5bfb1a5254e47da92 \
- --hash=sha256:50602afada6d6cbfad699b0c7bb50d5ccffa7e46a3d738092afddc1f9758427f \
- --hash=sha256:68fb519c14306fec9720a2a5b45bc9f0c8d1b9c72adf45c37baedfcd949c35a2 \
- --hash=sha256:77f396e6ef4c73fdc33a9157446466f1cff553d979bd00ecb64385760c6babdc \
- --hash=sha256:81957921f441d50af23654aa6c5e5eaf9b06aba7f0a19c18a538dc7ef291c5a1 \
- --hash=sha256:819b3830a1543db06c4d4b865e70ded25be52a2e0631ccd2f6a47a2822f2fd7c \
- --hash=sha256:897b80890765f037df3403d22bab41627ca8811ae55e9a722fd0392850ec4d86 \
- --hash=sha256:98c4d36e99714e55cfbaaee6dd5badbc9a1ec339ebfc3b1f52e293aee6bb71a4 \
- --hash=sha256:9df7ed3b3d2e0ecfe09e14741b857df43adb5a3ddadc919a2d94fbdf78fea53c \
- --hash=sha256:9fa600030013c4de8165339db93d182b9431076eb98eb40ee068700c9c813e34 \
- --hash=sha256:a80a78046a72361de73f8f395f1f1e49f956c6be882eed58505a15f3e430962b \
- --hash=sha256:afa17f5bc4d1b10afd4466fd3a44dc0e245382deca5b3c353d8b757f9e3ecb8d \
- --hash=sha256:b3d267842bf12586ba6c734f89d1f5b871df0273157918b0ccefa29deb05c21c \
- --hash=sha256:b5b9eccad747aabaaffbc6064800670f0c297e52c12754eb1d976c57e4f74dcb \
- --hash=sha256:bfaef573a63ba8923503d27530362590ff4f576c626d86a9fed95822a8255fd7 \
- --hash=sha256:c5687b8d43cf58545ade1fe3e055f70eac7a5a1a0bf42824308d868289a95737 \
- --hash=sha256:cba8c411ef271aa037d7357a2bc8f9ee8b58b9965831d9e51baf703280dc73d3 \
- --hash=sha256:d15a181d1ecd0d4270dc32edb46f7cb7733c7c508857278d3d378d14d606db2d \
- --hash=sha256:d4b0ba9512519522b118090257be113b9468d804b19d63c71dbcf4a48fa32358 \
- --hash=sha256:d4db7c7aef085872ef65a8fd7d6d09a14ae91f691dec3e87ee5ee0539d516f53 \
- --hash=sha256:d4eccecf9adf6fbcc6861a38015c2a64f38b9d94838ac1810a9023a0609e1b78 \
- --hash=sha256:d67d839ede4ed1b28a4e8909735fc992a923cdb84e618544973d7dfc71540803 \
- --hash=sha256:daf496c58a8c52083df09b80c860005194014c3698698d1a57cbcfa182142a3a \
- --hash=sha256:dbad0e9d368bb989f4515da330b88a057617d16b6a8245084f1b05400f24609f \
- --hash=sha256:e61ceaab6f49fb8bdfaa0f92c4b57bcfbea54c09277b1b4f7ac376bfb7a7c174 \
- --hash=sha256:f84fbc98b019fef2ee9a1cb3ce93e3187a6df0b2538a651bfb890254ba9f90b5
+ # via
+ # aim
+ # pandas
+pyyaml==6.0.2 \
+ --hash=sha256:01179a4a8559ab5de078078f37e5c1a30d76bb88519906844fd7bdea1b7729ff \
+ --hash=sha256:0833f8694549e586547b576dcfaba4a6b55b9e96098b36cdc7ebefe667dfed48 \
+ --hash=sha256:0a9a2848a5b7feac301353437eb7d5957887edbf81d56e903999a75a3d743086 \
+ --hash=sha256:0b69e4ce7a131fe56b7e4d770c67429700908fc0752af059838b1cfb41960e4e \
+ --hash=sha256:0ffe8360bab4910ef1b9e87fb812d8bc0a308b0d0eef8c8f44e0254ab3b07133 \
+ --hash=sha256:11d8f3dd2b9c1207dcaf2ee0bbbfd5991f571186ec9cc78427ba5bd32afae4b5 \
+ --hash=sha256:17e311b6c678207928d649faa7cb0d7b4c26a0ba73d41e99c4fff6b6c3276484 \
+ --hash=sha256:1e2120ef853f59c7419231f3bf4e7021f1b936f6ebd222406c3b60212205d2ee \
+ --hash=sha256:1f71ea527786de97d1a0cc0eacd1defc0985dcf6b3f17bb77dcfc8c34bec4dc5 \
+ --hash=sha256:23502f431948090f597378482b4812b0caae32c22213aecf3b55325e049a6c68 \
+ --hash=sha256:24471b829b3bf607e04e88d79542a9d48bb037c2267d7927a874e6c205ca7e9a \
+ --hash=sha256:29717114e51c84ddfba879543fb232a6ed60086602313ca38cce623c1d62cfbf \
+ --hash=sha256:2e99c6826ffa974fe6e27cdb5ed0021786b03fc98e5ee3c5bfe1fd5015f42b99 \
+ --hash=sha256:39693e1f8320ae4f43943590b49779ffb98acb81f788220ea932a6b6c51004d8 \
+ --hash=sha256:3ad2a3decf9aaba3d29c8f537ac4b243e36bef957511b4766cb0057d32b0be85 \
+ --hash=sha256:3b1fdb9dc17f5a7677423d508ab4f243a726dea51fa5e70992e59a7411c89d19 \
+ --hash=sha256:41e4e3953a79407c794916fa277a82531dd93aad34e29c2a514c2c0c5fe971cc \
+ --hash=sha256:43fa96a3ca0d6b1812e01ced1044a003533c47f6ee8aca31724f78e93ccc089a \
+ --hash=sha256:50187695423ffe49e2deacb8cd10510bc361faac997de9efef88badc3bb9e2d1 \
+ --hash=sha256:5ac9328ec4831237bec75defaf839f7d4564be1e6b25ac710bd1a96321cc8317 \
+ --hash=sha256:5d225db5a45f21e78dd9358e58a98702a0302f2659a3c6cd320564b75b86f47c \
+ --hash=sha256:6395c297d42274772abc367baaa79683958044e5d3835486c16da75d2a694631 \
+ --hash=sha256:688ba32a1cffef67fd2e9398a2efebaea461578b0923624778664cc1c914db5d \
+ --hash=sha256:68ccc6023a3400877818152ad9a1033e3db8625d899c72eacb5a668902e4d652 \
+ --hash=sha256:70b189594dbe54f75ab3a1acec5f1e3faa7e8cf2f1e08d9b561cb41b845f69d5 \
+ --hash=sha256:797b4f722ffa07cc8d62053e4cff1486fa6dc094105d13fea7b1de7d8bf71c9e \
+ --hash=sha256:7c36280e6fb8385e520936c3cb3b8042851904eba0e58d277dca80a5cfed590b \
+ --hash=sha256:7e7401d0de89a9a855c839bc697c079a4af81cf878373abd7dc625847d25cbd8 \
+ --hash=sha256:80bab7bfc629882493af4aa31a4cfa43a4c57c83813253626916b8c7ada83476 \
+ --hash=sha256:82d09873e40955485746739bcb8b4586983670466c23382c19cffecbf1fd8706 \
+ --hash=sha256:8388ee1976c416731879ac16da0aff3f63b286ffdd57cdeb95f3f2e085687563 \
+ --hash=sha256:8824b5a04a04a047e72eea5cec3bc266db09e35de6bdfe34c9436ac5ee27d237 \
+ --hash=sha256:8b9c7197f7cb2738065c481a0461e50ad02f18c78cd75775628afb4d7137fb3b \
+ --hash=sha256:9056c1ecd25795207ad294bcf39f2db3d845767be0ea6e6a34d856f006006083 \
+ --hash=sha256:936d68689298c36b53b29f23c6dbb74de12b4ac12ca6cfe0e047bedceea56180 \
+ --hash=sha256:9b22676e8097e9e22e36d6b7bda33190d0d400f345f23d4065d48f4ca7ae0425 \
+ --hash=sha256:a4d3091415f010369ae4ed1fc6b79def9416358877534caf6a0fdd2146c87a3e \
+ --hash=sha256:a8786accb172bd8afb8be14490a16625cbc387036876ab6ba70912730faf8e1f \
+ --hash=sha256:a9f8c2e67970f13b16084e04f134610fd1d374bf477b17ec1599185cf611d725 \
+ --hash=sha256:bc2fa7c6b47d6bc618dd7fb02ef6fdedb1090ec036abab80d4681424b84c1183 \
+ --hash=sha256:c70c95198c015b85feafc136515252a261a84561b7b1d51e3384e0655ddf25ab \
+ --hash=sha256:cc1c1159b3d456576af7a3e4d1ba7e6924cb39de8f67111c735f6fc832082774 \
+ --hash=sha256:ce826d6ef20b1bc864f0a68340c8b3287705cae2f8b4b1d932177dcc76721725 \
+ --hash=sha256:d584d9ec91ad65861cc08d42e834324ef890a082e591037abe114850ff7bbc3e \
+ --hash=sha256:d7fded462629cfa4b685c5416b949ebad6cec74af5e2d42905d41e257e0869f5 \
+ --hash=sha256:d84a1718ee396f54f3a086ea0a66d8e552b2ab2017ef8b420e92edbc841c352d \
+ --hash=sha256:d8e03406cac8513435335dbab54c0d385e4a49e4945d2909a581c83647ca0290 \
+ --hash=sha256:e10ce637b18caea04431ce14fabcf5c64a1c61ec9c56b071a4b7ca131ca52d44 \
+ --hash=sha256:ec031d5d2feb36d1d1a24380e4db6d43695f3748343d99434e6f5f9156aaa2ed \
+ --hash=sha256:ef6107725bd54b262d6dedcc2af448a266975032bc85ef0172c5f059da6325b4 \
+ --hash=sha256:efdca5630322a10774e8e98e1af481aad470dd62c3170801852d752aa7a783ba \
+ --hash=sha256:f753120cb8181e736c57ef7636e83f31b9c0d1722c516f7e86cf15b7aa57ff12 \
+ --hash=sha256:ff3824dc5261f50c9b0dfb3be22b4567a6f938ccce4587b38952d85fd9e9afe4
# via
# -r tools/python/requirements.txt
# bokeh
+ # flax
# mkdocs
+ # mkdocs-get-deps
+ # ml-collections
+ # orbax-checkpoint
# pyyaml-env-tag
pyyaml-env-tag==0.1 \
--hash=sha256:70092675bda14fdec33b31ba77e7543de9ddc88f2e5b99160396572d11525bdb \
--hash=sha256:af31106dec8a4d68c60207c1886031cbf839b68aa7abccdb19868200532c2069
# via mkdocs
-qdldl==0.1.5.post2 \
- --hash=sha256:05b3079837c0ec86136b4a29b3842eab7bfc7a5517d751a3e5d0d5c111a2e523 \
- --hash=sha256:15d0fbff31aa19195b135ca934cf75025d46a275d915eebb7c11a7d16e148096 \
- --hash=sha256:227fe8988a86b9f9ed341ad20d11502789b4d05bceddb09a47dbb24b08d79966 \
- --hash=sha256:408a34b735be5425dc088cdebb1129f0f5d8cc9fd8c888fc9ed0bd1a02a65d6f \
- --hash=sha256:438b303b8b7b95531d93b457657ec89e742bd90c9a72da1eebfb51095007922c \
- --hash=sha256:5269f40521b12941f1334a162f8f06375df6a89f0f90d8a758ae3b83b8931b18 \
- --hash=sha256:53b19b8509f529fa6fdc8f869f6172d5c89587b657aa24d958d339de3bc47a73 \
- --hash=sha256:655f5e83c9e46f2d9b32508852d92b6e8fa6d166a6f48960aac54e81cd578417 \
- --hash=sha256:7daf7ad1bfff1da71da06e82d5147bdb1ac866581617d8f06cc4eeda48e2a149 \
- --hash=sha256:879cd43b41babda79d4896f6b5a79dfbf96be5f13489553c793659116a2e9ce4 \
- --hash=sha256:ab77ca440cbca98377e3ade32860c8d7e4fa97759d6266759a7e2f718ec4ded1 \
- --hash=sha256:ae054e987066ae861c0bc648a7cdd523cfb1849353bc9b1591ecbf2a55ca8b7d \
- --hash=sha256:ae0b70e7599dd58ef16d6500947b8d2bdd4272ffbbd2ebf5c516691fdfb82212 \
- --hash=sha256:d6f0f55bb853f10e3a2025193af2d1cc202697cc7985fe7785d681114c5b3cdb \
- --hash=sha256:fa7057d8888ea8ebba859da8b25d40e10e2f12013f6b0b033c9ab6e68cd10763 \
- --hash=sha256:ffbdd5bd07f2340ad2ce01d44cc95223ffa256136ac5dc32f4f80926701640fb
+qdldl==0.1.7.post4 \
+ --hash=sha256:004e4c5c8c200f483d86b4c8a70c546b11a59501dbe24f811752998b833d679d \
+ --hash=sha256:0bd3d9ab3074be041552297c90bd0b44fc2d2b3e5b9e7a8896d3c0878b85fcea \
+ --hash=sha256:0c163b9afb92c4b69d446387b1d4295094438b041ec4e8510271b6c4ff1f86fd \
+ --hash=sha256:0c9b6bf14689766e29fa2f7652b49e0d5a8215b646aec4a9306834418241de97 \
+ --hash=sha256:12a658077a83a6aab9d122ca8f4ae4e96a06633109fa604414657ac2f065bd9b \
+ --hash=sha256:1496a820ffb0c1a5bb18392b44052b83b5442745b15f62bbf2d22eec1f506afe \
+ --hash=sha256:2d1596bef9d38e58fb6121d8aa8662322ee92f584a4189d01770a9ff821d1a5f \
+ --hash=sha256:3770f6048e65231ead488c5e8982fffee2756e0682cc5a81d02fc56a02586050 \
+ --hash=sha256:3cec8d76f2588e83dee94d01a371297699f3701ac0039d304760ed8e25cd4739 \
+ --hash=sha256:3fe0904e3ce11610ca663032fb8d6b0cfaae26699ae2659ac79aaf4049f32ae0 \
+ --hash=sha256:40485f33c518fcbf78d95329ab0f55f10b3ccd06bea2fe7c8faf8cb16aae2485 \
+ --hash=sha256:410a9a6a1405f475ccdb16d44e16c4a8266a90952bd396482a8840c61d9e839d \
+ --hash=sha256:47c1b27712444d7b1030c562ed79af18320b4a910454716c9d88114e181eddec \
+ --hash=sha256:490b52049c4cd794cb9bb2a8b26d69e74bbb71e55b5f0cac1480de971970d79c \
+ --hash=sha256:5227ace6741618aa9aa2b0162740e806040f3a69e88204911e74b5d220d5bfce \
+ --hash=sha256:656c06f965b4121dd3a8aa8b39fc4ec4650ea487812a7fd06419834464595bbf \
+ --hash=sha256:684306b37a2f06f72c18edd2d6fa45a832e99071ebd87b875d172719e09a322d \
+ --hash=sha256:782d56522b134429a8e6b8c1a77477ff82665fbc0052808ce183853be7605888 \
+ --hash=sha256:87f31e7f2a2708def201b6dc507a48ada7e0c37efd0afda7ef6ef94ae3487c2c \
+ --hash=sha256:8e5c88f428350bac03bca36fb05b7d062219298928b89f6072d565fc5fd43c4f \
+ --hash=sha256:8f1e449b8079c744166fb87c1bf01954ef6344898063bfac1afae1a295c8a04d \
+ --hash=sha256:a40429f5c0d0edb28d22c4e52c2459fd9a64892ba7d8a39ba51a1a37b3581927 \
+ --hash=sha256:acd16e857a0b8d200dd2f9ba6b0941adc42d822b3eb5fc02a455362fbaaf7da7 \
+ --hash=sha256:b53ad4ecd90c8031e0094fbab0b0bf09520b382177db63ec9568f06b4f16c219 \
+ --hash=sha256:b6f8d59c01fa5c9dc3b6463fc7e1de7601dcb1aa16b6e14a6d5d283169dc629f \
+ --hash=sha256:b85beb51096100dcdea575acedbafb5bac2b7f44485a1d7090bb68a47c8f9928 \
+ --hash=sha256:e23ff54d54db837a55c56da197638d0f54f1fe25fb90f63c9d1f18779efdda27 \
+ --hash=sha256:e29c33ef7dcd51ccc617d5c097f4904f8d522d44bc427a75810d1c56fe2c2ccb \
+ --hash=sha256:e2b9e92bb52d3bc49cfc9fd9a761adb692f049c46e68c0535ed07df2de8292f5 \
+ --hash=sha256:ebf39433b467d2b33872e96fd05ed4a74d701eb94cd14cb010d5980fbdc02954 \
+ --hash=sha256:f63fde49b54fbf2feebf30b11ef7fd0543376a0fbc800b7d4e4c51b8ef39ff2b \
+ --hash=sha256:f6639d63c3bf9abbfdffafd3c99b7c603359ca748ab62117ec7fc0948a1c5e77 \
+ --hash=sha256:f6710b0c1013292697262803ddd549a81cdfdbdbbbcfa5b56aad04ac9cebbb4a \
+ --hash=sha256:ff4a9c5f7fa96e222c767aaaabea9d5df1d099e172c14b322b98d54dac03705d
# via osqp
-requests==2.28.1 \
- --hash=sha256:7c5599b102feddaa661c826c56ab4fee28bfd17f5abca1ebbe3e7f19d7c97983 \
- --hash=sha256:8fefa2a1a1365bf5520aac41836fbee479da67864514bdb821f31ce07ce65349
- # via -r tools/python/requirements.txt
-scipy==1.9.3 \
- --hash=sha256:06d2e1b4c491dc7d8eacea139a1b0b295f74e1a1a0f704c375028f8320d16e31 \
- --hash=sha256:0d54222d7a3ba6022fdf5773931b5d7c56efe41ede7f7128c7b1637700409108 \
- --hash=sha256:1884b66a54887e21addf9c16fb588720a8309a57b2e258ae1c7986d4444d3bc0 \
- --hash=sha256:1a72d885fa44247f92743fc20732ae55564ff2a519e8302fb7e18717c5355a8b \
- --hash=sha256:2318bef588acc7a574f5bfdff9c172d0b1bf2c8143d9582e05f878e580a3781e \
- --hash=sha256:4db5b30849606a95dcf519763dd3ab6fe9bd91df49eba517359e450a7d80ce2e \
- --hash=sha256:545c83ffb518094d8c9d83cce216c0c32f8c04aaf28b92cc8283eda0685162d5 \
- --hash=sha256:5a04cd7d0d3eff6ea4719371cbc44df31411862b9646db617c99718ff68d4840 \
- --hash=sha256:5b88e6d91ad9d59478fafe92a7c757d00c59e3bdc3331be8ada76a4f8d683f58 \
- --hash=sha256:68239b6aa6f9c593da8be1509a05cb7f9efe98b80f43a5861cd24c7557e98523 \
- --hash=sha256:83b89e9586c62e787f5012e8475fbb12185bafb996a03257e9675cd73d3736dd \
- --hash=sha256:83c06e62a390a9167da60bedd4575a14c1f58ca9dfde59830fc42e5197283dab \
- --hash=sha256:90453d2b93ea82a9f434e4e1cba043e779ff67b92f7a0e85d05d286a3625df3c \
- --hash=sha256:abaf921531b5aeaafced90157db505e10345e45038c39e5d9b6c7922d68085cb \
- --hash=sha256:b41bc822679ad1c9a5f023bc93f6d0543129ca0f37c1ce294dd9d386f0a21096 \
- --hash=sha256:c68db6b290cbd4049012990d7fe71a2abd9ffbe82c0056ebe0f01df8be5436b0 \
- --hash=sha256:cff3a5295234037e39500d35316a4c5794739433528310e117b8a9a0c76d20fc \
- --hash=sha256:d01e1dd7b15bd2449c8bfc6b7cc67d630700ed655654f0dfcf121600bad205c9 \
- --hash=sha256:d644a64e174c16cb4b2e41dfea6af722053e83d066da7343f333a54dae9bc31c \
- --hash=sha256:da8245491d73ed0a994ed9c2e380fd058ce2fa8a18da204681f2fe1f57f98f95 \
- --hash=sha256:fbc5c05c85c1a02be77b1ff591087c83bc44579c6d2bd9fb798bb64ea5e1a027
+requests==2.32.3 \
+ --hash=sha256:55365417734eb18255590a9ff9eb97e9e1da868d4ccd6402399eaf68af20a760 \
+ --hash=sha256:70761cfe03c773ceb22aa2f671b4757976145175cdfca038c02654d061d6dcc6
+ # via
+ # -r tools/python/requirements.txt
+ # aim
+ # tensorflow
+ # tensorflow-datasets
+restrictedpython==7.2 \
+ --hash=sha256:139cb41da6e57521745a566d05825f7a09e6a884f7fa922568cff0a70b84ce6b \
+ --hash=sha256:4d1d30f709a6621ca7c4236f08b67b732a651c8099145f137078c7dd4bed3d21
+ # via aim
+rich==13.8.0 \
+ --hash=sha256:2e85306a063b9492dffc86278197a60cbece75bcb766022f3436f567cae11bdc \
+ --hash=sha256:a5ac1f1cd448ade0d59cc3356f7db7a7ccda2c8cbae9c7a90c28ff463d3e91f4
+ # via
+ # flax
+ # keras
+s3transfer==0.10.2 \
+ --hash=sha256:0711534e9356d3cc692fdde846b4a1e4b0cb6519971860796e6bc4c7aea00ef6 \
+ --hash=sha256:eca1c20de70a39daee580aef4986996620f365c4e0fda6a86100231d62f1bf69
+ # via boto3
+scipy==1.13.1 \
+ --hash=sha256:017367484ce5498445aade74b1d5ab377acdc65e27095155e448c88497755a5d \
+ --hash=sha256:095a87a0312b08dfd6a6155cbbd310a8c51800fc931b8c0b84003014b874ed3c \
+ --hash=sha256:20335853b85e9a49ff7572ab453794298bcf0354d8068c5f6775a0eabf350aca \
+ --hash=sha256:27e52b09c0d3a1d5b63e1105f24177e544a222b43611aaf5bc44d4a0979e32f9 \
+ --hash=sha256:2831f0dc9c5ea9edd6e51e6e769b655f08ec6db6e2e10f86ef39bd32eb11da54 \
+ --hash=sha256:2ac65fb503dad64218c228e2dc2d0a0193f7904747db43014645ae139c8fad16 \
+ --hash=sha256:392e4ec766654852c25ebad4f64e4e584cf19820b980bc04960bca0b0cd6eaa2 \
+ --hash=sha256:436bbb42a94a8aeef855d755ce5a465479c721e9d684de76bf61a62e7c2b81d5 \
+ --hash=sha256:45484bee6d65633752c490404513b9ef02475b4284c4cfab0ef946def50b3f59 \
+ --hash=sha256:54f430b00f0133e2224c3ba42b805bfd0086fe488835effa33fa291561932326 \
+ --hash=sha256:5713f62f781eebd8d597eb3f88b8bf9274e79eeabf63afb4a737abc6c84ad37b \
+ --hash=sha256:5d72782f39716b2b3509cd7c33cdc08c96f2f4d2b06d51e52fb45a19ca0c86a1 \
+ --hash=sha256:637e98dcf185ba7f8e663e122ebf908c4702420477ae52a04f9908707456ba4d \
+ --hash=sha256:8335549ebbca860c52bf3d02f80784e91a004b71b059e3eea9678ba994796a24 \
+ --hash=sha256:949ae67db5fa78a86e8fa644b9a6b07252f449dcf74247108c50e1d20d2b4627 \
+ --hash=sha256:a014c2b3697bde71724244f63de2476925596c24285c7a637364761f8710891c \
+ --hash=sha256:a78b4b3345f1b6f68a763c6e25c0c9a23a9fd0f39f5f3d200efe8feda560a5fa \
+ --hash=sha256:cdd7dacfb95fea358916410ec61bbc20440f7860333aee6d882bb8046264e949 \
+ --hash=sha256:cfa31f1def5c819b19ecc3a8b52d28ffdcc7ed52bb20c9a7589669dd3c250989 \
+ --hash=sha256:d533654b7d221a6a97304ab63c41c96473ff04459e404b83275b60aa8f4b7004 \
+ --hash=sha256:d605e9c23906d1994f55ace80e0125c587f96c020037ea6aa98d01b4bd2e222f \
+ --hash=sha256:de3ade0e53bc1f21358aa74ff4830235d716211d7d077e340c7349bc3542e884 \
+ --hash=sha256:e89369d27f9e7b0884ae559a3a956e77c02114cc60a6058b4e5011572eea9299 \
+ --hash=sha256:eccfa1906eacc02de42d70ef4aecea45415f5be17e72b61bafcfd329bdc52e94 \
+ --hash=sha256:f26264b282b9da0952a024ae34710c2aff7d27480ee91a2e82b7b7073c24722f
# via
# -r tools/python/requirements.txt
# jax
# jaxlib
# osqp
# qdldl
-shapely==2.0.0 \
- --hash=sha256:11f1b1231a6c04213fb1226c6968d1b1b3b369ec42d1e9655066af87631860ea \
- --hash=sha256:13a9f978cd287e0fa95f39904a2bb36deddab490e4fab8bf43eba01b7d9eb58f \
- --hash=sha256:17d0f89581aa15f7887052a6adf2753f9fe1c3fdbb6116653972e0d43e720e65 \
- --hash=sha256:21ba32a6c45b7f8ab7d2d8d5cf339704e2d1dfdf3e2fb465b950a0c9bc894a4f \
- --hash=sha256:2287d0cb592c1814e9f48065888af7ee3f13e090e6f7fa3e208b06a83fb2f6af \
- --hash=sha256:292c22ff7806e3a25bc4324295e9204169c61a09165d4c9ee0a9784c1709c85e \
- --hash=sha256:40c397d67ba609a163d38b649eee2b06c5f9bdc86d244a8e4cd09c6e2791cf3c \
- --hash=sha256:44198fc188fe4b7dd39ef0fd325395d1d6ab0c29a7bbaa15663a16c362bf6f62 \
- --hash=sha256:5477be8c11bf3109f7b804bb2d57536538b8d0a6118207f1020d71338f1a827c \
- --hash=sha256:550f110940d79931b6a12a17de07f6b158c9586c4b121f885af11458ae5626d7 \
- --hash=sha256:56c0e70749f8c2956493e9333375d2e2264ce25c838fc49c3a2ececbf2d3ba92 \
- --hash=sha256:5fe8649aafe6adcb4d90f7f735f06ca8ca02a16da273d901f1dd02afc0d3618e \
- --hash=sha256:6c71738702cf5c3fc60b3bbe869c321b053ea754f57addded540a71c78c2612e \
- --hash=sha256:7266080d39946395ba4b31fa35b9b7695e0a4e38ccabf0c67e2936caf9f9b054 \
- --hash=sha256:73771b3f65c2949cce0b310b9b62b8ce069407ceb497a9dd4436f9a4d059f12c \
- --hash=sha256:73d605fcefd06ee997ba307ef363448d355f3c3e81b3f56ed332eaf6d506e1b5 \
- --hash=sha256:7b2c41514ba985ea3772eee9b386d620784cccb7a459a270a072f3ef01fdd807 \
- --hash=sha256:820bee508e4a0e564db22f8b55bb5e6e7f326d8d7c103639c42f5d3f378f4067 \
- --hash=sha256:8a7ba97c97d85c1f07c57f9524c45128ef2bf8279061945d78052c78862b357f \
- --hash=sha256:8b9f780c3b79b4a6501e0e8833b1877841b7b0e0a243e77b529fda8f1030afc2 \
- --hash=sha256:91bbca0378eb82f0808f0e59150ac0952086f4caaab87ad8515a5e55e896c21e \
- --hash=sha256:99420c89af78f371b96f0e2bad9afdebc6d0707d4275d157101483e4c4049fd6 \
- --hash=sha256:a391cae931976fb6d8d15a4f4a92006358e93486454a812dde1d64184041a476 \
- --hash=sha256:a9b6651812f2caa23e4d06bc06a2ed34450f82cb1c110c170a25b01bbb090895 \
- --hash=sha256:b1def13ec2a74ebda2210d2fc1c53cecce5a079ec90f341101399427874507f1 \
- --hash=sha256:b3d97f3ce6df47ca68c2d64b8c3cfa5c8ccc0fbc81ef8e15ff6004a6426e71b1 \
- --hash=sha256:c47a61b1cd0c5b064c6d912bce7dba78c01f319f65ecccd6e61eecd21861a37a \
- --hash=sha256:c4b99a3456e06dc55482569669ece969cdab311f2ad2a1d5622fc770f68cf3cd \
- --hash=sha256:d28e19791c9be2ba1cb2fddefa86f73364bdf8334e88dbcd78a8e4494c0af66b \
- --hash=sha256:d486cab823f0a978964ae97ca10564ea2b2ced93e84a2ef0b7b62cbacec9d3d2 \
- --hash=sha256:de3722c68e49fbde8cb6859695bbb8fb9a4d48bbdf34fcf38b7994d2bd9772e2 \
- --hash=sha256:e4ed31658fd0799eaa3569982aab1a5bc8fcf25ec196606bf137ee4fa984be88 \
- --hash=sha256:e991ad155783cd0830b895ec8f310fde9e79a7b283776b889a751fb1e7c819fc \
- --hash=sha256:eab24b60ae96b7375adceb1f120be818c59bd69db0f3540dc89527d8a371d253 \
- --hash=sha256:eaea9ddee706654026a84aceb9a3156105917bab3de58fcf150343f847478202 \
- --hash=sha256:ef98fec4a3aca6d33e3b9fdd680fe513cc7d1c6aedc65ada8a3965601d9d4bcf \
- --hash=sha256:f69c418f2040c8593e33b1aba8f2acf890804b073b817535b5d291139d152af5 \
- --hash=sha256:f96b24da0242791cd6042f6caf074e7a4537a66ca2d1b57d423feb98ba901295
+shapely==2.0.6 \
+ --hash=sha256:0334bd51828f68cd54b87d80b3e7cee93f249d82ae55a0faf3ea21c9be7b323a \
+ --hash=sha256:1bbc783529a21f2bd50c79cef90761f72d41c45622b3e57acf78d984c50a5d13 \
+ --hash=sha256:2423f6c0903ebe5df6d32e0066b3d94029aab18425ad4b07bf98c3972a6e25a1 \
+ --hash=sha256:28f87cdf5308a514763a5c38de295544cb27429cfa655d50ed8431a4796090c4 \
+ --hash=sha256:29a34e068da2d321e926b5073539fd2a1d4429a2c656bd63f0bd4c8f5b236d0b \
+ --hash=sha256:2ad2fae12dca8d2b727fa12b007e46fbc522148a584f5d6546c539f3464dccde \
+ --hash=sha256:2b542d7f1dbb89192d3512c52b679c822ba916f93479fa5d4fc2fe4fa0b3c9e8 \
+ --hash=sha256:2c665a0301c645615a107ff7f52adafa2153beab51daf34587170d85e8ba6805 \
+ --hash=sha256:2de00c3bfa80d6750832bde1d9487e302a6dd21d90cb2f210515cefdb616e5f5 \
+ --hash=sha256:392f66f458a0a2c706254f473290418236e52aa4c9b476a072539d63a2460595 \
+ --hash=sha256:3a82d58a1134d5e975f19268710e53bddd9c473743356c90d97ce04b73e101ee \
+ --hash=sha256:3ec3a0eab496b5e04633a39fa3d5eb5454628228201fb24903d38174ee34565e \
+ --hash=sha256:42805ef90783ce689a4dde2b6b2f261e2c52609226a0438d882e3ced40bb3013 \
+ --hash=sha256:42fd4cd4834747e4990227e4cbafb02242c0cffe9ce7ef9971f53ac52d80d55f \
+ --hash=sha256:44246d30124a4f1a638a7d5419149959532b99dfa25b54393512e6acc9c211ac \
+ --hash=sha256:537c4b2716d22c92036d00b34aac9d3775e3691f80c7aa517c2c290351f42cd8 \
+ --hash=sha256:5aeb0f51a9db176da9a30cb2f4329b6fbd1e26d359012bb0ac3d3c7781667a9e \
+ --hash=sha256:665990c84aece05efb68a21b3523a6b2057e84a1afbef426ad287f0796ef8a48 \
+ --hash=sha256:6d2cb146191a47bd0cee8ff5f90b47547b82b6345c0d02dd8b25b88b68af62d7 \
+ --hash=sha256:7060566bc4888b0c8ed14b5d57df8a0ead5c28f9b69fb6bed4476df31c51b0af \
+ --hash=sha256:81d9dfe155f371f78c8d895a7b7f323bb241fb148d848a2bf2244f79213123fe \
+ --hash=sha256:837d395fac58aa01aa544495b97940995211e3e25f9aaf87bc3ba5b3a8cd1ac7 \
+ --hash=sha256:83b94a44ab04a90e88be69e7ddcc6f332da7c0a0ebb1156e1c4f568bbec983c3 \
+ --hash=sha256:8b3b818c4407eaa0b4cb376fd2305e20ff6df757bf1356651589eadc14aab41b \
+ --hash=sha256:98fea108334be345c283ce74bf064fa00cfdd718048a8af7343c59eb40f59726 \
+ --hash=sha256:997f6159b1484059ec239cacaa53467fd8b5564dabe186cd84ac2944663b0bf6 \
+ --hash=sha256:9a7a78b0d51257a367ee115f4d41ca4d46edbd0dd280f697a8092dd3989867b2 \
+ --hash=sha256:b02154b3e9d076a29a8513dffcb80f047a5ea63c897c0cd3d3679f29363cf7e5 \
+ --hash=sha256:b3304883bd82d44be1b27a9d17f1167fda8c7f5a02a897958d86c59ec69b705e \
+ --hash=sha256:b3dc9fb0eb56498912025f5eb352b5126f04801ed0e8bdbd867d21bdbfd7cbd0 \
+ --hash=sha256:c02eb6bf4cfb9fe6568502e85bb2647921ee49171bcd2d4116c7b3109724ef9b \
+ --hash=sha256:c6d88ade96bf02f6bfd667ddd3626913098e243e419a0325ebef2bbd481d1eb6 \
+ --hash=sha256:cec9193519940e9d1b86a3b4f5af9eb6910197d24af02f247afbfb47bcb3fab0 \
+ --hash=sha256:d37d070da9e0e0f0a530a621e17c0b8c3c9d04105655132a87cfff8bd77cc4c2 \
+ --hash=sha256:d93b7e0e71c9f095e09454bf18dad5ea716fb6ced5df3cb044564a00723f339d \
+ --hash=sha256:e1c84c3f53144febf6af909d6b581bc05e8785d57e27f35ebaa5c1ab9baba13b \
+ --hash=sha256:e3fdef0a1794a8fe70dc1f514440aa34426cc0ae98d9a1027fb299d45741c381 \
+ --hash=sha256:eba5bae271d523c938274c61658ebc34de6c4b33fdf43ef7e938b5776388c1be \
+ --hash=sha256:ed5867e598a9e8ac3291da6cc9baa62ca25706eea186117034e8ec0ea4355653 \
+ --hash=sha256:f32c23d2f43d54029f986479f7c1f6e09c6b3a19353a3833c2ffb226fb63a855 \
+ --hash=sha256:fa7468e4f5b92049c0f36d63c3e309f85f2775752e076378e36c6387245c5462 \
+ --hash=sha256:fbb7bf02a7542dba55129062570211cfb0defa05386409b3e306c39612e7fbcc
# via -r tools/python/requirements.txt
six==1.16.0 \
--hash=sha256:1e61c37477a1626458e36f7b1d82aa5c9b094fa4802892072e49de9c60c4c926 \
--hash=sha256:8abb2f1d86890a2dfb989f9a77cfcfd3e47c2a354b01111771326f8aa26e0254
# via
+ # astunparse
# glog
+ # google-pasta
+ # ml-collections
+ # promise
# python-dateutil
-sympy==1.12 \
- --hash=sha256:c3588cd4295d0c0f603d0f2ae780587e64e2efeedb3521e46b9bb1d08d184fa5 \
- --hash=sha256:ebf595c8dac3e0fdc4152c51878b498396ec7f30e7a914d6071e674d49420fb8
+ # tensorboard
+ # tensorflow
+ # tensorflow-probability
+sniffio==1.3.1 \
+ --hash=sha256:2f6da418d1f1e0fddd844478f41680e794e6051915791a034ff65e5f100525a2 \
+ --hash=sha256:f4324edc670a0f49750a81b895f35c3adb843cca46f0530f79fc1babb23789dc
+ # via anyio
+sqlalchemy==2.0.35 \
+ --hash=sha256:016b2e665f778f13d3c438651dd4de244214b527a275e0acf1d44c05bc6026a9 \
+ --hash=sha256:032d979ce77a6c2432653322ba4cbeabf5a6837f704d16fa38b5a05d8e21fa00 \
+ --hash=sha256:0375a141e1c0878103eb3d719eb6d5aa444b490c96f3fedab8471c7f6ffe70ee \
+ --hash=sha256:042622a5306c23b972192283f4e22372da3b8ddf5f7aac1cc5d9c9b222ab3ff6 \
+ --hash=sha256:05c3f58cf91683102f2f0265c0db3bd3892e9eedabe059720492dbaa4f922da1 \
+ --hash=sha256:0630774b0977804fba4b6bbea6852ab56c14965a2b0c7fc7282c5f7d90a1ae72 \
+ --hash=sha256:0f9f3f9a3763b9c4deb8c5d09c4cc52ffe49f9876af41cc1b2ad0138878453cf \
+ --hash=sha256:1b56961e2d31389aaadf4906d453859f35302b4eb818d34a26fab72596076bb8 \
+ --hash=sha256:22b83aed390e3099584b839b93f80a0f4a95ee7f48270c97c90acd40ee646f0b \
+ --hash=sha256:25b0f63e7fcc2a6290cb5f7f5b4fc4047843504983a28856ce9b35d8f7de03cc \
+ --hash=sha256:2a275a806f73e849e1c309ac11108ea1a14cd7058577aba962cd7190e27c9e3c \
+ --hash=sha256:2ab3f0336c0387662ce6221ad30ab3a5e6499aab01b9790879b6578fd9b8faa1 \
+ --hash=sha256:2e795c2f7d7249b75bb5f479b432a51b59041580d20599d4e112b5f2046437a3 \
+ --hash=sha256:3655af10ebcc0f1e4e06c5900bb33e080d6a1fa4228f502121f28a3b1753cde5 \
+ --hash=sha256:4668bd8faf7e5b71c0319407b608f278f279668f358857dbfd10ef1954ac9f90 \
+ --hash=sha256:4c31943b61ed8fdd63dfd12ccc919f2bf95eefca133767db6fbbd15da62078ec \
+ --hash=sha256:4fdcd72a789c1c31ed242fd8c1bcd9ea186a98ee8e5408a50e610edfef980d71 \
+ --hash=sha256:627dee0c280eea91aed87b20a1f849e9ae2fe719d52cbf847c0e0ea34464b3f7 \
+ --hash=sha256:67219632be22f14750f0d1c70e62f204ba69d28f62fd6432ba05ab295853de9b \
+ --hash=sha256:6921ee01caf375363be5e9ae70d08ce7ca9d7e0e8983183080211a062d299468 \
+ --hash=sha256:69683e02e8a9de37f17985905a5eca18ad651bf592314b4d3d799029797d0eb3 \
+ --hash=sha256:6a93c5a0dfe8d34951e8a6f499a9479ffb9258123551fa007fc708ae2ac2bc5e \
+ --hash=sha256:732e026240cdd1c1b2e3ac515c7a23820430ed94292ce33806a95869c46bd139 \
+ --hash=sha256:7befc148de64b6060937231cbff8d01ccf0bfd75aa26383ffdf8d82b12ec04ff \
+ --hash=sha256:890da8cd1941fa3dab28c5bac3b9da8502e7e366f895b3b8e500896f12f94d11 \
+ --hash=sha256:89b64cd8898a3a6f642db4eb7b26d1b28a497d4022eccd7717ca066823e9fb01 \
+ --hash=sha256:8a6219108a15fc6d24de499d0d515c7235c617b2540d97116b663dade1a54d62 \
+ --hash=sha256:8cdf1a0dbe5ced887a9b127da4ffd7354e9c1a3b9bb330dce84df6b70ccb3a8d \
+ --hash=sha256:8d625eddf7efeba2abfd9c014a22c0f6b3796e0ffb48f5d5ab106568ef01ff5a \
+ --hash=sha256:93a71c8601e823236ac0e5d087e4f397874a421017b3318fd92c0b14acf2b6db \
+ --hash=sha256:9509c4123491d0e63fb5e16199e09f8e262066e58903e84615c301dde8fa2e87 \
+ --hash=sha256:a29762cd3d116585278ffb2e5b8cc311fb095ea278b96feef28d0b423154858e \
+ --hash=sha256:a62dd5d7cc8626a3634208df458c5fe4f21200d96a74d122c83bc2015b333bc1 \
+ --hash=sha256:ada603db10bb865bbe591939de854faf2c60f43c9b763e90f653224138f910d9 \
+ --hash=sha256:aee110e4ef3c528f3abbc3c2018c121e708938adeeff9006428dd7c8555e9b3f \
+ --hash=sha256:b76d63495b0508ab9fc23f8152bac63205d2a704cd009a2b0722f4c8e0cba8e0 \
+ --hash=sha256:c0d8326269dbf944b9201911b0d9f3dc524d64779a07518199a58384c3d37a44 \
+ --hash=sha256:c41411e192f8d3ea39ea70e0fae48762cd11a2244e03751a98bd3c0ca9a4e936 \
+ --hash=sha256:c68fe3fcde03920c46697585620135b4ecfdfc1ed23e75cc2c2ae9f8502c10b8 \
+ --hash=sha256:cb8bea573863762bbf45d1e13f87c2d2fd32cee2dbd50d050f83f87429c9e1ea \
+ --hash=sha256:cc32b2990fc34380ec2f6195f33a76b6cdaa9eecf09f0c9404b74fc120aef36f \
+ --hash=sha256:ccae5de2a0140d8be6838c331604f91d6fafd0735dbdcee1ac78fc8fbaba76b4 \
+ --hash=sha256:d299797d75cd747e7797b1b41817111406b8b10a4f88b6e8fe5b5e59598b43b0 \
+ --hash=sha256:e04b622bb8a88f10e439084486f2f6349bf4d50605ac3e445869c7ea5cf0fa8c \
+ --hash=sha256:e11d7ea4d24f0a262bccf9a7cd6284c976c5369dac21db237cff59586045ab9f \
+ --hash=sha256:e21f66748ab725ade40fa7af8ec8b5019c68ab00b929f6643e1b1af461eddb60 \
+ --hash=sha256:eb60b026d8ad0c97917cb81d3662d0b39b8ff1335e3fabb24984c6acd0c900a2 \
+ --hash=sha256:f021d334f2ca692523aaf7bbf7592ceff70c8594fad853416a81d66b35e3abf9 \
+ --hash=sha256:f552023710d4b93d8fb29a91fadf97de89c5926c6bd758897875435f2a939f33
+ # via
+ # aim
+ # alembic
+starlette==0.38.6 \
+ --hash=sha256:4517a1409e2e73ee4951214ba012052b9e16f60e90d73cfb06192c19203bbb05 \
+ --hash=sha256:863a1588f5574e70a821dadefb41e4881ea451a47a3cd1b4df359d4ffefe5ead
+ # via fastapi
+sympy==1.13.2 \
+ --hash=sha256:401449d84d07be9d0c7a46a64bd54fe097667d5e7181bfe67ec777be9e01cb13 \
+ --hash=sha256:c51d75517712f1aed280d4ce58506a4a88d635d6b5dd48b39102a7ae1f3fcfe9
# via -r tools/python/requirements.txt
tabulate==0.9.0 \
--hash=sha256:0095b12bf5966de529c0feb1fa08671671b3368eec77d7ef7ab114be2c068b3c \
--hash=sha256:024ca478df22e9340661486f85298cff5f6dcdba14f3813e8830015b9ed1948f
# via -r tools/python/requirements.txt
-tornado==6.4 \
- --hash=sha256:02ccefc7d8211e5a7f9e8bc3f9e5b0ad6262ba2fbb683a6443ecc804e5224ce0 \
- --hash=sha256:10aeaa8006333433da48dec9fe417877f8bcc21f48dda8d661ae79da357b2a63 \
- --hash=sha256:27787de946a9cffd63ce5814c33f734c627a87072ec7eed71f7fc4417bb16263 \
- --hash=sha256:6f8a6c77900f5ae93d8b4ae1196472d0ccc2775cc1dfdc9e7727889145c45052 \
- --hash=sha256:71ddfc23a0e03ef2df1c1397d859868d158c8276a0603b96cf86892bff58149f \
- --hash=sha256:72291fa6e6bc84e626589f1c29d90a5a6d593ef5ae68052ee2ef000dfd273dee \
- --hash=sha256:88b84956273fbd73420e6d4b8d5ccbe913c65d31351b4c004ae362eba06e1f78 \
- --hash=sha256:e43bc2e5370a6a8e413e1e1cd0c91bedc5bd62a74a532371042a18ef19e10579 \
- --hash=sha256:f0251554cdd50b4b44362f73ad5ba7126fc5b2c2895cc62b14a1c2d7ea32f212 \
- --hash=sha256:f7894c581ecdcf91666a0912f18ce5e757213999e183ebfc2c3fdbf4d5bd764e \
- --hash=sha256:fd03192e287fbd0899dd8f81c6fb9cbbc69194d2074b38f384cb6fa72b80e9c2
+tenacity==9.0.0 \
+ --hash=sha256:807f37ca97d62aa361264d497b0e31e92b8027044942bfa756160d908320d73b \
+ --hash=sha256:93de0c98785b27fcf659856aa9f54bfbd399e29969b0621bc7f762bd441b4539
+ # via plotly
+tensorboard==2.17.1 \
+ --hash=sha256:253701a224000eeca01eee6f7e978aea7b408f60b91eb0babdb04e78947b773e
+ # via tensorflow
+tensorboard-data-server==0.7.2 \
+ --hash=sha256:7e0610d205889588983836ec05dc098e80f97b7e7bbff7e994ebb78f578d0ddb \
+ --hash=sha256:9fe5d24221b29625dbc7328b0436ca7fc1c23de4acf4d272f1180856e32f9f60 \
+ --hash=sha256:ef687163c24185ae9754ed5650eb5bc4d84ff257aabdc33f0cc6f74d8ba54530
+ # via tensorboard
+tensorflow==2.17.0 \
+ --hash=sha256:0ad7bfea6afb4ded3928ca5b24df9fda876cea4904c103a5163fcc0c3483e7a4 \
+ --hash=sha256:147c93ded4cb7e500a65d3c26d74744ff41660db7a8afe2b00d1d08bf329b4ec \
+ --hash=sha256:278bc80642d799adf08dc4e04f291aab603bba7457d50c1f9bc191ebbca83f43 \
+ --hash=sha256:4ae8e6746deb2ec807b902ba26d62fcffb6a6b53555a1a5906ec00416c5e4175 \
+ --hash=sha256:515fe5ae8a9bc50312575412b08515f3ca66514c155078e0707bdffbea75d783 \
+ --hash=sha256:72adfef0ee39dd641627906fd7b244fcf21bdd8a87216a998ed74d9c74653aff \
+ --hash=sha256:8339777b1b5ebd8ffadaa8196f786e65fbb081a371d8e87b52f24563392d8552 \
+ --hash=sha256:8f80d11ad3766570deb6ff47d2bed2d166f51399ca08205e38ef024345571d6f \
+ --hash=sha256:97f89e95d68b4b46e1072243b9f315c3b340e27cc07b1e1988e2ca97ad844305 \
+ --hash=sha256:b36683ac28af20abc3a548c72bf4537b00df1b1f3dd39d59df3873fefaf26f15 \
+ --hash=sha256:ca82f98ea38fa6c9e08ccc69eb6c2fab5b35b30a8999115b8b63b6f02fc69d9d \
+ --hash=sha256:dde37cff74ed22b8fa2eea944805b001ae38e96adc989666422bdea34f4e2d47 \
+ --hash=sha256:e46090587f69e33637d17d7c3d94a790cac7d4bc5ff5ecbf3e71fdc6982fe96e \
+ --hash=sha256:e8d26d6c24ccfb139db1306599257ca8f5cfe254ef2d023bfb667f374a17a64d \
+ --hash=sha256:ee18b4fcd627c5e872eabb25092af6c808b6ec77948662c88fc5c89a60eb0211 \
+ --hash=sha256:ef615c133cf4d592a073feda634ccbeb521a554be57de74f8c318d38febbeab5
+ # via
+ # -r tools/python/requirements.txt
+ # tf-keras
+tensorflow-datasets==4.9.3 \
+ --hash=sha256:09cd60eccab0d5a9d15f53e76ee0f1b530ee5aa3665e42be621a4810d9fa5db6 \
+ --hash=sha256:90390077dde2c9e4e240754ddfc5bb50b482946d421c8a34677c3afdb0463427
+ # via -r tools/python/requirements.txt
+tensorflow-io-gcs-filesystem==0.37.1 \
+ --hash=sha256:0df00891669390078a003cedbdd3b8e645c718b111917535fa1d7725e95cdb95 \
+ --hash=sha256:249c12b830165841411ba71e08215d0e94277a49c551e6dd5d72aab54fe5491b \
+ --hash=sha256:257aab23470a0796978efc9c2bcf8b0bc80f22e6298612a4c0a50d3f4e88060c \
+ --hash=sha256:286389a203a5aee1a4fa2e53718c661091aa5fea797ff4fa6715ab8436b02e6c \
+ --hash=sha256:32c50ab4e29a23c1f91cd0f9ab8c381a0ab10f45ef5c5252e94965916041737c \
+ --hash=sha256:426de1173cb81fbd62becec2012fc00322a295326d90eb6c737fab636f182aed \
+ --hash=sha256:6e1f2796b57e799a8ca1b75bf47c2aaa437c968408cc1a402a9862929e104cda \
+ --hash=sha256:8943036bbf84e7a2be3705cb56f9c9df7c48c9e614bb941f0936c58e3ca89d6f \
+ --hash=sha256:8febbfcc67c61e542a5ac1a98c7c20a91a5e1afc2e14b1ef0cb7c28bc3b6aa70 \
+ --hash=sha256:9679b36e3a80921876f31685ab6f7270f3411a4cc51bc2847e80d0e4b5291e27 \
+ --hash=sha256:b02f9c5f94fd62773954a04f69b68c4d576d076fd0db4ca25d5479f0fbfcdbad \
+ --hash=sha256:ee5da49019670ed364f3e5fb86b46420841a6c3cb52a300553c63841671b3e6d \
+ --hash=sha256:ee7c8ee5fe2fd8cb6392669ef16e71841133041fee8a330eff519ad9b36e4556 \
+ --hash=sha256:fbb33f1745f218464a59cecd9a18e32ca927b0f4d77abd8f8671b645cc1a182f \
+ --hash=sha256:fe8dcc6d222258a080ac3dfcaaaa347325ce36a7a046277f6b3e19abc1efb3c5 \
+ --hash=sha256:ffebb6666a7bfc28005f4fbbb111a455b5e7d6cd3b12752b7050863ecb27d5cc
+ # via tensorflow
+tensorflow-metadata==1.15.0 \
+ --hash=sha256:cb84d8e159128aeae7b3f6013ccd7969c69d2e6d1a7b255dbfa6f5344d962986
+ # via tensorflow-datasets
+tensorflow-probability==0.24.0 \
+ --hash=sha256:8c1774683e38359dbcaf3697e79b7e6a4e69b9c7b3679e78ee18f43e59e5759b
+ # via -r tools/python/requirements.txt
+tensorstore==0.1.64 \
+ --hash=sha256:1a78aedbddccc09ea283b145496da03dbc7eb8693ae4e01074ed791d72b7eac2 \
+ --hash=sha256:24a4cebaf9d0e75d494342948f68edc971d6bb90e23192ddf8d98397fb1ff3cb \
+ --hash=sha256:2b0a1e3294d2e690a9c269ea50d62f2f60f7935ca507243d8b56b2871b0e201f \
+ --hash=sha256:3da6fa00ddf312e1b502d2ee9de39b858a78a02b396114201c67c01bc03fc382 \
+ --hash=sha256:3e35c6e90429e517d3debdb974cb5d42e57d8c002629343a34483efbe0d4e490 \
+ --hash=sha256:40cae39aca2992fdac0ed5fbcef71f72cd38a759b1a61c37d95ad395606697b4 \
+ --hash=sha256:55af5ec5bd78056e4df18f4af107bac7ea84d2bdc34ff6ab6642b3a036f99390 \
+ --hash=sha256:72517af8c5f9c49d0343acb7c6b0cc250f8077ca989285d471d3a64dbbfcc36b \
+ --hash=sha256:72f76231ce12bfd266358a096e9c6000a2d86c1f4f24c3891c29b2edfffc5df4 \
+ --hash=sha256:7fa89e90876fb5377efc54f3f37326a6fb83ec9e1326565819a75a4e80949886 \
+ --hash=sha256:806774968ee4cc8809114281730e9fad5970a94a7ef9104bc54fa35a32068b2f \
+ --hash=sha256:80c510024cc31c4dee7f478ea67a0b4b4cacf5a6bffe8c4e446188fdbe2d7b4c \
+ --hash=sha256:8cf64ee03c7cd62a0dde2f4d1f3f8784d50aea3a2e85a65686be0fe33ea18ed5 \
+ --hash=sha256:9968f9a9b9cd7c669bfae5244307e105c006038e8dd156eebbf2146f771ba369 \
+ --hash=sha256:abbe9c65978a5423751409df9c98efb69b2093953aa37d3a1605fc60663eb1d4 \
+ --hash=sha256:b46296a1c1f43f472e589d2fb43b9d6549d711486be78b6e3aafaff4179d8f56 \
+ --hash=sha256:c32976f5a0e881a097b52a488fb16d33a1d94a86393115098da87894fc9c5abf \
+ --hash=sha256:c369088c74c0dda30398290724513a0289f25ccc01865ed5aec62e57f1930709 \
+ --hash=sha256:c90d38b552c79f0d688cc3d502a9023e3dee9821881d6727d8aa06482ccdc0c1 \
+ --hash=sha256:cc315029f49c0f294f0721462c221e0ef4c15360a526cc34392ac81565fd63b8 \
+ --hash=sha256:f47597209ce11228cfe6b94999f582788aac5571e85c3e8dcaa43b1f07660589
+ # via
+ # flashbax
+ # flax
+ # orbax-checkpoint
+termcolor==2.4.0 \
+ --hash=sha256:9297c0df9c99445c2412e832e882a7884038a25617c60cea2ad69488d4040d63 \
+ --hash=sha256:aab9e56047c8ac41ed798fa36d892a37aca6b3e9159f3e0c24bc64a9b3ac7b7a
+ # via
+ # tensorflow
+ # tensorflow-datasets
+tf-keras==2.17.0 \
+ --hash=sha256:cc97717e4dc08487f327b0740a984043a9e0123c7a4e21206711669d3ec41c88 \
+ --hash=sha256:fda97c18da30da0f72a5a7e80f3eee343b09f4c206dad6c57c944fb2cd18560e
+ # via -r tools/python/requirements.txt
+toml==0.10.2 \
+ --hash=sha256:806143ae5bfb6a3c6e736a764057db0e6a0e05e338b5630894a5f779cabb4f9b \
+ --hash=sha256:b3bda1d108d5dd99f4a20d24d9c348e91c4db7ab1b749200bded2f839ccbe68f
+ # via tensorflow-datasets
+tomli==2.0.1 \
+ --hash=sha256:939de3e7a6161af0c887ef91b7d41a53e7c5a1ca976325f429cb46ea9bc30ecc \
+ --hash=sha256:de526c12914f0c550d15924c62d72abc48d6fe7364aa87328337a31007fe8a4f
+ # via yapf
+toolz==0.12.1 \
+ --hash=sha256:d22731364c07d72eea0a0ad45bafb2c2937ab6fd38a3507bf55eae8744aa7d85 \
+ --hash=sha256:ecca342664893f177a13dac0e6b41cbd8ac25a358e5f215316d43e2100224f4d
+ # via chex
+tornado==6.4.1 \
+ --hash=sha256:163b0aafc8e23d8cdc3c9dfb24c5368af84a81e3364745ccb4427669bf84aec8 \
+ --hash=sha256:25486eb223babe3eed4b8aecbac33b37e3dd6d776bc730ca14e1bf93888b979f \
+ --hash=sha256:454db8a7ecfcf2ff6042dde58404164d969b6f5d58b926da15e6b23817950fc4 \
+ --hash=sha256:613bf4ddf5c7a95509218b149b555621497a6cc0d46ac341b30bd9ec19eac7f3 \
+ --hash=sha256:6d5ce3437e18a2b66fbadb183c1d3364fb03f2be71299e7d10dbeeb69f4b2a14 \
+ --hash=sha256:8ae50a504a740365267b2a8d1a90c9fbc86b780a39170feca9bcc1787ff80842 \
+ --hash=sha256:92d3ab53183d8c50f8204a51e6f91d18a15d5ef261e84d452800d4ff6fc504e9 \
+ --hash=sha256:a02a08cc7a9314b006f653ce40483b9b3c12cda222d6a46d4ac63bb6c9057698 \
+ --hash=sha256:b24b8982ed444378d7f21d563f4180a2de31ced9d8d84443907a0a64da2072e7 \
+ --hash=sha256:d9a566c40b89757c9aa8e6f032bcdb8ca8795d7c1a9762910c722b1635c9de4d \
+ --hash=sha256:e2e20b9113cd7293f164dc46fffb13535266e713cdb87bd2d15ddb336e96cfc4
# via bokeh
+tqdm==4.66.5 \
+ --hash=sha256:90279a3770753eafc9194a0364852159802111925aa30eb3f9d85b0e805ac7cd \
+ --hash=sha256:e1020aef2e5096702d8a025ac7d16b1577279c9d63f8375b63083e9a5f0fcbad
+ # via
+ # aim
+ # tensorflow-datasets
+typeguard==2.13.3 \
+ --hash=sha256:00edaa8da3a133674796cf5ea87d9f4b4c367d77476e185e80251cc13dfbb8c4 \
+ --hash=sha256:5e3e3be01e887e7eafae5af63d1f36c849aaa94e3a0112097312aabfa16284f1
+ # via jaxtyping
+typing-extensions==4.12.2 \
+ --hash=sha256:04e5ca0351e0f3f85c6853954072df659d0d13fac324d0072316b67d7794700d \
+ --hash=sha256:1a7ead55c7e559dd4dee8856e3a88b41225abfe1ce8df57b7c13915fe121ffb8
+ # via
+ # alembic
+ # anyio
+ # chex
+ # clu
+ # etils
+ # fastapi
+ # flashbax
+ # flax
+ # optree
+ # orbax-checkpoint
+ # pydantic
+ # pydantic-core
+ # sqlalchemy
+ # starlette
+ # tensorflow
+ # uvicorn
tzdata==2024.1 \
--hash=sha256:2674120f8d891909751c38abcdfd386ac0a5a1127954fbc332af6b5ceae07efd \
--hash=sha256:9068bc196136463f5245e51efda838afa15aaeca9903f49050dfa2679db4d252
# via pandas
-urllib3==1.26.13 \
- --hash=sha256:47cc05d99aaa09c9e72ed5809b60e7ba354e64b59c9c173ac3018642d8bb41fc \
- --hash=sha256:c083dd0dce68dbfbe1129d5271cb90f9447dea7d52097c6e0126120c521ddea8
- # via requests
-validators==0.22.0 \
- --hash=sha256:61cf7d4a62bbae559f2e54aed3b000cea9ff3e2fdbe463f51179b92c58c9585a \
- --hash=sha256:77b2689b172eeeb600d9605ab86194641670cdb73b60afd577142a9397873370
+urllib3==1.26.20 \
+ --hash=sha256:0ed14ccfbf1c30a9072c7ca157e4319b70d65f623e91e7b32fadb2853431016e \
+ --hash=sha256:40c2dc0c681e47eb8f90e7e27bf6ff7df2e677421fd46756da1161c39ca70d32
+ # via
+ # botocore
+ # requests
+uvicorn==0.30.6 \
+ --hash=sha256:4b15decdda1e72be08209e860a1e10e92439ad5b97cf44cc945fcbee66fc5788 \
+ --hash=sha256:65fd46fe3fda5bdc1b03b94eb634923ff18cd35b2f084813ea79d1f103f711b5
+ # via aim
+validators==0.34.0 \
+ --hash=sha256:647fe407b45af9a74d245b943b18e6a816acf4926974278f6dd617778e1e781f \
+ --hash=sha256:c804b476e3e6d3786fa07a30073a4ef694e617805eb1946ceee3fe5a9b8b1321
# via -r tools/python/requirements.txt
-watchdog==2.1.9 \
- --hash=sha256:083171652584e1b8829581f965b9b7723ca5f9a2cd7e20271edf264cfd7c1412 \
- --hash=sha256:117ffc6ec261639a0209a3252546b12800670d4bf5f84fbd355957a0595fe654 \
- --hash=sha256:186f6c55abc5e03872ae14c2f294a153ec7292f807af99f57611acc8caa75306 \
- --hash=sha256:195fc70c6e41237362ba720e9aaf394f8178bfc7fa68207f112d108edef1af33 \
- --hash=sha256:226b3c6c468ce72051a4c15a4cc2ef317c32590d82ba0b330403cafd98a62cfd \
- --hash=sha256:247dcf1df956daa24828bfea5a138d0e7a7c98b1a47cf1fa5b0c3c16241fcbb7 \
- --hash=sha256:255bb5758f7e89b1a13c05a5bceccec2219f8995a3a4c4d6968fe1de6a3b2892 \
- --hash=sha256:43ce20ebb36a51f21fa376f76d1d4692452b2527ccd601950d69ed36b9e21609 \
- --hash=sha256:4f4e1c4aa54fb86316a62a87b3378c025e228178d55481d30d857c6c438897d6 \
- --hash=sha256:5952135968519e2447a01875a6f5fc8c03190b24d14ee52b0f4b1682259520b1 \
- --hash=sha256:64a27aed691408a6abd83394b38503e8176f69031ca25d64131d8d640a307591 \
- --hash=sha256:6b17d302850c8d412784d9246cfe8d7e3af6bcd45f958abb2d08a6f8bedf695d \
- --hash=sha256:70af927aa1613ded6a68089a9262a009fbdf819f46d09c1a908d4b36e1ba2b2d \
- --hash=sha256:7a833211f49143c3d336729b0020ffd1274078e94b0ae42e22f596999f50279c \
- --hash=sha256:8250546a98388cbc00c3ee3cc5cf96799b5a595270dfcfa855491a64b86ef8c3 \
- --hash=sha256:97f9752208f5154e9e7b76acc8c4f5a58801b338de2af14e7e181ee3b28a5d39 \
- --hash=sha256:9f05a5f7c12452f6a27203f76779ae3f46fa30f1dd833037ea8cbc2887c60213 \
- --hash=sha256:a735a990a1095f75ca4f36ea2ef2752c99e6ee997c46b0de507ba40a09bf7330 \
- --hash=sha256:ad576a565260d8f99d97f2e64b0f97a48228317095908568a9d5c786c829d428 \
- --hash=sha256:b530ae007a5f5d50b7fbba96634c7ee21abec70dc3e7f0233339c81943848dc1 \
- --hash=sha256:bfc4d351e6348d6ec51df007432e6fe80adb53fd41183716017026af03427846 \
- --hash=sha256:d3dda00aca282b26194bdd0adec21e4c21e916956d972369359ba63ade616153 \
- --hash=sha256:d9820fe47c20c13e3c9dd544d3706a2a26c02b2b43c993b62fcd8011bcc0adb3 \
- --hash=sha256:ed80a1628cee19f5cfc6bb74e173f1b4189eb532e705e2a13e3250312a62e0c9 \
- --hash=sha256:ee3e38a6cc050a8830089f79cbec8a3878ec2fe5160cdb2dc8ccb6def8552658
+watchdog==5.0.2 \
+ --hash=sha256:14dd4ed023d79d1f670aa659f449bcd2733c33a35c8ffd88689d9d243885198b \
+ --hash=sha256:29e4a2607bd407d9552c502d38b45a05ec26a8e40cc7e94db9bb48f861fa5abc \
+ --hash=sha256:3960136b2b619510569b90f0cd96408591d6c251a75c97690f4553ca88889769 \
+ --hash=sha256:3e8d5ff39f0a9968952cce548e8e08f849141a4fcc1290b1c17c032ba697b9d7 \
+ --hash=sha256:53ed1bf71fcb8475dd0ef4912ab139c294c87b903724b6f4a8bd98e026862e6d \
+ --hash=sha256:5597c051587f8757798216f2485e85eac583c3b343e9aa09127a3a6f82c65ee8 \
+ --hash=sha256:638bcca3d5b1885c6ec47be67bf712b00a9ab3d4b22ec0881f4889ad870bc7e8 \
+ --hash=sha256:6bec703ad90b35a848e05e1b40bf0050da7ca28ead7ac4be724ae5ac2653a1a0 \
+ --hash=sha256:726eef8f8c634ac6584f86c9c53353a010d9f311f6c15a034f3800a7a891d941 \
+ --hash=sha256:72990192cb63872c47d5e5fefe230a401b87fd59d257ee577d61c9e5564c62e5 \
+ --hash=sha256:7d1aa7e4bb0f0c65a1a91ba37c10e19dabf7eaaa282c5787e51371f090748f4b \
+ --hash=sha256:8c47150aa12f775e22efff1eee9f0f6beee542a7aa1a985c271b1997d340184f \
+ --hash=sha256:901ee48c23f70193d1a7bc2d9ee297df66081dd5f46f0ca011be4f70dec80dab \
+ --hash=sha256:963f7c4c91e3f51c998eeff1b3fb24a52a8a34da4f956e470f4b068bb47b78ee \
+ --hash=sha256:9814adb768c23727a27792c77812cf4e2fd9853cd280eafa2bcfa62a99e8bd6e \
+ --hash=sha256:aa9cd6e24126d4afb3752a3e70fce39f92d0e1a58a236ddf6ee823ff7dba28ee \
+ --hash=sha256:b6dc8f1d770a8280997e4beae7b9a75a33b268c59e033e72c8a10990097e5fde \
+ --hash=sha256:b84bff0391ad4abe25c2740c7aec0e3de316fdf7764007f41e248422a7760a7f \
+ --hash=sha256:ba32efcccfe2c58f4d01115440d1672b4eb26cdd6fc5b5818f1fb41f7c3e1889 \
+ --hash=sha256:bda40c57115684d0216556671875e008279dea2dc00fcd3dde126ac8e0d7a2fb \
+ --hash=sha256:c4a440f725f3b99133de610bfec93d570b13826f89616377715b9cd60424db6e \
+ --hash=sha256:d010be060c996db725fbce7e3ef14687cdcc76f4ca0e4339a68cc4532c382a73 \
+ --hash=sha256:d2ab34adc9bf1489452965cdb16a924e97d4452fcf88a50b21859068b50b5c3b \
+ --hash=sha256:d7594a6d32cda2b49df3fd9abf9b37c8d2f3eab5df45c24056b4a671ac661619 \
+ --hash=sha256:d961f4123bb3c447d9fcdcb67e1530c366f10ab3a0c7d1c0c9943050936d4877 \
+ --hash=sha256:dae7a1879918f6544201d33666909b040a46421054a50e0f773e0d870ed7438d \
+ --hash=sha256:dcebf7e475001d2cdeb020be630dc5b687e9acdd60d16fea6bb4508e7b94cf76 \
+ --hash=sha256:f627c5bf5759fdd90195b0c0431f99cff4867d212a67b384442c51136a098ed7 \
+ --hash=sha256:f8b2918c19e0d48f5f20df458c84692e2a054f02d9df25e6c3c930063eca64c1 \
+ --hash=sha256:fb223456db6e5f7bd9bbd5cd969f05aae82ae21acc00643b60d81c770abd402b
# via mkdocs
-xyzservices==2024.4.0 \
- --hash=sha256:6a04f11487a6fb77d92a98984cd107fbd9157fd5e65f929add9c3d6e604ee88c \
- --hash=sha256:b83e48c5b776c9969fffcfff57b03d02b1b1cd6607a9d9c4e7f568b01ef47f4c
+websockets==13.1 \
+ --hash=sha256:004280a140f220c812e65f36944a9ca92d766b6cc4560be652a0a3883a79ed8a \
+ --hash=sha256:035233b7531fb92a76beefcbf479504db8c72eb3bff41da55aecce3a0f729e54 \
+ --hash=sha256:149e622dc48c10ccc3d2760e5f36753db9cacf3ad7bc7bbbfd7d9c819e286f23 \
+ --hash=sha256:163e7277e1a0bd9fb3c8842a71661ad19c6aa7bb3d6678dc7f89b17fbcc4aeb7 \
+ --hash=sha256:18503d2c5f3943e93819238bf20df71982d193f73dcecd26c94514f417f6b135 \
+ --hash=sha256:1971e62d2caa443e57588e1d82d15f663b29ff9dfe7446d9964a4b6f12c1e700 \
+ --hash=sha256:204e5107f43095012b00f1451374693267adbb832d29966a01ecc4ce1db26faf \
+ --hash=sha256:2510c09d8e8df777177ee3d40cd35450dc169a81e747455cc4197e63f7e7bfe5 \
+ --hash=sha256:25c35bf84bf7c7369d247f0b8cfa157f989862c49104c5cf85cb5436a641d93e \
+ --hash=sha256:2f85cf4f2a1ba8f602298a853cec8526c2ca42a9a4b947ec236eaedb8f2dc80c \
+ --hash=sha256:308e20f22c2c77f3f39caca508e765f8725020b84aa963474e18c59accbf4c02 \
+ --hash=sha256:325b1ccdbf5e5725fdcb1b0e9ad4d2545056479d0eee392c291c1bf76206435a \
+ --hash=sha256:327b74e915cf13c5931334c61e1a41040e365d380f812513a255aa804b183418 \
+ --hash=sha256:346bee67a65f189e0e33f520f253d5147ab76ae42493804319b5716e46dddf0f \
+ --hash=sha256:38377f8b0cdeee97c552d20cf1865695fcd56aba155ad1b4ca8779a5b6ef4ac3 \
+ --hash=sha256:3c78383585f47ccb0fcf186dcb8a43f5438bd7d8f47d69e0b56f71bf431a0a68 \
+ --hash=sha256:4059f790b6ae8768471cddb65d3c4fe4792b0ab48e154c9f0a04cefaabcd5978 \
+ --hash=sha256:459bf774c754c35dbb487360b12c5727adab887f1622b8aed5755880a21c4a20 \
+ --hash=sha256:463e1c6ec853202dd3657f156123d6b4dad0c546ea2e2e38be2b3f7c5b8e7295 \
+ --hash=sha256:4676df3fe46956fbb0437d8800cd5f2b6d41143b6e7e842e60554398432cf29b \
+ --hash=sha256:485307243237328c022bc908b90e4457d0daa8b5cf4b3723fd3c4a8012fce4c6 \
+ --hash=sha256:48a2ef1381632a2f0cb4efeff34efa97901c9fbc118e01951ad7cfc10601a9bb \
+ --hash=sha256:4b889dbd1342820cc210ba44307cf75ae5f2f96226c0038094455a96e64fb07a \
+ --hash=sha256:586a356928692c1fed0eca68b4d1c2cbbd1ca2acf2ac7e7ebd3b9052582deefa \
+ --hash=sha256:58cf7e75dbf7e566088b07e36ea2e3e2bd5676e22216e4cad108d4df4a7402a0 \
+ --hash=sha256:5993260f483d05a9737073be197371940c01b257cc45ae3f1d5d7adb371b266a \
+ --hash=sha256:5dd6da9bec02735931fccec99d97c29f47cc61f644264eb995ad6c0c27667238 \
+ --hash=sha256:5f2e75431f8dc4a47f31565a6e1355fb4f2ecaa99d6b89737527ea917066e26c \
+ --hash=sha256:5f9fee94ebafbc3117c30be1844ed01a3b177bb6e39088bc6b2fa1dc15572084 \
+ --hash=sha256:61fc0dfcda609cda0fc9fe7977694c0c59cf9d749fbb17f4e9483929e3c48a19 \
+ --hash=sha256:624459daabeb310d3815b276c1adef475b3e6804abaf2d9d2c061c319f7f187d \
+ --hash=sha256:62d516c325e6540e8a57b94abefc3459d7dab8ce52ac75c96cad5549e187e3a7 \
+ --hash=sha256:6548f29b0e401eea2b967b2fdc1c7c7b5ebb3eeb470ed23a54cd45ef078a0db9 \
+ --hash=sha256:6d2aad13a200e5934f5a6767492fb07151e1de1d6079c003ab31e1823733ae79 \
+ --hash=sha256:6d6855bbe70119872c05107e38fbc7f96b1d8cb047d95c2c50869a46c65a8e96 \
+ --hash=sha256:70c5be9f416aa72aab7a2a76c90ae0a4fe2755c1816c153c1a2bcc3333ce4ce6 \
+ --hash=sha256:730f42125ccb14602f455155084f978bd9e8e57e89b569b4d7f0f0c17a448ffe \
+ --hash=sha256:7a43cfdcddd07f4ca2b1afb459824dd3c6d53a51410636a2c7fc97b9a8cf4842 \
+ --hash=sha256:7bd6abf1e070a6b72bfeb71049d6ad286852e285f146682bf30d0296f5fbadfa \
+ --hash=sha256:7c1e90228c2f5cdde263253fa5db63e6653f1c00e7ec64108065a0b9713fa1b3 \
+ --hash=sha256:7c65ffa900e7cc958cd088b9a9157a8141c991f8c53d11087e6fb7277a03f81d \
+ --hash=sha256:80c421e07973a89fbdd93e6f2003c17d20b69010458d3a8e37fb47874bd67d51 \
+ --hash=sha256:82d0ba76371769d6a4e56f7e83bb8e81846d17a6190971e38b5de108bde9b0d7 \
+ --hash=sha256:83f91d8a9bb404b8c2c41a707ac7f7f75b9442a0a876df295de27251a856ad09 \
+ --hash=sha256:87c6e35319b46b99e168eb98472d6c7d8634ee37750d7693656dc766395df096 \
+ --hash=sha256:8d23b88b9388ed85c6faf0e74d8dec4f4d3baf3ecf20a65a47b836d56260d4b9 \
+ --hash=sha256:9156c45750b37337f7b0b00e6248991a047be4aa44554c9886fe6bdd605aab3b \
+ --hash=sha256:91a0fa841646320ec0d3accdff5b757b06e2e5c86ba32af2e0815c96c7a603c5 \
+ --hash=sha256:95858ca14a9f6fa8413d29e0a585b31b278388aa775b8a81fa24830123874678 \
+ --hash=sha256:95df24ca1e1bd93bbca51d94dd049a984609687cb2fb08a7f2c56ac84e9816ea \
+ --hash=sha256:9b37c184f8b976f0c0a231a5f3d6efe10807d41ccbe4488df8c74174805eea7d \
+ --hash=sha256:9b6f347deb3dcfbfde1c20baa21c2ac0751afaa73e64e5b693bb2b848efeaa49 \
+ --hash=sha256:9d75baf00138f80b48f1eac72ad1535aac0b6461265a0bcad391fc5aba875cfc \
+ --hash=sha256:9ef8aa8bdbac47f4968a5d66462a2a0935d044bf35c0e5a8af152d58516dbeb5 \
+ --hash=sha256:a11e38ad8922c7961447f35c7b17bffa15de4d17c70abd07bfbe12d6faa3e027 \
+ --hash=sha256:a1b54689e38d1279a51d11e3467dd2f3a50f5f2e879012ce8f2d6943f00e83f0 \
+ --hash=sha256:a3b3366087c1bc0a2795111edcadddb8b3b59509d5db5d7ea3fdd69f954a8878 \
+ --hash=sha256:a569eb1b05d72f9bce2ebd28a1ce2054311b66677fcd46cf36204ad23acead8c \
+ --hash=sha256:a7affedeb43a70351bb811dadf49493c9cfd1ed94c9c70095fd177e9cc1541fa \
+ --hash=sha256:a9a396a6ad26130cdae92ae10c36af09d9bfe6cafe69670fd3b6da9b07b4044f \
+ --hash=sha256:a9ab1e71d3d2e54a0aa646ab6d4eebfaa5f416fe78dfe4da2839525dc5d765c6 \
+ --hash=sha256:a9cd1af7e18e5221d2878378fbc287a14cd527fdd5939ed56a18df8a31136bb2 \
+ --hash=sha256:a9dcaf8b0cc72a392760bb8755922c03e17a5a54e08cca58e8b74f6902b433cf \
+ --hash=sha256:b9d7439d7fab4dce00570bb906875734df13d9faa4b48e261c440a5fec6d9708 \
+ --hash=sha256:bcc03c8b72267e97b49149e4863d57c2d77f13fae12066622dc78fe322490fe6 \
+ --hash=sha256:c11d4d16e133f6df8916cc5b7e3e96ee4c44c936717d684a94f48f82edb7c92f \
+ --hash=sha256:c1dca61c6db1166c48b95198c0b7d9c990b30c756fc2923cc66f68d17dc558fd \
+ --hash=sha256:c518e84bb59c2baae725accd355c8dc517b4a3ed8db88b4bc93c78dae2974bf2 \
+ --hash=sha256:c7934fd0e920e70468e676fe7f1b7261c1efa0d6c037c6722278ca0228ad9d0d \
+ --hash=sha256:c7e72ce6bda6fb9409cc1e8164dd41d7c91466fb599eb047cfda72fe758a34a7 \
+ --hash=sha256:c90d6dec6be2c7d03378a574de87af9b1efea77d0c52a8301dd831ece938452f \
+ --hash=sha256:ceec59f59d092c5007e815def4ebb80c2de330e9588e101cf8bd94c143ec78a5 \
+ --hash=sha256:cf1781ef73c073e6b0f90af841aaf98501f975d306bbf6221683dd594ccc52b6 \
+ --hash=sha256:d04f13a1d75cb2b8382bdc16ae6fa58c97337253826dfe136195b7f89f661557 \
+ --hash=sha256:d6d300f8ec35c24025ceb9b9019ae9040c1ab2f01cddc2bcc0b518af31c75c14 \
+ --hash=sha256:d8dbb1bf0c0a4ae8b40bdc9be7f644e2f3fb4e8a9aca7145bfa510d4a374eeb7 \
+ --hash=sha256:de58647e3f9c42f13f90ac7e5f58900c80a39019848c5547bc691693098ae1bd \
+ --hash=sha256:deeb929efe52bed518f6eb2ddc00cc496366a14c726005726ad62c2dd9017a3c \
+ --hash=sha256:df01aea34b6e9e33572c35cd16bae5a47785e7d5c8cb2b54b2acdb9678315a17 \
+ --hash=sha256:e2620453c075abeb0daa949a292e19f56de518988e079c36478bacf9546ced23 \
+ --hash=sha256:e4450fc83a3df53dec45922b576e91e94f5578d06436871dce3a6be38e40f5db \
+ --hash=sha256:e54affdeb21026329fb0744ad187cf812f7d3c2aa702a5edb562b325191fcab6 \
+ --hash=sha256:e9875a0143f07d74dc5e1ded1c4581f0d9f7ab86c78994e2ed9e95050073c94d \
+ --hash=sha256:f1c3cf67185543730888b20682fb186fc8d0fa6f07ccc3ef4390831ab4b388d9 \
+ --hash=sha256:f48c749857f8fb598fb890a75f540e3221d0976ed0bf879cf3c7eef34151acee \
+ --hash=sha256:f779498eeec470295a2b1a5d97aa1bc9814ecd25e1eb637bd9d1c73a327387f6
+ # via aim
+werkzeug==3.0.4 \
+ --hash=sha256:02c9eb92b7d6c06f31a782811505d2157837cea66aaede3e217c7c27c039476c \
+ --hash=sha256:34f2371506b250df4d4f84bfe7b0921e4762525762bbd936614909fe25cd7306
+ # via
+ # flask
+ # tensorboard
+wheel==0.44.0 \
+ --hash=sha256:2376a90c98cc337d18623527a97c31797bd02bad0033d41547043a1cbfbe448f \
+ --hash=sha256:a29c3f2817e95ab89aa4660681ad547c0e9547f20e75b0562fe7723c9a2a9d49
+ # via astunparse
+wrapt==1.16.0 \
+ --hash=sha256:0d2691979e93d06a95a26257adb7bfd0c93818e89b1406f5a28f36e0d8c1e1fc \
+ --hash=sha256:14d7dc606219cdd7405133c713f2c218d4252f2a469003f8c46bb92d5d095d81 \
+ --hash=sha256:1a5db485fe2de4403f13fafdc231b0dbae5eca4359232d2efc79025527375b09 \
+ --hash=sha256:1acd723ee2a8826f3d53910255643e33673e1d11db84ce5880675954183ec47e \
+ --hash=sha256:1ca9b6085e4f866bd584fb135a041bfc32cab916e69f714a7d1d397f8c4891ca \
+ --hash=sha256:1dd50a2696ff89f57bd8847647a1c363b687d3d796dc30d4dd4a9d1689a706f0 \
+ --hash=sha256:2076fad65c6736184e77d7d4729b63a6d1ae0b70da4868adeec40989858eb3fb \
+ --hash=sha256:2a88e6010048489cda82b1326889ec075a8c856c2e6a256072b28eaee3ccf487 \
+ --hash=sha256:3ebf019be5c09d400cf7b024aa52b1f3aeebeff51550d007e92c3c1c4afc2a40 \
+ --hash=sha256:418abb18146475c310d7a6dc71143d6f7adec5b004ac9ce08dc7a34e2babdc5c \
+ --hash=sha256:43aa59eadec7890d9958748db829df269f0368521ba6dc68cc172d5d03ed8060 \
+ --hash=sha256:44a2754372e32ab315734c6c73b24351d06e77ffff6ae27d2ecf14cf3d229202 \
+ --hash=sha256:490b0ee15c1a55be9c1bd8609b8cecd60e325f0575fc98f50058eae366e01f41 \
+ --hash=sha256:49aac49dc4782cb04f58986e81ea0b4768e4ff197b57324dcbd7699c5dfb40b9 \
+ --hash=sha256:5eb404d89131ec9b4f748fa5cfb5346802e5ee8836f57d516576e61f304f3b7b \
+ --hash=sha256:5f15814a33e42b04e3de432e573aa557f9f0f56458745c2074952f564c50e664 \
+ --hash=sha256:5f370f952971e7d17c7d1ead40e49f32345a7f7a5373571ef44d800d06b1899d \
+ --hash=sha256:66027d667efe95cc4fa945af59f92c5a02c6f5bb6012bff9e60542c74c75c362 \
+ --hash=sha256:66dfbaa7cfa3eb707bbfcd46dab2bc6207b005cbc9caa2199bcbc81d95071a00 \
+ --hash=sha256:685f568fa5e627e93f3b52fda002c7ed2fa1800b50ce51f6ed1d572d8ab3e7fc \
+ --hash=sha256:6906c4100a8fcbf2fa735f6059214bb13b97f75b1a61777fcf6432121ef12ef1 \
+ --hash=sha256:6a42cd0cfa8ffc1915aef79cb4284f6383d8a3e9dcca70c445dcfdd639d51267 \
+ --hash=sha256:6dcfcffe73710be01d90cae08c3e548d90932d37b39ef83969ae135d36ef3956 \
+ --hash=sha256:6f6eac2360f2d543cc875a0e5efd413b6cbd483cb3ad7ebf888884a6e0d2e966 \
+ --hash=sha256:72554a23c78a8e7aa02abbd699d129eead8b147a23c56e08d08dfc29cfdddca1 \
+ --hash=sha256:73870c364c11f03ed072dda68ff7aea6d2a3a5c3fe250d917a429c7432e15228 \
+ --hash=sha256:73aa7d98215d39b8455f103de64391cb79dfcad601701a3aa0dddacf74911d72 \
+ --hash=sha256:75ea7d0ee2a15733684badb16de6794894ed9c55aa5e9903260922f0482e687d \
+ --hash=sha256:7bd2d7ff69a2cac767fbf7a2b206add2e9a210e57947dd7ce03e25d03d2de292 \
+ --hash=sha256:807cc8543a477ab7422f1120a217054f958a66ef7314f76dd9e77d3f02cdccd0 \
+ --hash=sha256:8e9723528b9f787dc59168369e42ae1c3b0d3fadb2f1a71de14531d321ee05b0 \
+ --hash=sha256:9090c9e676d5236a6948330e83cb89969f433b1943a558968f659ead07cb3b36 \
+ --hash=sha256:9153ed35fc5e4fa3b2fe97bddaa7cbec0ed22412b85bcdaf54aeba92ea37428c \
+ --hash=sha256:9159485323798c8dc530a224bd3ffcf76659319ccc7bbd52e01e73bd0241a0c5 \
+ --hash=sha256:941988b89b4fd6b41c3f0bfb20e92bd23746579736b7343283297c4c8cbae68f \
+ --hash=sha256:94265b00870aa407bd0cbcfd536f17ecde43b94fb8d228560a1e9d3041462d73 \
+ --hash=sha256:98b5e1f498a8ca1858a1cdbffb023bfd954da4e3fa2c0cb5853d40014557248b \
+ --hash=sha256:9b201ae332c3637a42f02d1045e1d0cccfdc41f1f2f801dafbaa7e9b4797bfc2 \
+ --hash=sha256:a0ea261ce52b5952bf669684a251a66df239ec6d441ccb59ec7afa882265d593 \
+ --hash=sha256:a33a747400b94b6d6b8a165e4480264a64a78c8a4c734b62136062e9a248dd39 \
+ --hash=sha256:a452f9ca3e3267cd4d0fcf2edd0d035b1934ac2bd7e0e57ac91ad6b95c0c6389 \
+ --hash=sha256:a86373cf37cd7764f2201b76496aba58a52e76dedfaa698ef9e9688bfd9e41cf \
+ --hash=sha256:ac83a914ebaf589b69f7d0a1277602ff494e21f4c2f743313414378f8f50a4cf \
+ --hash=sha256:aefbc4cb0a54f91af643660a0a150ce2c090d3652cf4052a5397fb2de549cd89 \
+ --hash=sha256:b3646eefa23daeba62643a58aac816945cadc0afaf21800a1421eeba5f6cfb9c \
+ --hash=sha256:b47cfad9e9bbbed2339081f4e346c93ecd7ab504299403320bf85f7f85c7d46c \
+ --hash=sha256:b935ae30c6e7400022b50f8d359c03ed233d45b725cfdd299462f41ee5ffba6f \
+ --hash=sha256:bb2dee3874a500de01c93d5c71415fcaef1d858370d405824783e7a8ef5db440 \
+ --hash=sha256:bc57efac2da352a51cc4658878a68d2b1b67dbe9d33c36cb826ca449d80a8465 \
+ --hash=sha256:bf5703fdeb350e36885f2875d853ce13172ae281c56e509f4e6eca049bdfb136 \
+ --hash=sha256:c31f72b1b6624c9d863fc095da460802f43a7c6868c5dda140f51da24fd47d7b \
+ --hash=sha256:c5cd603b575ebceca7da5a3a251e69561bec509e0b46e4993e1cac402b7247b8 \
+ --hash=sha256:d2efee35b4b0a347e0d99d28e884dfd82797852d62fcd7ebdeee26f3ceb72cf3 \
+ --hash=sha256:d462f28826f4657968ae51d2181a074dfe03c200d6131690b7d65d55b0f360f8 \
+ --hash=sha256:d5e49454f19ef621089e204f862388d29e6e8d8b162efce05208913dde5b9ad6 \
+ --hash=sha256:da4813f751142436b075ed7aa012a8778aa43a99f7b36afe9b742d3ed8bdc95e \
+ --hash=sha256:db2e408d983b0e61e238cf579c09ef7020560441906ca990fe8412153e3b291f \
+ --hash=sha256:db98ad84a55eb09b3c32a96c576476777e87c520a34e2519d3e59c44710c002c \
+ --hash=sha256:dbed418ba5c3dce92619656802cc5355cb679e58d0d89b50f116e4a9d5a9603e \
+ --hash=sha256:dcdba5c86e368442528f7060039eda390cc4091bfd1dca41e8046af7c910dda8 \
+ --hash=sha256:decbfa2f618fa8ed81c95ee18a387ff973143c656ef800c9f24fb7e9c16054e2 \
+ --hash=sha256:e4fdb9275308292e880dcbeb12546df7f3e0f96c6b41197e0cf37d2826359020 \
+ --hash=sha256:eb1b046be06b0fce7249f1d025cd359b4b80fc1c3e24ad9eca33e0dcdb2e4a35 \
+ --hash=sha256:eb6e651000a19c96f452c85132811d25e9264d836951022d6e81df2fff38337d \
+ --hash=sha256:ed867c42c268f876097248e05b6117a65bcd1e63b779e916fe2e33cd6fd0d3c3 \
+ --hash=sha256:edfad1d29c73f9b863ebe7082ae9321374ccb10879eeabc84ba3b69f2579d537 \
+ --hash=sha256:f2058f813d4f2b5e3a9eb2eb3faf8f1d99b81c3e51aeda4b168406443e8ba809 \
+ --hash=sha256:f6b2d0c6703c988d334f297aa5df18c45e97b0af3679bb75059e0e0bd8b1069d \
+ --hash=sha256:f8212564d49c50eb4565e502814f694e240c55551a5f1bc841d4fcaabb0a9b8a \
+ --hash=sha256:ffa565331890b90056c01db69c0fe634a776f8019c143a5ae265f9c6bc4bd6d4
+ # via
+ # clu
+ # tensorflow
+ # tensorflow-datasets
+xyzservices==2024.9.0 \
+ --hash=sha256:68fb8353c9dbba4f1ff6c0f2e5e4e596bb9e1db7f94f4f7dfbcb26e25aa66fde \
+ --hash=sha256:776ae82b78d6e5ca63dd6a94abb054df8130887a4a308473b54a6bd364de8644
# via bokeh
-yapf==0.32.0 \
- --hash=sha256:8fea849025584e486fd06d6ba2bed717f396080fd3cc236ba10cb97c4c51cf32 \
- --hash=sha256:a3f5085d37ef7e3e004c4ba9f9b3e40c54ff1901cd111f05145ae313a7c67d1b
+yapf==0.40.2 \
+ --hash=sha256:4dab8a5ed7134e26d57c1647c7483afb3f136878b579062b786c9ba16b94637b \
+ --hash=sha256:adc8b5dd02c0143108878c499284205adb258aad6db6634e5b869e7ee2bd548b
# via -r tools/python/requirements.txt
-zipp==3.11.0 \
- --hash=sha256:83a28fcb75844b5c0cdaf5aa4003c2d728c77e05f5aeabe8e95e56727005fbaa \
- --hash=sha256:a7a22e05929290a67401440b39690ae6563279bced5f314609d9d03798f56766
- # via importlib-metadata
+zipp==3.20.1 \
+ --hash=sha256:9960cd8967c8f85a56f920d5d507274e74f9ff813a0ab8889a5b5be2daf44064 \
+ --hash=sha256:c22b14cc4763c5a5b04134207736c107db42e9d3ef2d9779d465f5f1bcba572b
+ # via
+ # etils
+ # importlib-metadata
+ # importlib-resources
+
+# The following packages are considered to be unsafe in a requirements file:
+setuptools==74.0.0 \
+ --hash=sha256:0274581a0037b638b9fc1c6883cc71c0210865aaa76073f7882376b641b84e8f \
+ --hash=sha256:a85e96b8be2b906f3e3e789adec6a9323abf79758ecfa3065bd740d81158b11e
+ # via
+ # -r tools/python/requirements.txt
+ # tensorboard
+ # tensorflow
diff --git a/tools/python/requirements.txt b/tools/python/requirements.txt
index 09121c8..342d8ab 100644
--- a/tools/python/requirements.txt
+++ b/tools/python/requirements.txt
@@ -8,7 +8,7 @@
opencv-python
osqp
pkginfo
-pygobject
+pygobject==3.42.2
requests
scipy
shapely
@@ -25,6 +25,28 @@
bokeh
tabulate
+flask
+
casadi>=3.6.6
+# ML libraries
jax[cuda12]
+jaxtyping
+optax
+flax
+clu
+
+# Pin this so we can actually depend on it. Used by tensorflow/jax.
+setuptools==74.0.0
+
+tensorflow
+tensorflow_datasets
+tensorflow_probability
+tf_keras
+
+# Experience buffer for reinforcement learning
+flashbax
+
+# Experiment tracking
+aim
+plotly
diff --git a/tools/python/runtime_binary.sh b/tools/python/runtime_binary.sh
index 8498408..95283e0 100755
--- a/tools/python/runtime_binary.sh
+++ b/tools/python/runtime_binary.sh
@@ -27,6 +27,9 @@
LD_LIBRARY_PATH+=":${path}/../gtk_runtime/lib/x86_64-linux-gnu"
LD_LIBRARY_PATH+=":${path}/../gtk_runtime/usr/lib/x86_64-linux-gnu"
LD_LIBRARY_PATH+=":${path}/../gtk_runtime/usr/lib"
+ if [[ -e "${path}/../pip_deps_nvidia_nccl_cu12" ]]; then
+ LD_LIBRARY_PATH+=":${path}/../pip_deps_nvidia_nccl_cu12/site-packages/nvidia/nccl/lib/"
+ fi
export LD_LIBRARY_PATH
break
fi
diff --git a/tools/python/update_helper_files/Dockerfile b/tools/python/update_helper_files/Dockerfile
index 3a4d42c..551674e 100644
--- a/tools/python/update_helper_files/Dockerfile
+++ b/tools/python/update_helper_files/Dockerfile
@@ -8,3 +8,4 @@
RUN DEBIAN_FRONTEND=noninteractive apt install --no-install-recommends -y python3
RUN DEBIAN_FRONTEND=noninteractive apt install --no-install-recommends -y pkgconf
RUN DEBIAN_FRONTEND=noninteractive apt install --no-install-recommends -y libcairo2-dev
+RUN DEBIAN_FRONTEND=noninteractive apt install --no-install-recommends -y libgirepository1.0-dev
diff --git a/tools/python/whl_overrides.json b/tools/python/whl_overrides.json
index 5dd81b7..c27c8ac 100644
--- a/tools/python/whl_overrides.json
+++ b/tools/python/whl_overrides.json
@@ -3,37 +3,169 @@
"sha256": "526a04eadab8b4ee719ce68f204172ead1027549089702d99b9059f129ff1308",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/absl_py-2.1.0-py3-none-any.whl"
},
- "bokeh==3.4.1": {
- "sha256": "1e3c502a0a8205338fc74dadbfa321f8a0965441b39501e36796a47b4017b642",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/bokeh-3.4.1-py3-none-any.whl"
+ "aim==3.24.0": {
+ "sha256": "1789bcc9edf69ae90bb18a6f3fa4862095b8020eadc7e5e0e93ba4f242250947",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/aim-3.24.0-cp39-cp39-manylinux_2_28_x86_64.whl"
+ },
+ "aim_ui==3.24.0": {
+ "sha256": "b62fbcb0ea4b036b99985d4c649220cdbe4523f05408dcb2324ffc7e4539f321",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/aim_ui-3.24.0-py3-none-any.whl"
+ },
+ "aimrecords==0.0.7": {
+ "sha256": "b9276890891c5fd68f817e20fc5d466a80c01e22fa468eaa979331448a75d601",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/aimrecords-0.0.7-py2.py3-none-any.whl"
+ },
+ "aimrocks==0.5.2": {
+ "sha256": "e6a79076d669dbf221442399da893baff6c1549031edbb5d556042d1b9b6525c",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/aimrocks-0.5.2-cp39-cp39-manylinux_2_24_x86_64.whl"
+ },
+ "aiofiles==24.1.0": {
+ "sha256": "b4ec55f4195e3eb5d7abd1bf7e061763e864dd4954231fb8539a0ef8bb8260e5",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/aiofiles-24.1.0-py3-none-any.whl"
+ },
+ "alembic==1.13.3": {
+ "sha256": "908e905976d15235fae59c9ac42c4c5b75cfcefe3d27c0fbf7ae15a37715d80e",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/alembic-1.13.3-py3-none-any.whl"
+ },
+ "annotated_types==0.7.0": {
+ "sha256": "1f02e8b43a8fbbc3f3e0d4f0f4bfc8131bcb4eebe8849b8e5c773f3a1c582a53",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/annotated_types-0.7.0-py3-none-any.whl"
+ },
+ "anyio==4.6.0": {
+ "sha256": "c7d2e9d63e31599eeb636c8c5c03a7e108d73b345f064f1c19fdc87b79036a9a",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/anyio-4.6.0-py3-none-any.whl"
+ },
+ "array_record==0.5.1": {
+ "sha256": "9922862216a9d3be76fdc27968af1ec0ea20f986329998ba45b0f01ee3e646fa",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/array_record-0.5.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "astunparse==1.6.3": {
+ "sha256": "c2652417f2c8b5bb325c885ae329bdf3f86424075c4fd1a128674bc6fba4b8e8",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/astunparse-1.6.3-py2.py3-none-any.whl"
+ },
+ "base58==2.0.1": {
+ "sha256": "447adc750d6b642987ffc6d397ecd15a799852d5f6a1d308d384500243825058",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/base58-2.0.1-py3-none-any.whl"
+ },
+ "blinker==1.8.2": {
+ "sha256": "1779309f71bf239144b9399d06ae925637cf6634cf6bd131104184531bf67c01",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/blinker-1.8.2-py3-none-any.whl"
+ },
+ "bokeh==3.4.3": {
+ "sha256": "c6f33817f866fc67fbeb5df79cd13a8bb592c05c591f3fd7f4f22b824f7afa01",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/bokeh-3.4.3-py3-none-any.whl"
+ },
+ "boto3==1.35.27": {
+ "sha256": "3da139ca038032e92086e26d23833b557f0c257520162bfd3d6f580bf8032c86",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/boto3-1.35.27-py3-none-any.whl"
+ },
+ "botocore==1.35.27": {
+ "sha256": "c299c70b5330a8634e032883ce8a72c2c6d9fdbc985d8191199cb86b92e7cbbd",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/botocore-1.35.27-py3-none-any.whl"
+ },
+ "cachetools==5.5.0": {
+ "sha256": "02134e8439cdc2ffb62023ce1debca2944c3f289d66bb17ead3ab3dede74b292",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/cachetools-5.5.0-py3-none-any.whl"
},
"casadi==3.6.6": {
"sha256": "cc3594b348f306018b142638d0a8c4026f80e996b4e9798fc504899256a7b029",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/casadi-3.6.6-cp39-none-manylinux2014_x86_64.whl"
},
- "certifi==2022.9.24": {
- "sha256": "90c1a32f1d68f940488354e36370f6cca89f0f106db09518524c88d6ed83f382",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/certifi-2022.9.24-py3-none-any.whl"
+ "certifi==2024.8.30": {
+ "sha256": "922820b53db7a7257ffbda3f597266d435245903d80737e34f8a45ff3e3230d8",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/certifi-2024.8.30-py3-none-any.whl"
},
- "charset_normalizer==2.1.1": {
- "sha256": "83e9a75d1911279afd89352c68b45348559d1fc0506b054b346651b5e7fee29f",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/charset_normalizer-2.1.1-py3-none-any.whl"
+ "cffi==1.17.1": {
+ "sha256": "cdf5ce3acdfd1661132f2a9c19cac174758dc2352bfe37d98aa7512c6b7178b3",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/cffi-1.17.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
},
- "click==8.1.3": {
- "sha256": "bb4d8133cb15a609f44e8213d9b391b0809795062913b383c62be0ee95b1db48",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/click-8.1.3-py3-none-any.whl"
+ "charset_normalizer==3.3.2": {
+ "sha256": "b261ccdec7821281dade748d088bb6e9b69e6d15b30652b74cbbac25e280b796",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/charset_normalizer-3.3.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
},
- "contourpy==1.2.1": {
- "sha256": "e1d59258c3c67c865435d8fbeb35f8c59b8bef3d6f46c1f29f6123556af28445",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/contourpy-1.2.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ "chex==0.1.86": {
+ "sha256": "251c20821092323a3d9c28e1cf80e4a58180978bec368f531949bd9847eee568",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/chex-0.1.86-py3-none-any.whl"
},
- "cycler==0.11.0": {
- "sha256": "3a27e95f763a428a739d2add979fa7494c912a32c17c4c38c4d5f082cad165a3",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/cycler-0.11.0-py3-none-any.whl"
+ "click==8.1.7": {
+ "sha256": "ae74fb96c20a0277a1d615f1e4d73c8414f5a98db8b799a7931d1582f3390c28",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/click-8.1.7-py3-none-any.whl"
},
- "fonttools==4.38.0": {
- "sha256": "820466f43c8be8c3009aef8b87e785014133508f0de64ec469e4efb643ae54fb",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/fonttools-4.38.0-py3-none-any.whl"
+ "cloudpickle==3.1.0": {
+ "sha256": "fe11acda67f61aaaec473e3afe030feb131d78a43461b718185363384f1ba12e",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/cloudpickle-3.1.0-py3-none-any.whl"
+ },
+ "clu==0.0.12": {
+ "sha256": "0d183e7d25f7dd0700444510a264e24700e2f068bdabd199ed22866f7e54edba",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/clu-0.0.12-py3-none-any.whl"
+ },
+ "contextlib2==21.6.0": {
+ "sha256": "3fbdb64466afd23abaf6c977627b75b6139a5a3e8ce38405c5b413aed7a0471f",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/contextlib2-21.6.0-py2.py3-none-any.whl"
+ },
+ "contourpy==1.3.0": {
+ "sha256": "68a32389b06b82c2fdd68276148d7b9275b5f5cf13e5417e4252f6d1a34f72a2",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/contourpy-1.3.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "cryptography==43.0.1": {
+ "sha256": "511f4273808ab590912a93ddb4e3914dfd8a388fed883361b02dea3791f292e1",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/cryptography-43.0.1-cp39-abi3-manylinux_2_28_x86_64.whl"
+ },
+ "cycler==0.12.1": {
+ "sha256": "85cef7cff222d8644161529808465972e51340599459b8ac3ccbac5a854e0d30",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/cycler-0.12.1-py3-none-any.whl"
+ },
+ "decorator==5.1.1": {
+ "sha256": "b8c3f85900b9dc423225913c5aace94729fe1fa9763b38939a95226f02d37186",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/decorator-5.1.1-py3-none-any.whl"
+ },
+ "dm_tree==0.1.8": {
+ "sha256": "181c35521d480d0365f39300542cb6cd7fd2b77351bb43d7acfda15aef63b317",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/dm_tree-0.1.8-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "etils==1.5.2": {
+ "sha256": "6dc882d355e1e98a5d1a148d6323679dc47c9a5792939b9de72615aa4737eb0b",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/etils-1.5.2-py3-none-any.whl"
+ },
+ "exceptiongroup==1.2.2": {
+ "sha256": "3111b9d131c238bec2f8f516e123e14ba243563fb135d3fe885990585aa7795b",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/exceptiongroup-1.2.2-py3-none-any.whl"
+ },
+ "fastapi==0.115.0": {
+ "sha256": "17ea427674467486e997206a5ab25760f6b09e069f099b96f5b55a32fb6f1631",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/fastapi-0.115.0-py3-none-any.whl"
+ },
+ "filelock==3.16.1": {
+ "sha256": "2082e5703d51fbf98ea75855d9d5527e33d8ff23099bec374a134febee6946b0",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/filelock-3.16.1-py3-none-any.whl"
+ },
+ "flashbax==0.1.2": {
+ "sha256": "ac50b2580808ce63787da0ae240db14986e3404ade98a33335e6d7a5efe84859",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/flashbax-0.1.2-py3-none-any.whl"
+ },
+ "flask==3.0.3": {
+ "sha256": "34e815dfaa43340d1d15a5c3a02b8476004037eb4840b34910c6e21679d288f3",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/flask-3.0.3-py3-none-any.whl"
+ },
+ "flatbuffers==24.3.25": {
+ "sha256": "8dbdec58f935f3765e4f7f3cf635ac3a77f83568138d6a2311f524ec96364812",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/flatbuffers-24.3.25-py2.py3-none-any.whl"
+ },
+ "flax==0.8.5": {
+ "sha256": "c96e46d1c48a300d010ebf5c4846f163bdd7acc6efff5ff2bfb1cb5b08aa65d8",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/flax-0.8.5-py3-none-any.whl"
+ },
+ "fonttools==4.53.1": {
+ "sha256": "84ec3fb43befb54be490147b4a922b5314e16372a643004f182babee9f9c3407",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/fonttools-4.53.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "fsspec==2024.6.1": {
+ "sha256": "3cb443f8bcd2efb31295a5b9fdb02aee81d8452c80d28f97a6d0959e6cee101e",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/fsspec-2024.6.1-py3-none-any.whl"
+ },
+ "gast==0.6.0": {
+ "sha256": "52b182313f7330389f72b069ba00f174cfe2a06411099547288839c6cbafbd54",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/gast-0.6.0-py3-none-any.whl"
},
"ghp_import==2.1.0": {
"sha256": "8337dd7b50877f163d4c0289bc1f1c7f127550241988d568c1db512c4324a619",
@@ -43,13 +175,45 @@
"sha256": "88cee83dea8bddf73db7edbf5bd697237628389ef476c0a0ecad639c606189e5",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/glog-0.3.1-py2.py3-none-any.whl"
},
- "idna==3.4": {
- "sha256": "90b77e79eaa3eba6de819a0c442c0b4ceefc341a7a2ab77d7562bf49f425c5c2",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/idna-3.4-py3-none-any.whl"
+ "google_pasta==0.2.0": {
+ "sha256": "b32482794a366b5366a32c92a9a9201b107821889935a02b3e51f6b432ea84ed",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/google_pasta-0.2.0-py3-none-any.whl"
},
- "importlib_metadata==5.1.0": {
- "sha256": "d84d17e21670ec07990e1044a99efe8d615d860fd176fc29ef5c306068fda313",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/importlib_metadata-5.1.0-py3-none-any.whl"
+ "greenlet==3.1.1": {
+ "sha256": "63e4844797b975b9af3a3fb8f7866ff08775f5426925e1e0bbcfe7932059a12c",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/greenlet-3.1.1-cp39-cp39-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl"
+ },
+ "grpcio==1.66.1": {
+ "sha256": "48b0d92d45ce3be2084b92fb5bae2f64c208fea8ceed7fccf6a7b524d3c4942e",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/grpcio-1.66.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "h11==0.14.0": {
+ "sha256": "e3fe4ac4b851c468cc8363d500db52c2ead036020723024a109d37346efaa761",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/h11-0.14.0-py3-none-any.whl"
+ },
+ "h5py==3.11.0": {
+ "sha256": "67462d0669f8f5459529de179f7771bd697389fcb3faab54d63bf788599a48ea",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/h5py-3.11.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "humanize==4.10.0": {
+ "sha256": "39e7ccb96923e732b5c2e27aeaa3b10a8dfeeba3eb965ba7b74a3eb0e30040a6",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/humanize-4.10.0-py3-none-any.whl"
+ },
+ "idna==3.8": {
+ "sha256": "050b4e5baadcd44d760cedbd2b8e639f2ff89bbc7a5730fcc662954303377aac",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/idna-3.8-py3-none-any.whl"
+ },
+ "importlib_metadata==8.4.0": {
+ "sha256": "66f342cc6ac9818fc6ff340576acd24d65ba0b3efabb2b4ac08b598965a4a2f1",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/importlib_metadata-8.4.0-py3-none-any.whl"
+ },
+ "importlib_resources==6.4.4": {
+ "sha256": "dda242603d1c9cd836c3368b1174ed74cb4049ecd209e7a1a0104620c18c5c11",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/importlib_resources-6.4.4-py3-none-any.whl"
+ },
+ "itsdangerous==2.2.0": {
+ "sha256": "c6242fc49e35958c8b15141343aa660db5fc54d4f13a1db01a3f5891b98700ef",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/itsdangerous-2.2.0-py3-none-any.whl"
},
"jax==0.4.30": {
"sha256": "289b30ae03b52f7f4baf6ef082a9f4e3e29c1080e22d13512c5ecf02d5f1a55b",
@@ -67,33 +231,69 @@
"sha256": "f74a6b0e09df4b5e2ee399ebb9f0e01190e26e84ccb0a758fadb516415c07f18",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/jaxlib-0.4.30-cp39-cp39-manylinux2014_x86_64.whl"
},
- "jinja2==3.1.2": {
- "sha256": "6088930bfe239f0e6710546ab9c19c9ef35e29792895fed6e6e31a023a182a61",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/Jinja2-3.1.2-py3-none-any.whl"
+ "jaxtyping==0.2.34": {
+ "sha256": "2f81fb6d1586e497a6ea2d28c06dcab37b108a096cbb36ea3fe4fa2e1c1f32e5",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/jaxtyping-0.2.34-py3-none-any.whl"
},
- "kiwisolver==1.4.4": {
- "sha256": "7c43e1e1206cd421cd92e6b3280d4385d41d7166b3ed577ac20444b6995a445f",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/kiwisolver-1.4.4-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl"
+ "jinja2==3.1.4": {
+ "sha256": "bc5dd2abb727a5319567b7a813e6a2e7318c39f4f487cfe6c89c6f9c7d25197d",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/jinja2-3.1.4-py3-none-any.whl"
},
- "markdown==3.3.7": {
- "sha256": "f5da449a6e1c989a4cea2631aa8ee67caa5a2ef855d551c88f9e309f4634c621",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/Markdown-3.3.7-py3-none-any.whl"
+ "jmespath==1.0.1": {
+ "sha256": "02e2e4cc71b5bcab88332eebf907519190dd9e6e82107fa7f83b1003a6252980",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/jmespath-1.0.1-py3-none-any.whl"
},
- "markupsafe==2.1.1": {
- "sha256": "56442863ed2b06d19c37f94d999035e15ee982988920e12a5b4ba29b62ad1f77",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/MarkupSafe-2.1.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ "keras==3.5.0": {
+ "sha256": "d37a3c623935713473ceb25241b52bce9d1e0ff5b36e5d0f6f47ed55f8500c9a",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/keras-3.5.0-py3-none-any.whl"
},
- "matplotlib==3.6.2": {
- "sha256": "795ad83940732b45d39b82571f87af0081c120feff2b12e748d96bb191169e33",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/matplotlib-3.6.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ "kiwisolver==1.4.6": {
+ "sha256": "872c1323f29f0822000e47acac9a0b6ed2af843a20b27c85fa0fdc906f98140f",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/kiwisolver-1.4.6-cp39-cp39-manylinux_2_12_x86_64.manylinux2010_x86_64.whl"
+ },
+ "libclang==18.1.1": {
+ "sha256": "c533091d8a3bbf7460a00cb6c1a71da93bffe148f172c7d03b1c31fbf8aa2a0b",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/libclang-18.1.1-py2.py3-none-manylinux2010_x86_64.whl"
+ },
+ "mako==1.3.5": {
+ "sha256": "260f1dbc3a519453a9c856dedfe4beb4e50bd5a26d96386cb6c80856556bb91a",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/Mako-1.3.5-py3-none-any.whl"
+ },
+ "markdown==3.7": {
+ "sha256": "7eb6df5690b81a1d7942992c97fad2938e956e79df20cbc6186e9c3a77b1c803",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/Markdown-3.7-py3-none-any.whl"
+ },
+ "markdown_it_py==3.0.0": {
+ "sha256": "355216845c60bd96232cd8d8c40e8f9765cc86f46880e43a8fd22dc1a1a8cab1",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/markdown_it_py-3.0.0-py3-none-any.whl"
+ },
+ "markupsafe==2.1.5": {
+ "sha256": "17b950fccb810b3293638215058e432159d2b71005c74371d784862b7e4683f3",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/MarkupSafe-2.1.5-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "matplotlib==3.9.2": {
+ "sha256": "1cd93b91ab47a3616b4d3c42b52f8363b88ca021e340804c6ab2536344fad9ca",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/matplotlib-3.9.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "mdurl==0.1.2": {
+ "sha256": "84008a41e51615a49fc9966191ff91509e3c40b939176e643fd50a5c2196b8f8",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/mdurl-0.1.2-py3-none-any.whl"
},
"mergedeep==1.3.4": {
"sha256": "70775750742b25c0d8f36c55aed03d24c3384d17c951b3175d898bd778ef0307",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/mergedeep-1.3.4-py3-none-any.whl"
},
- "mkdocs==1.4.2": {
- "sha256": "c8856a832c1e56702577023cd64cc5f84948280c1c0fcc6af4cd39006ea6aa8c",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/mkdocs-1.4.2-py3-none-any.whl"
+ "mkdocs==1.6.1": {
+ "sha256": "db91759624d1647f3f34aa0c3f327dd2601beae39a366d6e064c03468d35c20e",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/mkdocs-1.6.1-py3-none-any.whl"
+ },
+ "mkdocs_get_deps==0.2.0": {
+ "sha256": "2bf11d0b133e77a0dd036abeeb06dec8775e46efa526dc70667d8863eefc6134",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/mkdocs_get_deps-0.2.0-py3-none-any.whl"
+ },
+ "ml_collections==0.1.1": {
+ "sha256": "557fa6c3f35b8b99a7395fa3b3d3409f939d6a0e50af1439a5becbf1cbfce3a6",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/ml_collections-0.1.1-py3-none-any.whl"
},
"ml_dtypes==0.4.0": {
"sha256": "f1724ddcdf5edbaf615a62110af47407f1719b8d02e68ccee60683acb5f74da1",
@@ -103,9 +303,21 @@
"sha256": "a0b2b9fe80bbcd81a6647ff13108738cfb482d481d826cc0e02f5b35e5c88d2c",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/mpmath-1.3.0-py3-none-any.whl"
},
- "numpy==1.25.2": {
- "sha256": "d7806500e4f5bdd04095e849265e55de20d8cc4b661b038957354327f6d9b295",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/numpy-1.25.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ "msgpack==1.0.8": {
+ "sha256": "5dbf059fb4b7c240c873c1245ee112505be27497e90f7c6591261c7d3c3a8228",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/msgpack-1.0.8-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "namex==0.0.8": {
+ "sha256": "7ddb6c2bb0e753a311b7590f84f6da659dd0c05e65cb89d519d54c0a250c0487",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/namex-0.0.8-py3-none-any.whl"
+ },
+ "nest_asyncio==1.6.0": {
+ "sha256": "87af6efd6b5e897c81050477ef65c62e2b2f35d51703cae01aff2905b1852e1c",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/nest_asyncio-1.6.0-py3-none-any.whl"
+ },
+ "numpy==1.26.4": {
+ "sha256": "f870204a840a60da0b12273ef34f7051e98c3b5961b61b0c2c1be6dfd64fbcd3",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/numpy-1.26.4-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
},
"nvidia_cublas_cu12==12.6.1.4": {
"sha256": "5dd125ece5469dbdceebe2e9536ad8fc4abd38aa394a7ace42fc8a930a1e81e3",
@@ -147,49 +359,101 @@
"sha256": "125a6c2a44e96386dda634e13d944e60b07a0402d391a070e8fb4104b34ea1ab",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/nvidia_nvjitlink_cu12-12.6.68-py3-none-manylinux2014_x86_64.whl"
},
- "opencv_python==4.6.0.66": {
- "sha256": "dbdc84a9b4ea2cbae33861652d25093944b9959279200b7ae0badd32439f74de",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/opencv_python-4.6.0.66-cp36-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ "opencv_python==4.10.0.84": {
+ "sha256": "9ace140fc6d647fbe1c692bcb2abce768973491222c067c131d80957c595b71f",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/opencv_python-4.10.0.84-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
},
"opt_einsum==3.3.0": {
"sha256": "2455e59e3947d3c275477df7f5205b30635e266fe6dc300e3d9f9646bfcea147",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/opt_einsum-3.3.0-py3-none-any.whl"
},
- "osqp==0.6.2.post8": {
- "sha256": "22724b3ac4eaf17582e3ff35cb6660c026e71138f27fc21dbae4f1dc60904c64",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/osqp-0.6.2.post8-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ "optax==0.2.3": {
+ "sha256": "083e603dcd731d7e74d99f71c12f77937dd53f79001b4c09c290e4f47dd2e94f",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/optax-0.2.3-py3-none-any.whl"
},
- "packaging==21.3": {
- "sha256": "ef103e05f519cdc783ae24ea4e2e0f508a9c99b2d4969652eed6a2e1ea5bd522",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/packaging-21.3-py3-none-any.whl"
+ "optree==0.12.1": {
+ "sha256": "27ae426745931ae1c2ccd7a78b27f9b7402167e0600fa62e2ef1cd58727e7b94",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/optree-0.12.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "orbax_checkpoint==0.6.1": {
+ "sha256": "f7fcb1ef528cee294ea244e769eaee17de2379c68a00d6df4c3a463e5cf716a1",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/orbax_checkpoint-0.6.1-py3-none-any.whl"
+ },
+ "osqp==0.6.7.post1": {
+ "sha256": "8e153385dad35e0e5b28a3ef593ec65d28eb180b3f65711b35b9113ebba6ef7c",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/osqp-0.6.7.post1-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "packaging==24.1": {
+ "sha256": "5b8f2217dbdbd2f7f384c41c628544e6d52f2d0f53c6d0c3ea61aa5d1d7ff124",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/packaging-24.1-py3-none-any.whl"
},
"pandas==2.2.2": {
"sha256": "66b479b0bd07204e37583c191535505410daa8df638fd8e75ae1b383851fe921",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pandas-2.2.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
},
- "pillow==9.3.0": {
- "sha256": "97aabc5c50312afa5e0a2b07c17d4ac5e865b250986f8afe2b02d772567a380c",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/Pillow-9.3.0-cp39-cp39-manylinux_2_28_x86_64.whl"
+ "pathspec==0.12.1": {
+ "sha256": "a0d503e138a4c123b27490a4f7beda6a01c6f288df0e4a8b79c7eb0dc7b4cc08",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pathspec-0.12.1-py3-none-any.whl"
+ },
+ "pillow==10.4.0": {
+ "sha256": "b2724fdb354a868ddf9a880cb84d102da914e99119211ef7ecbdc613b8c96b3c",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pillow-10.4.0-cp39-cp39-manylinux_2_28_x86_64.whl"
},
"pkginfo==1.11.1": {
"sha256": "bfa76a714fdfc18a045fcd684dbfc3816b603d9d075febef17cb6582bea29573",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pkginfo-1.11.1-py3-none-any.whl"
},
- "pycairo==1.22.0": {
- "sha256": "451b9f68e45b9f9cae5069cd6eab44ad339ae55cf177be904c0fab6a55228b85",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pycairo-1.22.0-cp39-cp39-manylinux_2_34_x86_64.whl"
+ "platformdirs==4.2.2": {
+ "sha256": "2d7a1657e36a80ea911db832a8a6ece5ee53d8de21edd5cc5879af6530b1bfee",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/platformdirs-4.2.2-py3-none-any.whl"
+ },
+ "plotly==5.24.1": {
+ "sha256": "f67073a1e637eb0dc3e46324d9d51e2fe76e9727c892dde64ddf1e1b51f29089",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/plotly-5.24.1-py3-none-any.whl"
+ },
+ "promise==2.3": {
+ "sha256": "d10acd69e1aed4de5840e3915edf51c877dfc7c7ae440fd081019edbf62820a4",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/promise-2.3-py3-none-any.whl"
+ },
+ "protobuf==3.20.3": {
+ "sha256": "daa564862dd0d39c00f8086f88700fdbe8bc717e993a21e90711acfed02f2402",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/protobuf-3.20.3-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.whl"
+ },
+ "psutil==6.0.0": {
+ "sha256": "5fd9a97c8e94059b0ef54a7d4baf13b405011176c3b6ff257c247cae0d560ecd",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/psutil-6.0.0-cp36-abi3-manylinux_2_12_x86_64.manylinux2010_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "pycairo==1.26.1": {
+ "sha256": "5eb499c081ff03ffed8edaa115325edf46eda7f89b53793a4b70dfc72180cc31",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pycairo-1.26.1-cp39-cp39-manylinux_2_34_x86_64.whl"
+ },
+ "pycparser==2.22": {
+ "sha256": "c3702b6d3dd8c7abc1afa565d7e63d53a1d0bd86cdc24edd75470f4de499cfcc",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pycparser-2.22-py3-none-any.whl"
+ },
+ "pydantic==2.9.2": {
+ "sha256": "f048cec7b26778210e28a0459867920654d48e5e62db0958433636cde4254f12",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pydantic-2.9.2-py3-none-any.whl"
+ },
+ "pydantic_core==2.23.4": {
+ "sha256": "1278e0d324f6908e872730c9102b0112477a7f7cf88b308e4fc36ce1bdb6d58c",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pydantic_core-2.23.4-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "pygments==2.18.0": {
+ "sha256": "b8e6aca0523f3ab76fee51799c488e38782ac06eafcf95e7ba832985c8e7b13a",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pygments-2.18.0-py3-none-any.whl"
},
"pygobject==3.42.2": {
"sha256": "c11807320f696b07525b97800570e80a6563a649f2950d66501e13474e5c3a36",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/PyGObject-3.42.2-cp39-cp39-linux_x86_64.whl"
},
- "pyparsing==3.0.9": {
- "sha256": "5026bae9a10eeaefb61dab2f09052b9f4307d44aee4eda64b309723d8d206bbc",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pyparsing-3.0.9-py3-none-any.whl"
+ "pyparsing==3.1.4": {
+ "sha256": "a6a7ee4235a3f944aa1fa2249307708f893fe5717dc603503c6c7969c070fb7c",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pyparsing-3.1.4-py3-none-any.whl"
},
- "python_dateutil==2.8.2": {
- "sha256": "961d03dc3453ebbc59dbdea9e4e11c5651520a876d0f4db161e8674aae935da9",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/python_dateutil-2.8.2-py2.py3-none-any.whl"
+ "python_dateutil==2.9.0.post0": {
+ "sha256": "a8b2bc7bffae282281c8140a97d3aa9c14da0b136dfe83f850eea9a5f7470427",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/python_dateutil-2.9.0.post0-py2.py3-none-any.whl"
},
"python_gflags==3.1.2": {
"sha256": "e2bd55abd9bb6e3b32026fd6c26a81c3f49979f24162fe73dc48da4fc306e74b",
@@ -199,72 +463,188 @@
"sha256": "328171f4e3623139da4983451950b28e95ac706e13f3f2630a879749e7a8b319",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pytz-2024.1-py2.py3-none-any.whl"
},
- "pyyaml==6.0": {
- "sha256": "40527857252b61eacd1d9af500c3337ba8deb8fc298940291486c465c8b46ec0",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/PyYAML-6.0-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_12_x86_64.manylinux2010_x86_64.whl"
+ "pyyaml==6.0.2": {
+ "sha256": "3b1fdb9dc17f5a7677423d508ab4f243a726dea51fa5e70992e59a7411c89d19",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/PyYAML-6.0.2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
},
"pyyaml_env_tag==0.1": {
"sha256": "af31106dec8a4d68c60207c1886031cbf839b68aa7abccdb19868200532c2069",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/pyyaml_env_tag-0.1-py3-none-any.whl"
},
- "qdldl==0.1.5.post2": {
- "sha256": "15d0fbff31aa19195b135ca934cf75025d46a275d915eebb7c11a7d16e148096",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/qdldl-0.1.5.post2-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ "qdldl==0.1.7.post4": {
+ "sha256": "12a658077a83a6aab9d122ca8f4ae4e96a06633109fa604414657ac2f065bd9b",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/qdldl-0.1.7.post4-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
},
- "requests==2.28.1": {
- "sha256": "8fefa2a1a1365bf5520aac41836fbee479da67864514bdb821f31ce07ce65349",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/requests-2.28.1-py3-none-any.whl"
+ "requests==2.32.3": {
+ "sha256": "70761cfe03c773ceb22aa2f671b4757976145175cdfca038c02654d061d6dcc6",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/requests-2.32.3-py3-none-any.whl"
},
- "scipy==1.9.3": {
- "sha256": "c68db6b290cbd4049012990d7fe71a2abd9ffbe82c0056ebe0f01df8be5436b0",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/scipy-1.9.3-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ "restrictedpython==7.2": {
+ "sha256": "139cb41da6e57521745a566d05825f7a09e6a884f7fa922568cff0a70b84ce6b",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/RestrictedPython-7.2-py3-none-any.whl"
},
- "shapely==2.0.0": {
- "sha256": "91bbca0378eb82f0808f0e59150ac0952086f4caaab87ad8515a5e55e896c21e",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/shapely-2.0.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ "rich==13.8.0": {
+ "sha256": "2e85306a063b9492dffc86278197a60cbece75bcb766022f3436f567cae11bdc",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/rich-13.8.0-py3-none-any.whl"
+ },
+ "s3transfer==0.10.2": {
+ "sha256": "eca1c20de70a39daee580aef4986996620f365c4e0fda6a86100231d62f1bf69",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/s3transfer-0.10.2-py3-none-any.whl"
+ },
+ "scipy==1.13.1": {
+ "sha256": "637e98dcf185ba7f8e663e122ebf908c4702420477ae52a04f9908707456ba4d",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/scipy-1.13.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "setuptools==74.0.0": {
+ "sha256": "0274581a0037b638b9fc1c6883cc71c0210865aaa76073f7882376b641b84e8f",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/setuptools-74.0.0-py3-none-any.whl"
+ },
+ "shapely==2.0.6": {
+ "sha256": "b02154b3e9d076a29a8513dffcb80f047a5ea63c897c0cd3d3679f29363cf7e5",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/shapely-2.0.6-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
},
"six==1.16.0": {
"sha256": "8abb2f1d86890a2dfb989f9a77cfcfd3e47c2a354b01111771326f8aa26e0254",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/six-1.16.0-py2.py3-none-any.whl"
},
- "sympy==1.12": {
- "sha256": "c3588cd4295d0c0f603d0f2ae780587e64e2efeedb3521e46b9bb1d08d184fa5",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/sympy-1.12-py3-none-any.whl"
+ "sniffio==1.3.1": {
+ "sha256": "2f6da418d1f1e0fddd844478f41680e794e6051915791a034ff65e5f100525a2",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/sniffio-1.3.1-py3-none-any.whl"
+ },
+ "sqlalchemy==2.0.35": {
+ "sha256": "890da8cd1941fa3dab28c5bac3b9da8502e7e366f895b3b8e500896f12f94d11",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/SQLAlchemy-2.0.35-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "starlette==0.38.6": {
+ "sha256": "4517a1409e2e73ee4951214ba012052b9e16f60e90d73cfb06192c19203bbb05",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/starlette-0.38.6-py3-none-any.whl"
+ },
+ "sympy==1.13.2": {
+ "sha256": "c51d75517712f1aed280d4ce58506a4a88d635d6b5dd48b39102a7ae1f3fcfe9",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/sympy-1.13.2-py3-none-any.whl"
},
"tabulate==0.9.0": {
"sha256": "024ca478df22e9340661486f85298cff5f6dcdba14f3813e8830015b9ed1948f",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tabulate-0.9.0-py3-none-any.whl"
},
- "tornado==6.4": {
- "sha256": "f0251554cdd50b4b44362f73ad5ba7126fc5b2c2895cc62b14a1c2d7ea32f212",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tornado-6.4-cp38-abi3-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ "tenacity==9.0.0": {
+ "sha256": "93de0c98785b27fcf659856aa9f54bfbd399e29969b0621bc7f762bd441b4539",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tenacity-9.0.0-py3-none-any.whl"
+ },
+ "tensorboard==2.17.1": {
+ "sha256": "253701a224000eeca01eee6f7e978aea7b408f60b91eb0babdb04e78947b773e",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tensorboard-2.17.1-py3-none-any.whl"
+ },
+ "tensorboard_data_server==0.7.2": {
+ "sha256": "ef687163c24185ae9754ed5650eb5bc4d84ff257aabdc33f0cc6f74d8ba54530",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tensorboard_data_server-0.7.2-py3-none-manylinux_2_31_x86_64.whl"
+ },
+ "tensorflow==2.17.0": {
+ "sha256": "4ae8e6746deb2ec807b902ba26d62fcffb6a6b53555a1a5906ec00416c5e4175",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tensorflow-2.17.0-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "tensorflow_datasets==4.9.3": {
+ "sha256": "09cd60eccab0d5a9d15f53e76ee0f1b530ee5aa3665e42be621a4810d9fa5db6",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tensorflow_datasets-4.9.3-py3-none-any.whl"
+ },
+ "tensorflow_io_gcs_filesystem==0.37.1": {
+ "sha256": "0df00891669390078a003cedbdd3b8e645c718b111917535fa1d7725e95cdb95",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tensorflow_io_gcs_filesystem-0.37.1-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "tensorflow_metadata==1.15.0": {
+ "sha256": "cb84d8e159128aeae7b3f6013ccd7969c69d2e6d1a7b255dbfa6f5344d962986",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tensorflow_metadata-1.15.0-py3-none-any.whl"
+ },
+ "tensorflow_probability==0.24.0": {
+ "sha256": "8c1774683e38359dbcaf3697e79b7e6a4e69b9c7b3679e78ee18f43e59e5759b",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tensorflow_probability-0.24.0-py2.py3-none-any.whl"
+ },
+ "tensorstore==0.1.64": {
+ "sha256": "72f76231ce12bfd266358a096e9c6000a2d86c1f4f24c3891c29b2edfffc5df4",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tensorstore-0.1.64-cp39-cp39-manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "termcolor==2.4.0": {
+ "sha256": "9297c0df9c99445c2412e832e882a7884038a25617c60cea2ad69488d4040d63",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/termcolor-2.4.0-py3-none-any.whl"
+ },
+ "tf_keras==2.17.0": {
+ "sha256": "cc97717e4dc08487f327b0740a984043a9e0123c7a4e21206711669d3ec41c88",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tf_keras-2.17.0-py3-none-any.whl"
+ },
+ "toml==0.10.2": {
+ "sha256": "806143ae5bfb6a3c6e736a764057db0e6a0e05e338b5630894a5f779cabb4f9b",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/toml-0.10.2-py2.py3-none-any.whl"
+ },
+ "tomli==2.0.1": {
+ "sha256": "939de3e7a6161af0c887ef91b7d41a53e7c5a1ca976325f429cb46ea9bc30ecc",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tomli-2.0.1-py3-none-any.whl"
+ },
+ "toolz==0.12.1": {
+ "sha256": "d22731364c07d72eea0a0ad45bafb2c2937ab6fd38a3507bf55eae8744aa7d85",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/toolz-0.12.1-py3-none-any.whl"
+ },
+ "tornado==6.4.1": {
+ "sha256": "613bf4ddf5c7a95509218b149b555621497a6cc0d46ac341b30bd9ec19eac7f3",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tornado-6.4.1-cp38-abi3-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "tqdm==4.66.5": {
+ "sha256": "90279a3770753eafc9194a0364852159802111925aa30eb3f9d85b0e805ac7cd",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tqdm-4.66.5-py3-none-any.whl"
+ },
+ "typeguard==2.13.3": {
+ "sha256": "5e3e3be01e887e7eafae5af63d1f36c849aaa94e3a0112097312aabfa16284f1",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/typeguard-2.13.3-py3-none-any.whl"
+ },
+ "typing_extensions==4.12.2": {
+ "sha256": "04e5ca0351e0f3f85c6853954072df659d0d13fac324d0072316b67d7794700d",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/typing_extensions-4.12.2-py3-none-any.whl"
},
"tzdata==2024.1": {
"sha256": "9068bc196136463f5245e51efda838afa15aaeca9903f49050dfa2679db4d252",
"url": "https://software.frc971.org/Build-Dependencies/wheelhouse/tzdata-2024.1-py2.py3-none-any.whl"
},
- "urllib3==1.26.13": {
- "sha256": "47cc05d99aaa09c9e72ed5809b60e7ba354e64b59c9c173ac3018642d8bb41fc",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/urllib3-1.26.13-py2.py3-none-any.whl"
+ "urllib3==1.26.20": {
+ "sha256": "0ed14ccfbf1c30a9072c7ca157e4319b70d65f623e91e7b32fadb2853431016e",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/urllib3-1.26.20-py2.py3-none-any.whl"
},
- "validators==0.22.0": {
- "sha256": "61cf7d4a62bbae559f2e54aed3b000cea9ff3e2fdbe463f51179b92c58c9585a",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/validators-0.22.0-py3-none-any.whl"
+ "uvicorn==0.30.6": {
+ "sha256": "65fd46fe3fda5bdc1b03b94eb634923ff18cd35b2f084813ea79d1f103f711b5",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/uvicorn-0.30.6-py3-none-any.whl"
},
- "watchdog==2.1.9": {
- "sha256": "4f4e1c4aa54fb86316a62a87b3378c025e228178d55481d30d857c6c438897d6",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/watchdog-2.1.9-py3-none-manylinux2014_x86_64.whl"
+ "validators==0.34.0": {
+ "sha256": "c804b476e3e6d3786fa07a30073a4ef694e617805eb1946ceee3fe5a9b8b1321",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/validators-0.34.0-py3-none-any.whl"
},
- "xyzservices==2024.4.0": {
- "sha256": "b83e48c5b776c9969fffcfff57b03d02b1b1cd6607a9d9c4e7f568b01ef47f4c",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/xyzservices-2024.4.0-py3-none-any.whl"
+ "watchdog==5.0.2": {
+ "sha256": "726eef8f8c634ac6584f86c9c53353a010d9f311f6c15a034f3800a7a891d941",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/watchdog-5.0.2-py3-none-manylinux2014_x86_64.whl"
},
- "yapf==0.32.0": {
- "sha256": "8fea849025584e486fd06d6ba2bed717f396080fd3cc236ba10cb97c4c51cf32",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/yapf-0.32.0-py2.py3-none-any.whl"
+ "websockets==13.1": {
+ "sha256": "6d2aad13a200e5934f5a6767492fb07151e1de1d6079c003ab31e1823733ae79",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/websockets-13.1-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
},
- "zipp==3.11.0": {
- "sha256": "83a28fcb75844b5c0cdaf5aa4003c2d728c77e05f5aeabe8e95e56727005fbaa",
- "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/zipp-3.11.0-py3-none-any.whl"
+ "werkzeug==3.0.4": {
+ "sha256": "02c9eb92b7d6c06f31a782811505d2157837cea66aaede3e217c7c27c039476c",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/werkzeug-3.0.4-py3-none-any.whl"
+ },
+ "wheel==0.44.0": {
+ "sha256": "2376a90c98cc337d18623527a97c31797bd02bad0033d41547043a1cbfbe448f",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/wheel-0.44.0-py3-none-any.whl"
+ },
+ "wrapt==1.16.0": {
+ "sha256": "f8212564d49c50eb4565e502814f694e240c55551a5f1bc841d4fcaabb0a9b8a",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/wrapt-1.16.0-cp39-cp39-manylinux_2_5_x86_64.manylinux1_x86_64.manylinux_2_17_x86_64.manylinux2014_x86_64.whl"
+ },
+ "xyzservices==2024.9.0": {
+ "sha256": "776ae82b78d6e5ca63dd6a94abb054df8130887a4a308473b54a6bd364de8644",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/xyzservices-2024.9.0-py3-none-any.whl"
+ },
+ "yapf==0.40.2": {
+ "sha256": "adc8b5dd02c0143108878c499284205adb258aad6db6634e5b869e7ee2bd548b",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/yapf-0.40.2-py3-none-any.whl"
+ },
+ "zipp==3.20.1": {
+ "sha256": "9960cd8967c8f85a56f920d5d507274e74f9ff813a0ab8889a5b5be2daf44064",
+ "url": "https://software.frc971.org/Build-Dependencies/wheelhouse/zipp-3.20.1-py3-none-any.whl"
}
}
diff --git a/y2014/control_loops/python/extended_lqr.py b/y2014/control_loops/python/extended_lqr.py
index 699dd30..dca57eb 100755
--- a/y2014/control_loops/python/extended_lqr.py
+++ b/y2014/control_loops/python/extended_lqr.py
@@ -294,18 +294,18 @@
S_bar_1_eigh_eigenvalues_stiff[i] = max(
S_bar_1_eigh_eigenvalues_stiff) * 1.0
- #print 'eigh eigenvalues of S bar', S_bar_1_eigh_eigenvalues
- #print 'eigh eigenvectors of S bar', S_bar_1_eigh_eigenvectors.T
+ #print('eigh eigenvalues of S bar', S_bar_1_eigh_eigenvalues)
+ #print('eigh eigenvectors of S bar', S_bar_1_eigh_eigenvectors.T)
- #print 'S bar eig recreate', S_bar_1_eigh_eigenvectors * numpy.matrix(numpy.diag(S_bar_1_eigh_eigenvalues)) * S_bar_1_eigh_eigenvectors.T
- #print 'S bar eig recreate error', (S_bar_1_eigh_eigenvectors * numpy.matrix(numpy.diag(S_bar_1_eigh_eigenvalues)) * S_bar_1_eigh_eigenvectors.T - S_bar_t[1])
+ #print('S bar eig recreate', S_bar_1_eigh_eigenvectors * numpy.matrix(numpy.diag(S_bar_1_eigh_eigenvalues)) * S_bar_1_eigh_eigenvectors.T)
+ #print('S bar eig recreate error', (S_bar_1_eigh_eigenvectors * numpy.matrix(numpy.diag(S_bar_1_eigh_eigenvalues)) * S_bar_1_eigh_eigenvectors.T - S_bar_t[1]))
S_bar_stiff = S_bar_1_eigh_eigenvectors * numpy.matrix(
numpy.diag(
S_bar_1_eigh_eigenvalues_stiff)) * S_bar_1_eigh_eigenvectors.T
- print 'Min u', -numpy.linalg.solve(TotalS_1, Totals_1)
- print 'Min x_hat', optimal_x_1
+ print('Min u', -numpy.linalg.solve(TotalS_1, Totals_1))
+ print('Min x_hat', optimal_x_1)
s_bar_t[1] = -s_t[1] - (S_bar_stiff + S_t[1]) * optimal_x_1
s_scalar_bar_t[1] = 0.5 * (
optimal_u_1.T * TotalS_1 * optimal_u_1 - optimal_x_1.T *
@@ -313,21 +313,22 @@
optimal_x_1) + optimal_u_1.T * Totals_1 - optimal_x_1.T * (
s_bar_t[1] + s_t[1]) - s_scalar_t[1] + Totals_scalar_1
- print 'optimal_u_1', optimal_u_1
- print 'TotalS_1', TotalS_1
- print 'Totals_1', Totals_1
- print 'Totals_scalar_1', Totals_scalar_1
- print 'overall cost 1', 0.5 * (
- optimal_u_1.T * TotalS_1 *
- optimal_u_1) + optimal_u_1.T * Totals_1 + Totals_scalar_1
- print 'overall cost 0', 0.5 * (x_hat_initial.T * S_t[0] * x_hat_initial
- ) + x_hat_initial.T * s_t[0] + s_scalar_t[0]
+ print('optimal_u_1', optimal_u_1)
+ print('TotalS_1', TotalS_1)
+ print('Totals_1', Totals_1)
+ print('Totals_scalar_1', Totals_scalar_1)
+ print(
+ 'overall cost 1', 0.5 * (optimal_u_1.T * TotalS_1 * optimal_u_1) +
+ optimal_u_1.T * Totals_1 + Totals_scalar_1)
+ print(
+ 'overall cost 0', 0.5 * (x_hat_initial.T * S_t[0] * x_hat_initial) +
+ x_hat_initial.T * s_t[0] + s_scalar_t[0])
- print 't forward 0'
- print 'x_hat_initial[ 0]: %s' % (x_hat_initial)
- print 'x_hat[%2d]: %s' % (0, x_hat.T)
- print 'x_hat_next[%2d]: %s' % (0, x_hat_next.T)
- print 'u[%2d]: %s' % (0, u_t.T)
+ print('t forward 0')
+ print('x_hat_initial[ 0]: %s' % (x_hat_initial))
+ print('x_hat[%2d]: %s' % (0, x_hat.T))
+ print('x_hat_next[%2d]: %s' % (0, x_hat_next.T))
+ print('u[%2d]: %s' % (0, u_t.T))
print('L[ 0]: %s' % (L_t[0], )).replace('\n', '\n ')
print('l[ 0]: %s' % (l_t[0], )).replace('\n', '\n ')
@@ -337,14 +338,14 @@
# TODO(austin): optimal_x_1 is x_hat
x_hat = -numpy.linalg.solve((S_t[1] + S_bar_stiff), (s_t[1] + s_bar_t[1]))
- print 'new xhat', x_hat
+ print('new xhat', x_hat)
S_bar_t[1] = S_bar_stiff
last_x_hat_t[1] = x_hat
for t in range(1, l):
- print 't forward', t
+ print('t forward', t)
u_t = L_t[t] * x_hat + l_t[t]
x_hat_next = discrete_dynamics(x_hat, u_t)
@@ -354,8 +355,8 @@
u_t)
c_bar_t = x_hat - A_bar_t * x_hat_next - B_bar_t * u_t
- print 'x_hat[%2d]: %s' % (t, x_hat.T)
- print 'x_hat_next[%2d]: %s' % (t, x_hat_next.T)
+ print('x_hat[%2d]: %s' % (t, x_hat.T))
+ print('x_hat_next[%2d]: %s' % (t, x_hat_next.T))
print('L[%2d]: %s' % (
t,
L_t[t],
@@ -364,7 +365,7 @@
t,
l_t[t],
)).replace('\n', '\n ')
- print 'u[%2d]: %s' % (t, u_t.T)
+ print('u[%2d]: %s' % (t, u_t.T))
print('A_bar_t[%2d]: %s' % (t, A_bar_t)).replace(
'\n', '\n ')
@@ -414,19 +415,19 @@
x_hat = -numpy.linalg.inv(S_t[l] + S_bar_t[l]) * (s_t[l] + s_bar_t[l])
for t in reversed(range(l)):
- print 't backward', t
+ print('t backward', t)
# TODO(austin): I don't think we can use L_t like this here.
# I think we are off by 1 somewhere...
u_t = L_bar_t[t + 1] * x_hat + l_bar_t[t + 1]
x_hat_prev = inverse_discrete_dynamics(x_hat, u_t)
- print 'x_hat[%2d]: %s' % (t, x_hat.T)
- print 'x_hat_prev[%2d]: %s' % (t, x_hat_prev.T)
+ print('x_hat[%2d]: %s' % (t, x_hat.T))
+ print('x_hat_prev[%2d]: %s' % (t, x_hat_prev.T))
print('L_bar[%2d]: %s' % (t + 1, L_bar_t[t + 1])).replace(
'\n', '\n ')
print('l_bar[%2d]: %s' % (t + 1, l_bar_t[t + 1])).replace(
'\n', '\n ')
- print 'u[%2d]: %s' % (t, u_t.T)
+ print('u[%2d]: %s' % (t, u_t.T))
# Now compute the linearized A, B, and C
# Start by doing it numerically, and then optimize.
A_t = numerical_jacobian_x(discrete_dynamics, x_hat_prev, u_t)
diff --git a/y2018/control_loops/python/arm_trajectory.py b/y2018/control_loops/python/arm_trajectory.py
index 9db7717..8b1ce47 100755
--- a/y2018/control_loops/python/arm_trajectory.py
+++ b/y2018/control_loops/python/arm_trajectory.py
@@ -1,4 +1,4 @@
-#!/usr/bin/python3
+#!/usr/bin/env python3
import copy
import numpy
@@ -617,7 +617,7 @@
self.distance_array = copy.copy(distance_array)
self.max_dvelocity_unfiltered = self.curvature_trajectory_pass(
dynamics, alpha_unitizer, distance_array, vmax)
- print 'Finished curvature pass'
+ print('Finished curvature pass')
self.max_dvelocity_unfiltered[0] = 0.0
self.max_dvelocity_unfiltered[-1] = 0.0
@@ -626,12 +626,12 @@
self.max_dvelocity_unfiltered, dynamics, alpha_unitizer,
distance_array, vmax)
self.max_dvelocity = self.max_dvelocity_back_pass
- print 'Finished backwards pass'
+ print('Finished backwards pass')
self.max_dvelocity_forward_pass = self.forward_trajectory_pass(
self.max_dvelocity_back_pass, dynamics, alpha_unitizer,
distance_array, vmax)
- print 'Finished forwards pass'
+ print('Finished forwards pass')
def interpolate_velocity(self, d, d0, d1, v0, v1):
if v0 + v1 > 0:
@@ -718,7 +718,7 @@
dynamics = Dynamics(dt)
trajectory = Trajectory(path_step_size)
- print 'Initialized path'
+ print('Initialized path')
distance_array = numpy.linspace(
0.0, trajectory.length(),
@@ -769,7 +769,7 @@
io0 += alpha[0, 0] * dd
io1 += alpha[1, 0] * dd
- print 'Iterated through path'
+ print('Iterated through path')
# Bounds on the accelerations of the two DOFs.
# We'll draw an oval to represent the actual bounds here.
@@ -786,7 +786,7 @@
distance_array,
vmax=vmax)
- print 'Computed trajectory'
+ print('Computed trajectory')
# Now, we can get acceleration, velocity, and position as a function of distance.
# Acceleration is best effort (derived from the velocities), but velocity
@@ -839,7 +839,7 @@
sim_dt = dt
- print 'Starting simulation'
+ print('Starting simulation')
# Now, we can start following the trajectory!
for t in numpy.arange(0.0, 1.0, sim_dt):
if goal_distance == trajectory.length():
@@ -914,9 +914,9 @@
# starting point.
if (numpy.abs(U) > vmax).any():
# Saturated. Let's do a binary search.
- print "Saturated."
+ print("Saturated.")
if (goal_distance - last_goal_distance) < 1e-8:
- print "Not bothering to move"
+ print("Not bothering to move")
# Avoid the divide by 0 when interpolating. Just don't move
# since we are saturated.
fraction_along_path = 0.0
@@ -936,7 +936,8 @@
fraction_along_path -= step_size
else:
fraction_along_path += step_size
- print "Fraction", fraction_along_path, "at", goal_distance, "rad,", t, "sec", goal_velocity
+ print("Fraction", fraction_along_path, "at", goal_distance, "rad,",
+ t, "sec", goal_velocity)
goal_distance = (
(goal_distance - last_goal_distance) * fraction_along_path +
@@ -986,7 +987,7 @@
goal_distance = trajectory.length()
goal_velocity = 0.0
- print 'Finished simulation'
+ print('Finished simulation')
pylab.figure()
pylab.title("Trajecotry")
pylab.plot(theta0_array, theta1_array, label="desired path")
diff --git a/y2018/control_loops/python/extended_lqr.py b/y2018/control_loops/python/extended_lqr.py
index 9a4705b..a2a31af 100755
--- a/y2018/control_loops/python/extended_lqr.py
+++ b/y2018/control_loops/python/extended_lqr.py
@@ -66,14 +66,14 @@
final_B = numerical_jacobian_u(self.dynamics.discrete_dynamics,
numpy.matrix(numpy.zeros((4, 1))),
numpy.matrix(numpy.zeros((2, 1))))
- print 'Final A', final_A
- print 'Final B', final_B
+ print('Final A', final_A)
+ print('Final B', final_B)
K, self.S = controls.dlqr(final_A,
final_B,
self.Q,
self.R,
optimal_cost_function=True)
- print 'Final eig:', numpy.linalg.eig(final_A - final_B * K)
+ print('Final eig:', numpy.linalg.eig(final_A - final_B * K))
def final_cost(self, X, U):
"""Computes the final cost of being at X
@@ -85,6 +85,7 @@
Returns:
numpy.matrix(1, 1), The quadratic cost of being at X
"""
+ print('TODO(austin): S -> X.T * S * X, need to fix if we care')
return 0.5 * X.T * self.S * X
def cost(self, X, U):
@@ -111,8 +112,9 @@
numpy.matrix(self.num_states, self.num_states)
"""
zero_U = numpy.matrix(numpy.zeros((self.num_inputs, 1)))
- print 'S', self.S
- print 'Q_final', numerical_jacobian_x_x(self.final_cost, X_hat, zero_U)
+ print('S', self.S)
+ print('Q_final', numerical_jacobian_x_x(self.final_cost, X_hat,
+ zero_U))
return numerical_jacobian_x_x(self.final_cost, X_hat, zero_U)
def estimate_partial_cost_partial_x_final(self, X_hat):
@@ -448,8 +450,8 @@
numpy.diag(S_bar_1_eigh_eigenvalues_stiff)
) * S_bar_1_eigh_eigenvectors.T
- print 'Min u', -numpy.linalg.solve(TotalS_1, Totals_1)
- print 'Min x_hat', optimal_x_1
+ print('Min u', -numpy.linalg.solve(TotalS_1, Totals_1))
+ print('Min x_hat', optimal_x_1)
self.s_bar_t[1] = -self.s_t[1] - (S_bar_stiff +
self.S_t[1]) * optimal_x_1
self.s_scalar_bar_t[1] = 0.5 * (optimal_u_1.T * TotalS_1 * optimal_u_1 \
@@ -458,20 +460,20 @@
- optimal_x_1.T * (self.s_bar_t[1] + self.s_t[1]) \
- self.s_scalar_t[1] + Totals_scalar_1
- print 'optimal_u_1', optimal_u_1
- print 'TotalS_1', TotalS_1
- print 'Totals_1', Totals_1
- print 'Totals_scalar_1', Totals_scalar_1
- print 'overall cost 1', 0.5 * (optimal_u_1.T * TotalS_1 * optimal_u_1) \
- + optimal_u_1.T * Totals_1 + Totals_scalar_1
- print 'overall cost 0', 0.5 * (x_hat_initial.T * self.S_t[0] * x_hat_initial) \
- + x_hat_initial.T * self.s_t[0] + self.s_scalar_t[0]
+ print('optimal_u_1', optimal_u_1)
+ print('TotalS_1', TotalS_1)
+ print('Totals_1', Totals_1)
+ print('Totals_scalar_1', Totals_scalar_1)
+ print('overall cost 1', 0.5 * (optimal_u_1.T * TotalS_1 * optimal_u_1) \
+ + optimal_u_1.T * Totals_1 + Totals_scalar_1)
+ print('overall cost 0', 0.5 * (x_hat_initial.T * self.S_t[0] * x_hat_initial) \
+ + x_hat_initial.T * self.s_t[0] + self.s_scalar_t[0])
- print 't forward 0'
- print 'x_hat_initial[ 0]: %s' % (x_hat_initial)
- print 'x_hat[%2d]: %s' % (0, x_hat.T)
- print 'x_hat_next[%2d]: %s' % (0, x_hat_next.T)
- print 'u[%2d]: %s' % (0, u_t.T)
+ print('t forward 0')
+ print('x_hat_initial[ 0]: %s' % (x_hat_initial))
+ print('x_hat[%2d]: %s' % (0, x_hat.T))
+ print('x_hat_next[%2d]: %s' % (0, x_hat_next.T))
+ print('u[%2d]: %s' % (0, u_t.T))
print('L[ 0]: %s' % (self.L_t[0], )).replace('\n', '\n ')
print('l[ 0]: %s' % (self.l_t[0], )).replace('\n', '\n ')
@@ -482,14 +484,14 @@
# TODO(austin): optimal_x_1 is x_hat
x_hat = -numpy.linalg.solve((self.S_t[1] + S_bar_stiff),
(self.s_t[1] + self.s_bar_t[1]))
- print 'new xhat', x_hat
+ print('new xhat', x_hat)
self.S_bar_t[1] = S_bar_stiff
self.last_x_hat_t[1] = x_hat
for t in range(1, l):
- print 't forward', t
+ print('t forward', t)
u_t = self.L_t[t] * x_hat + self.l_t[t]
x_hat_next = self.dynamics.discrete_dynamics(x_hat, u_t)
@@ -499,8 +501,8 @@
self.dynamics.inverse_discrete_dynamics, x_hat_next, u_t)
c_bar_t = x_hat - A_bar_t * x_hat_next - B_bar_t * u_t
- print 'x_hat[%2d]: %s' % (t, x_hat.T)
- print 'x_hat_next[%2d]: %s' % (t, x_hat_next.T)
+ print('x_hat[%2d]: %s' % (t, x_hat.T))
+ print('x_hat_next[%2d]: %s' % (t, x_hat_next.T))
print('L[%2d]: %s' % (
t,
self.L_t[t],
@@ -509,7 +511,7 @@
t,
self.l_t[t],
)).replace('\n', '\n ')
- print 'u[%2d]: %s' % (t, u_t.T)
+ print('u[%2d]: %s' % (t, u_t.T))
print('A_bar_t[%2d]: %s' % (t, A_bar_t)).replace(
'\n', '\n ')
@@ -561,20 +563,20 @@
* (self.s_t[l] + self.s_bar_t[l])
for t in reversed(range(l)):
- print 't backward', t
+ print('t backward', t)
# TODO(austin): I don't think we can use L_t like this here.
# I think we are off by 1 somewhere...
u_t = self.L_bar_t[t + 1] * x_hat + self.l_bar_t[t + 1]
x_hat_prev = self.dynamics.inverse_discrete_dynamics(
x_hat, u_t)
- print 'x_hat[%2d]: %s' % (t, x_hat.T)
- print 'x_hat_prev[%2d]: %s' % (t, x_hat_prev.T)
+ print('x_hat[%2d]: %s' % (t, x_hat.T))
+ print('x_hat_prev[%2d]: %s' % (t, x_hat_prev.T))
print('L_bar[%2d]: %s' % (t + 1, self.L_bar_t[t + 1])).replace(
'\n', '\n ')
print('l_bar[%2d]: %s' % (t + 1, self.l_bar_t[t + 1])).replace(
'\n', '\n ')
- print 'u[%2d]: %s' % (t, u_t.T)
+ print('u[%2d]: %s' % (t, u_t.T))
# Now compute the linearized A, B, and C
# Start by doing it numerically, and then optimize.
A_t = numerical_jacobian_x(self.dynamics.discrete_dynamics,
diff --git a/y2020/wpilib_interface.cc b/y2020/wpilib_interface.cc
index 2213c16..8c8b480 100644
--- a/y2020/wpilib_interface.cc
+++ b/y2020/wpilib_interface.cc
@@ -123,9 +123,11 @@
void WriteConfigs(ctre::phoenix6::hardware::TalonFX *talon,
double stator_current_limit, double supply_current_limit) {
ctre::phoenix6::configs::CurrentLimitsConfigs current_limits;
- current_limits.StatorCurrentLimit = stator_current_limit;
+ current_limits.StatorCurrentLimit =
+ units::current::ampere_t{stator_current_limit};
current_limits.StatorCurrentLimitEnable = true;
- current_limits.SupplyCurrentLimit = supply_current_limit;
+ current_limits.SupplyCurrentLimit =
+ units::current::ampere_t{supply_current_limit};
current_limits.SupplyCurrentLimitEnable = true;
ctre::phoenix6::configs::TalonFXConfiguration configuration;
@@ -454,7 +456,8 @@
::std::unique_ptr<::ctre::phoenix6::hardware::TalonFX> t) {
climber_falcon_ = ::std::move(t);
ctre::phoenix6::configs::CurrentLimitsConfigs current_limits;
- current_limits.SupplyCurrentLimit = Values::kClimberSupplyCurrentLimit();
+ current_limits.SupplyCurrentLimit =
+ units::current::ampere_t{Values::kClimberSupplyCurrentLimit()};
current_limits.SupplyCurrentLimitEnable = true;
ctre::phoenix6::configs::TalonFXConfiguration configuration;
diff --git a/y2021_bot3/wpilib_interface.cc b/y2021_bot3/wpilib_interface.cc
index 4006736..f3c956e 100644
--- a/y2021_bot3/wpilib_interface.cc
+++ b/y2021_bot3/wpilib_interface.cc
@@ -119,9 +119,11 @@
void WriteConfigs(ctre::phoenix6::hardware::TalonFX *talon,
double stator_current_limit, double supply_current_limit) {
ctre::phoenix6::configs::CurrentLimitsConfigs current_limits;
- current_limits.StatorCurrentLimit = stator_current_limit;
+ current_limits.StatorCurrentLimit =
+ units::current::ampere_t{stator_current_limit};
current_limits.StatorCurrentLimitEnable = true;
- current_limits.SupplyCurrentLimit = supply_current_limit;
+ current_limits.SupplyCurrentLimit =
+ units::current::ampere_t{supply_current_limit};
current_limits.SupplyCurrentLimitEnable = true;
ctre::phoenix6::configs::TalonFXConfiguration configuration;
@@ -249,7 +251,8 @@
::std::unique_ptr<::ctre::phoenix6::hardware::TalonFX> t) {
climber_falcon_ = ::std::move(t);
ctre::phoenix6::configs::CurrentLimitsConfigs current_limits;
- current_limits.SupplyCurrentLimit = Values::kClimberSupplyCurrentLimit();
+ current_limits.SupplyCurrentLimit =
+ units::current::ampere_t{Values::kClimberSupplyCurrentLimit()};
current_limits.SupplyCurrentLimitEnable = true;
ctre::phoenix6::configs::TalonFXConfiguration configuration;
diff --git a/y2022/wpilib_interface.cc b/y2022/wpilib_interface.cc
index 1f82e91..469c93b 100644
--- a/y2022/wpilib_interface.cc
+++ b/y2022/wpilib_interface.cc
@@ -129,9 +129,11 @@
void WriteConfigs(ctre::phoenix6::hardware::TalonFX *talon,
double stator_current_limit, double supply_current_limit) {
ctre::phoenix6::configs::CurrentLimitsConfigs current_limits;
- current_limits.StatorCurrentLimit = stator_current_limit;
+ current_limits.StatorCurrentLimit =
+ units::current::ampere_t{stator_current_limit};
current_limits.StatorCurrentLimitEnable = true;
- current_limits.SupplyCurrentLimit = supply_current_limit;
+ current_limits.SupplyCurrentLimit =
+ units::current::ampere_t{supply_current_limit};
current_limits.SupplyCurrentLimitEnable = true;
ctre::phoenix6::configs::TalonFXConfiguration configuration;
@@ -483,10 +485,10 @@
for (auto &falcon : {catapult_falcon_1_can_, catapult_falcon_2_can_}) {
ctre::phoenix6::configs::CurrentLimitsConfigs current_limits;
current_limits.StatorCurrentLimit =
- Values::kIntakeRollerStatorCurrentLimit();
+ units::current::ampere_t{Values::kIntakeRollerStatorCurrentLimit()};
current_limits.StatorCurrentLimitEnable = true;
current_limits.SupplyCurrentLimit =
- Values::kIntakeRollerSupplyCurrentLimit();
+ units::current::ampere_t{Values::kIntakeRollerSupplyCurrentLimit()};
current_limits.SupplyCurrentLimitEnable = true;
ctre::phoenix6::configs::TalonFXConfiguration configuration;
diff --git a/y2023/control_loops/python/graph_edit.py b/y2023/control_loops/python/graph_edit.py
index f3035f1..eda7ee1 100644
--- a/y2023/control_loops/python/graph_edit.py
+++ b/y2023/control_loops/python/graph_edit.py
@@ -642,13 +642,13 @@
self.now_segment_pt = np.array(shift_angles(pt_theta))
if self.editing:
if self.edit_control1:
- if (self.now_segment_pt !=
- self.segments[self.index].control1).any():
+ if (self.now_segment_pt
+ != self.segments[self.index].control1).any():
self.previous_segment = self.segments[self.index].control1
self.segments[self.index].control1 = self.now_segment_pt
else:
- if (self.now_segment_pt !=
- self.segments[self.index].control2).any():
+ if (self.now_segment_pt
+ != self.segments[self.index].control2).any():
self.previous_segment = self.segments[self.index].control2
self.segments[self.index].control2 = self.now_segment_pt
diff --git a/y2023/wpilib_interface.cc b/y2023/wpilib_interface.cc
index bc14311..536f7bb 100644
--- a/y2023/wpilib_interface.cc
+++ b/y2023/wpilib_interface.cc
@@ -166,11 +166,11 @@
inverted_ = invert;
ctre::phoenix6::configs::CurrentLimitsConfigs current_limits;
- current_limits.StatorCurrentLimit =
- constants::Values::kDrivetrainStatorCurrentLimit();
+ current_limits.StatorCurrentLimit = units::current::ampere_t{
+ constants::Values::kDrivetrainStatorCurrentLimit()};
current_limits.StatorCurrentLimitEnable = true;
- current_limits.SupplyCurrentLimit =
- constants::Values::kDrivetrainSupplyCurrentLimit();
+ current_limits.SupplyCurrentLimit = units::current::ampere_t{
+ constants::Values::kDrivetrainSupplyCurrentLimit()};
current_limits.SupplyCurrentLimitEnable = true;
ctre::phoenix6::configs::MotorOutputConfigs output_configs;
@@ -196,11 +196,11 @@
void WriteRollerConfigs() {
ctre::phoenix6::configs::CurrentLimitsConfigs current_limits;
- current_limits.StatorCurrentLimit =
- constants::Values::kRollerStatorCurrentLimit();
+ current_limits.StatorCurrentLimit = units::current::ampere_t{
+ constants::Values::kRollerStatorCurrentLimit()};
current_limits.StatorCurrentLimitEnable = true;
- current_limits.SupplyCurrentLimit =
- constants::Values::kRollerSupplyCurrentLimit();
+ current_limits.SupplyCurrentLimit = units::current::ampere_t{
+ constants::Values::kRollerSupplyCurrentLimit()};
current_limits.SupplyCurrentLimitEnable = true;
ctre::phoenix6::configs::MotorOutputConfigs output_configs;
diff --git a/y2023_bot3/wpilib_interface.cc b/y2023_bot3/wpilib_interface.cc
index d8813be..0e43e10 100644
--- a/y2023_bot3/wpilib_interface.cc
+++ b/y2023_bot3/wpilib_interface.cc
@@ -147,11 +147,11 @@
inverted_ = invert;
ctre::phoenix6::configs::CurrentLimitsConfigs current_limits;
- current_limits.StatorCurrentLimit =
- constants::Values::kDrivetrainStatorCurrentLimit();
+ current_limits.StatorCurrentLimit = units::current::ampere_t{
+ constants::Values::kDrivetrainStatorCurrentLimit()};
current_limits.StatorCurrentLimitEnable = true;
- current_limits.SupplyCurrentLimit =
- constants::Values::kDrivetrainSupplyCurrentLimit();
+ current_limits.SupplyCurrentLimit = units::current::ampere_t{
+ constants::Values::kDrivetrainSupplyCurrentLimit()};
current_limits.SupplyCurrentLimitEnable = true;
ctre::phoenix6::configs::MotorOutputConfigs output_configs;
diff --git a/y2024/vision/viewer.cc b/y2024/vision/viewer.cc
index c72c08e..c741445 100644
--- a/y2024/vision/viewer.cc
+++ b/y2024/vision/viewer.cc
@@ -86,7 +86,9 @@
frc971::constants::ConstantsFetcher<y2024::Constants> constants_fetcher(
&event_loop);
- CHECK(absl::GetFlag(FLAGS_channel).length() == 8);
+ CHECK(absl::GetFlag(FLAGS_channel).length() == 8)
+ << " channel should be of the form '/cameraN' for viewing images from "
+ "camera N";
int camera_id = std::stoi(absl::GetFlag(FLAGS_channel).substr(7, 1));
const auto *calibration_data = FindCameraCalibration(
constants_fetcher.constants(), event_loop.node()->name()->string_view(),
diff --git a/y2024_bot3/BUILD b/y2024_bot3/BUILD
new file mode 100644
index 0000000..c766a54
--- /dev/null
+++ b/y2024_bot3/BUILD
@@ -0,0 +1,309 @@
+load("//aos:config.bzl", "aos_config")
+load("//aos/util:config_validator_macro.bzl", "config_validator_test")
+load("//frc971:downloader.bzl", "robot_downloader")
+
+config_validator_test(
+ name = "config_validator_test",
+ config = "//y2024_bot3:aos_config",
+)
+
+robot_downloader(
+ binaries = [
+ "//aos/network:web_proxy_main",
+ "//aos/events/logging:log_cat",
+ "//y2024_bot3/constants:constants_sender",
+ "//aos/events:aos_timing_report_streamer",
+ ],
+ data = [
+ ":aos_config",
+ "//aos/starter:roborio_irq_config.json",
+ "//y2024_bot3/constants:constants.json",
+ "@ctre_phoenix6_api_cpp_athena//:shared_libraries",
+ "@ctre_phoenix6_tools_athena//:shared_libraries",
+ "@ctre_phoenix_api_cpp_athena//:shared_libraries",
+ "@ctre_phoenix_cci_athena//:shared_libraries",
+ ],
+ dirs = [
+ "//y2024_bot3/www:www_files",
+ ],
+ start_binaries = [
+ "//aos/events/logging:logger_main",
+ "//aos/network:web_proxy_main",
+ "//aos/starter:irq_affinity",
+ ":joystick_reader",
+ ":wpilib_interface",
+ "//frc971/can_logger",
+ "//aos/network:message_bridge_client",
+ "//aos/network:message_bridge_server",
+ "//y2024_bot3/control_loops/superstructure:superstructure",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+)
+
+robot_downloader(
+ name = "orin_download",
+ binaries = [
+ "//frc971/wpilib:joystick_republish",
+ "//aos/events:aos_timing_report_streamer",
+ "//aos/events/logging:log_cat",
+ "//aos:aos_jitter",
+ "//aos/network:web_proxy_main",
+ "//aos/starter:irq_affinity",
+ "//aos/util:foxglove_websocket",
+ "//frc971/image_streamer:image_streamer",
+ "//frc971/orin:hardware_monitor",
+ "//frc971/orin:argus_monitor",
+ "//frc971/vision:intrinsics_calibration",
+ "//aos/util:filesystem_monitor",
+ "//y2024_bot3/vision:viewer",
+ "//y2024_bot3/constants:constants_sender",
+ "//frc971/orin:localizer_logger",
+ "//frc971/vision:foxglove_image_converter",
+ ],
+ data = [
+ ":aos_config",
+ "//frc971/orin:orin_irq_config.json",
+ "//y2024_bot3/constants:constants.json",
+ "//y2024_bot3/vision:image_streamer_start",
+ "//y2024_bot3/www:www_files",
+ ],
+ dirs = [
+ "//y2024_bot3/www:www_files",
+ "//frc971/image_streamer/www:www_files",
+ ],
+ start_binaries = [
+ "//aos/events/logging:logger_main",
+ "//frc971/imu_fdcan:can_translator",
+ "//frc971/imu_fdcan:dual_imu_blender",
+ "//aos/network:message_bridge_client",
+ "//aos/network:message_bridge_server",
+ "//aos/network:web_proxy_main",
+ "//aos/starter:irq_affinity",
+ "//frc971/orin:argus_camera",
+ "//y2024_bot3/orin:can_logger",
+ "//y2024_bot3/vision:apriltag_detector",
+ "//frc971/vision:image_logger",
+ ],
+ target_compatible_with = ["//tools/platforms/hardware:raspberry_pi"],
+ target_type = "pi",
+)
+
+aos_config(
+ name = "aos_config",
+ src = "y2024_bot3.json",
+ flatbuffers = [
+ "//aos/network:message_bridge_client_fbs",
+ "//aos/network:message_bridge_server_fbs",
+ "//aos/network:timestamp_fbs",
+ "//frc971/input:robot_state_fbs",
+ "//frc971/vision:vision_fbs",
+ "//frc971/vision:target_map_fbs",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ ":config_imu",
+ ":config_orin1",
+ ":config_roborio",
+ ],
+)
+
+aos_config(
+ name = "config_imu",
+ src = "y2024_bot3_imu.json",
+ flatbuffers = [
+ "//aos/network:message_bridge_client_fbs",
+ "//aos/network:message_bridge_server_fbs",
+ "//frc971/imu_fdcan:dual_imu_fbs",
+ "//frc971/imu_fdcan:can_translator_status_fbs",
+ "//frc971/imu_fdcan:dual_imu_blender_status_fbs",
+ "//y2024_bot3/constants:constants_fbs",
+ "//frc971/control_loops/drivetrain/localization:localizer_output_fbs",
+ "//frc971/can_logger:can_logging_fbs",
+ "//frc971/orin:hardware_stats_fbs",
+ "//aos/network:timestamp_fbs",
+ "//aos/util:filesystem_fbs",
+ "//aos/network:remote_message_fbs",
+ "//frc971/vision:calibration_fbs",
+ "//frc971/vision:target_map_fbs",
+ "//frc971/vision:vision_fbs",
+ "@com_github_foxglove_schemas//:schemas",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//aos/events:aos_config",
+ "//frc971/control_loops/drivetrain:aos_config",
+ ],
+)
+
+aos_config(
+ name = "config_roborio",
+ src = "y2024_bot3_roborio.json",
+ flatbuffers = [
+ "//frc971:can_configuration_fbs",
+ "//aos/network:remote_message_fbs",
+ "//aos/network:message_bridge_client_fbs",
+ "//aos/network:message_bridge_server_fbs",
+ "//frc971/wpilib:pdp_values_fbs",
+ "//y2024_bot3/constants:constants_fbs",
+ "//aos/network:timestamp_fbs",
+ "//y2024_bot3/control_loops/superstructure:superstructure_goal_fbs",
+ "//frc971/control_loops/drivetrain:drivetrain_can_position_fbs",
+ "//y2024_bot3/control_loops/superstructure:superstructure_can_position_fbs",
+ "//y2024_bot3/control_loops/superstructure:superstructure_output_fbs",
+ "//frc971/control_loops/drivetrain:rio_localizer_inputs_fbs",
+ "//y2024_bot3/control_loops/superstructure:superstructure_position_fbs",
+ "//frc971/control_loops/drivetrain/localization:localizer_output_fbs",
+ "//y2024_bot3/control_loops/superstructure:superstructure_status_fbs",
+ "//frc971/can_logger:can_logging_fbs",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ "//aos/events:aos_config",
+ "//frc971/control_loops/drivetrain:aos_config",
+ "//frc971/input:aos_config",
+ ],
+)
+
+aos_config(
+ name = "config_orin1",
+ src = "y2024_bot3_orin1.json",
+ flatbuffers = [
+ "//aos/network:message_bridge_client_fbs",
+ "//aos/network:message_bridge_server_fbs",
+ "//aos/network:timestamp_fbs",
+ "//aos/network:remote_message_fbs",
+ "//y2024_bot3/constants:constants_fbs",
+ "//frc971/control_loops/drivetrain/localization:localizer_output_fbs",
+ "//frc971/orin:hardware_stats_fbs",
+ "//frc971/vision:calibration_fbs",
+ "//frc971/vision:target_map_fbs",
+ "//frc971/vision:vision_fbs",
+ "//aos/util:filesystem_fbs",
+ "@com_github_foxglove_schemas//:schemas",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//aos/events:aos_config",
+ "//frc971/control_loops/drivetrain:aos_config",
+ "//frc971/input:aos_config",
+ ],
+)
+
+cc_library(
+ name = "constants",
+ srcs = [
+ "constants.cc",
+ ],
+ hdrs = [
+ "constants.h",
+ ],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//aos/mutex",
+ "//aos/network:team_number",
+ "//frc971:constants",
+ "//frc971/control_loops:pose",
+ "//frc971/control_loops:static_zeroing_single_dof_profiled_subsystem",
+ "//frc971/zeroing:absolute_encoder",
+ "//frc971/zeroing:pot_and_absolute_encoder",
+ "//y2024_bot3/constants:constants_fbs",
+ "@com_google_absl//absl/base",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
+ ],
+)
+
+cc_binary(
+ name = "wpilib_interface",
+ srcs = [
+ "wpilib_interface.cc",
+ ],
+ target_compatible_with = ["//tools/platforms/hardware:roborio"],
+ deps = [
+ ":constants",
+ "//aos:init",
+ "//aos:math",
+ "//aos/containers:sized_array",
+ "//aos/events:shm_event_loop",
+ "//aos/logging",
+ "//aos/stl_mutex",
+ "//aos/time",
+ "//aos/util:log_interval",
+ "//aos/util:phased_loop",
+ "//aos/util:wrapping_counter",
+ "//frc971:can_configuration_fbs",
+ "//frc971/constants:constants_sender_lib",
+ "//frc971/control_loops:control_loop",
+ "//frc971/control_loops:control_loops_fbs",
+ "//frc971/control_loops/drivetrain:drivetrain_can_position_fbs",
+ "//frc971/control_loops/drivetrain:drivetrain_position_fbs",
+ "//frc971/input:robot_state_fbs",
+ "//frc971/queues:gyro_fbs",
+ "//frc971/wpilib:ADIS16448",
+ "//frc971/wpilib:buffered_pcm",
+ "//frc971/wpilib:can_drivetrain_writer",
+ "//frc971/wpilib:can_sensor_reader",
+ "//frc971/wpilib:dma",
+ "//frc971/wpilib:drivetrain_writer",
+ "//frc971/wpilib:encoder_and_potentiometer",
+ "//frc971/wpilib:generic_can_writer",
+ "//frc971/wpilib:joystick_sender",
+ "//frc971/wpilib:logging_fbs",
+ "//frc971/wpilib:pdp_fetcher",
+ "//frc971/wpilib:sensor_reader",
+ "//frc971/wpilib:talonfx",
+ "//frc971/wpilib:wpilib_robot_base",
+ "//third_party:phoenix",
+ "//third_party:phoenix6",
+ "//third_party:wpilib",
+ "//y2024_bot3/constants:constants_fbs",
+ "//y2024_bot3/control_loops/superstructure:superstructure_can_position_fbs",
+ "//y2024_bot3/control_loops/superstructure:superstructure_output_fbs",
+ "//y2024_bot3/control_loops/superstructure:superstructure_position_fbs",
+ ],
+)
+
+cc_binary(
+ name = "joystick_reader",
+ srcs = [
+ ":joystick_reader.cc",
+ ],
+ deps = [
+ ":constants",
+ "//aos:init",
+ "//aos/actions:action_lib",
+ "//aos/logging",
+ "//frc971/constants:constants_sender_lib",
+ "//frc971/control_loops:profiled_subsystem_fbs",
+ "//frc971/control_loops:static_zeroing_single_dof_profiled_subsystem",
+ "//frc971/input:action_joystick_input",
+ "//frc971/input:drivetrain_input",
+ "//frc971/input:joystick_input",
+ "//frc971/input:redundant_joystick_data",
+ "//y2024_bot3/control_loops/superstructure:superstructure_goal_fbs",
+ "//y2024_bot3/control_loops/superstructure:superstructure_status_fbs",
+ ],
+)
+
+py_library(
+ name = "python_init",
+ srcs = ["__init__.py"],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+)
+
+sh_binary(
+ name = "log_web_proxy",
+ srcs = ["log_web_proxy.sh"],
+ data = [
+ ":aos_config",
+ "//aos/network:log_web_proxy_main",
+ "//frc971/www:starter_main_bundle.min.js",
+ "//y2024_bot3/www:field_main_bundle.min.js",
+ "//y2024_bot3/www:files",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+)
diff --git a/y2024_bot3/__init__.py b/y2024_bot3/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2024_bot3/__init__.py
diff --git a/y2024_bot3/constants.cc b/y2024_bot3/constants.cc
new file mode 100644
index 0000000..9b97566
--- /dev/null
+++ b/y2024_bot3/constants.cc
@@ -0,0 +1,41 @@
+#include "y2024_bot3/constants.h"
+
+#include <cinttypes>
+#include <map>
+
+#if __has_feature(address_sanitizer)
+#include "sanitizer/lsan_interface.h"
+#endif
+
+#include "absl/base/call_once.h"
+#include "absl/log/check.h"
+#include "absl/log/log.h"
+
+#include "aos/mutex/mutex.h"
+#include "aos/network/team_number.h"
+
+namespace y2024_bot3::constants {
+
+Values MakeValues(uint16_t team) {
+ LOG(INFO) << "creating a Constants for team: " << team;
+
+ Values r;
+
+ switch (team) {
+ // A set of constants for tests.
+ case 1:
+ break;
+
+ case kThirdRobotTeamNumber:
+ break;
+
+ default:
+ LOG(FATAL) << "unknown team: " << team;
+ }
+
+ return r;
+}
+
+Values MakeValues() { return MakeValues(aos::network::GetTeamNumber()); }
+
+} // namespace y2024_bot3::constants
diff --git a/y2024_bot3/constants.h b/y2024_bot3/constants.h
new file mode 100644
index 0000000..31d104f
--- /dev/null
+++ b/y2024_bot3/constants.h
@@ -0,0 +1,53 @@
+#ifndef Y2024_BOT3_CONSTANTS_H_
+#define Y2024_BOT3_CONSTANTS_H_
+
+#include <array>
+#include <cmath>
+#include <cstdint>
+
+#include "frc971/constants.h"
+#include "frc971/control_loops/pose.h"
+#include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h"
+#include "frc971/zeroing/absolute_encoder.h"
+#include "frc971/zeroing/pot_and_absolute_encoder.h"
+#include "y2024_bot3/constants/constants_generated.h"
+
+namespace y2024_bot3::constants {
+
+constexpr uint16_t kThirdRobotTeamNumber = 9971;
+
+struct Values {
+ static const int kSuperstructureCANWriterPriority = 35;
+
+ struct PotAndAbsEncoderConstants {
+ ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemParams<
+ ::frc971::zeroing::PotAndAbsoluteEncoderZeroingEstimator>
+ subsystem_params;
+ double potentiometer_offset;
+ };
+
+ struct AbsoluteEncoderConstants {
+ ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemParams<
+ ::frc971::zeroing::AbsoluteEncoderZeroingEstimator>
+ subsystem_params;
+ };
+
+ struct PotConstants {
+ ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemParams<
+ ::frc971::zeroing::RelativeEncoderZeroingEstimator>
+ subsystem_params;
+ double potentiometer_offset;
+ };
+};
+
+// Creates and returns a Values instance for the constants.
+// Should be called before realtime because this allocates memory.
+// Only the first call to either of these will be used.
+constants::Values MakeValues(uint16_t team);
+
+// Calls MakeValues with aos::network::GetTeamNumber()
+constants::Values MakeValues();
+
+} // namespace y2024_bot3::constants
+
+#endif // Y2024_BOT3_CONSTANTS_H_
diff --git a/y2024_bot3/constants/9971.json b/y2024_bot3/constants/9971.json
new file mode 100644
index 0000000..4eb1acf
--- /dev/null
+++ b/y2024_bot3/constants/9971.json
@@ -0,0 +1,35 @@
+{% from 'y2024_bot3/constants/common.jinja2' import arm_zero %}
+
+{
+ "cameras": [
+ {
+ "calibration": {% include 'y2024_bot3/constants/calib_files/calibration_imu-9971-0_cam-24-10_2024-02-24_16-44-05.json' %}
+ },
+ {
+ "calibration": {% include 'y2024_bot3/constants/calib_files/calibration_imu-9971-1_cam-24-12_2024-03-24_11-52-49.json' %}
+ },
+ {
+ "calibration": {% include 'y2024_bot3/constants/calib_files/calibration_orin1-9971-0_cam-24-09_2024-03-24_11-52-49.json' %}
+ },
+ {
+ "calibration": {% include 'y2024_bot3/constants/calib_files/calibration_orin1-9971-1_cam-24-11_2024-03-24_11-52-49.json' %}
+ }
+ ],
+ "robot": {
+ "arm_constants": {
+ {% set _ = arm_zero.update(
+ {
+ "measured_absolute_position" : 0.0992895926495078
+ }
+ ) %}
+ "zeroing_constants": {{ arm_zero | tojson(indent=2)}},
+ "potentiometer_offset": {{ 0 }},
+ "arm_positions": {
+ "intake": 0,
+ "idle": 1,
+ "amp": 2
+ }
+ }
+ },
+ {% include 'y2024_bot3/constants/common.json' %}
+}
diff --git a/y2024_bot3/constants/BUILD b/y2024_bot3/constants/BUILD
new file mode 100644
index 0000000..323bd49
--- /dev/null
+++ b/y2024_bot3/constants/BUILD
@@ -0,0 +1,108 @@
+load("//aos/flatbuffers:generate.bzl", "static_flatbuffer")
+load("//tools/build_rules:template.bzl", "jinja2_template")
+load("//y2024_bot3/constants:validator.bzl", "constants_json")
+
+cc_library(
+ name = "simulated_constants_sender",
+ srcs = ["simulated_constants_sender.cc"],
+ hdrs = ["simulated_constants_sender.h"],
+ data = [":test_constants.json"],
+ visibility = ["//y2024_bot3:__subpackages__"],
+ deps = [
+ ":constants_fbs",
+ ":constants_list_fbs",
+ "//aos/events:simulated_event_loop",
+ "//aos/testing:path",
+ "//frc971/constants:constants_sender_lib",
+ ],
+)
+
+jinja2_template(
+ name = "test_constants_unvalidated.json",
+ src = "test_constants.jinja2.json",
+ includes = glob([
+ "test_data/*.json",
+ ]) + [
+ "common.jinja2",
+ "common.json",
+ "//y2024_bot3/constants/calib_files",
+ "//y2024_bot3/control_loops/superstructure/arm:arm_json",
+ "//y2024_bot3/vision/maps",
+ ],
+ parameters = {},
+ visibility = ["//visibility:public"],
+)
+
+jinja2_template(
+ name = "constants_unvalidated.json",
+ src = "constants.jinja2.json",
+ includes = [
+ "9971.json",
+ "common.jinja2",
+ "common.json",
+ "//y2024_bot3/constants/calib_files",
+ "//y2024_bot3/control_loops/superstructure/arm:arm_json",
+ "//y2024_bot3/vision/maps",
+ ],
+ parameters = {},
+ visibility = ["//visibility:public"],
+)
+
+static_flatbuffer(
+ name = "constants_fbs",
+ srcs = ["constants.fbs"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//frc971/control_loops:profiled_subsystem_fbs",
+ "//frc971/vision:calibration_fbs",
+ "//frc971/vision:target_map_fbs",
+ "//frc971/zeroing:constants_fbs",
+ ],
+)
+
+static_flatbuffer(
+ name = "constants_list_fbs",
+ srcs = ["constants_list.fbs"],
+ visibility = ["//visibility:public"],
+ deps = [":constants_fbs"],
+)
+
+cc_binary(
+ name = "constants_sender",
+ srcs = ["constants_sender.cc"],
+ visibility = ["//visibility:public"],
+ deps = [
+ ":constants_fbs",
+ ":constants_list_fbs",
+ "//aos:init",
+ "//aos/events:shm_event_loop",
+ "//aos/testing:path",
+ "//frc971/constants:constants_sender_lib",
+ ],
+)
+
+cc_binary(
+ name = "constants_formatter",
+ srcs = ["constants_formatter.cc"],
+ data = [":constants_unvalidated.json"],
+ visibility = ["//visibility:public"],
+ deps = [
+ ":constants_list_fbs",
+ "//aos:init",
+ "//aos:json_to_flatbuffer",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
+ ],
+)
+
+constants_json(
+ name = "constants_json",
+ src = ":constants_unvalidated.json",
+ out = "constants.json",
+)
+
+constants_json(
+ name = "test_constants_json",
+ src = ":test_constants_unvalidated.json",
+ out = "test_constants.json",
+)
diff --git a/y2024_bot3/constants/calib_files/BUILD b/y2024_bot3/constants/calib_files/BUILD
new file mode 100644
index 0000000..1f33d50
--- /dev/null
+++ b/y2024_bot3/constants/calib_files/BUILD
@@ -0,0 +1,5 @@
+filegroup(
+ name = "calib_files",
+ srcs = glob(["*.json"]),
+ visibility = ["//visibility:public"],
+)
diff --git a/y2024_bot3/constants/calib_files/calibration_imu-9971-0_cam-24-10_2024-02-24_16-44-05.json b/y2024_bot3/constants/calib_files/calibration_imu-9971-0_cam-24-10_2024-02-24_16-44-05.json
new file mode 100755
index 0000000..e5f50e3
--- /dev/null
+++ b/y2024_bot3/constants/calib_files/calibration_imu-9971-0_cam-24-10_2024-02-24_16-44-05.json
@@ -0,0 +1,46 @@
+{
+ "node_name": "imu",
+ "team_number": 9971,
+ "intrinsics": [
+ 646.04834,
+ 0.0,
+ 703.327576,
+ 0.0,
+ 645.444458,
+ 527.86261,
+ 0.0,
+ 0.0,
+ 1.0
+ ],
+ "fixed_extrinsics": {
+ "data": [
+ 0.0,
+ -0.258819,
+ -0.965926,
+ -0.323293,
+ 1.0,
+ 0.0,
+ -0.0,
+ 0.268249,
+ 0.0,
+ -0.965926,
+ 0.258819,
+ 0.471129,
+ 0.0,
+ 0.0,
+ 0.0,
+ 1.0
+ ]
+ },
+ "dist_coeffs": [
+ -0.251594,
+ 0.064935,
+ 0.000479,
+ 0.000036,
+ -0.007207
+ ],
+ "calibration_timestamp": 1708821845975708672,
+ "camera_id": "24-10",
+ "camera_number": 0,
+ "reprojection_error": 1.523209
+}
diff --git a/y2024_bot3/constants/calib_files/calibration_imu-9971-1_cam-24-12_2024-03-24_11-52-49.json b/y2024_bot3/constants/calib_files/calibration_imu-9971-1_cam-24-12_2024-03-24_11-52-49.json
new file mode 100755
index 0000000..530e88a
--- /dev/null
+++ b/y2024_bot3/constants/calib_files/calibration_imu-9971-1_cam-24-12_2024-03-24_11-52-49.json
@@ -0,0 +1,46 @@
+{
+ "node_name": "imu",
+ "team_number": 9971,
+ "intrinsics": [
+ 647.19928,
+ 0.0,
+ 690.698181,
+ 0.0,
+ 646.449158,
+ 530.162842,
+ 0.0,
+ 0.0,
+ 1.0
+ ],
+ "fixed_extrinsics": {
+ "data": [
+ 0.99969,
+ 0.020217,
+ -0.014527,
+ 0.160342,
+ 0.009501,
+ 0.229548,
+ 0.973251,
+ 0.25208,
+ 0.023011,
+ -0.973088,
+ 0.229284,
+ 0.41504,
+ 0.0,
+ 0.0,
+ 0.0,
+ 1.0
+ ]
+ },
+ "dist_coeffs": [
+ -0.249799,
+ 0.062593,
+ 0.00003,
+ 0.000366,
+ -0.006532
+ ],
+ "calibration_timestamp": 1711306369592332476,
+ "camera_id": "24-12",
+ "camera_number": 1,
+ "reprojection_error": 1.23409
+}
\ No newline at end of file
diff --git a/y2024_bot3/constants/calib_files/calibration_orin1-9971-0_cam-24-09_2024-03-24_11-52-49.json b/y2024_bot3/constants/calib_files/calibration_orin1-9971-0_cam-24-09_2024-03-24_11-52-49.json
new file mode 100755
index 0000000..97234c9
--- /dev/null
+++ b/y2024_bot3/constants/calib_files/calibration_orin1-9971-0_cam-24-09_2024-03-24_11-52-49.json
@@ -0,0 +1,46 @@
+{
+ "node_name": "orin1",
+ "team_number": 9971,
+ "intrinsics": [
+ 648.187805,
+ 0.0,
+ 736.903137,
+ 0.0,
+ 648.028687,
+ 557.169861,
+ 0.0,
+ 0.0,
+ 1.0
+ ],
+ "fixed_extrinsics": {
+ "data": [
+ -0.999204,
+ -0.034711,
+ -0.019682,
+ 0.162103,
+ 0.028118,
+ -0.262536,
+ -0.964512,
+ -0.329348,
+ 0.028312,
+ -0.964298,
+ 0.263303,
+ 0.562319,
+ 0.0,
+ 0.0,
+ 0.0,
+ 1.0
+ ]
+ },
+ "dist_coeffs": [
+ -0.265564,
+ 0.078084,
+ -0.000231,
+ 0.000386,
+ -0.010425
+ ],
+ "calibration_timestamp": 1711306369593360533,
+ "camera_id": "24-09",
+ "camera_number": 0,
+ "reprojection_error": 1.881098
+}
\ No newline at end of file
diff --git a/y2024_bot3/constants/calib_files/calibration_orin1-9971-1_cam-24-11_2024-03-24_11-52-49.json b/y2024_bot3/constants/calib_files/calibration_orin1-9971-1_cam-24-11_2024-03-24_11-52-49.json
new file mode 100755
index 0000000..daef89c
--- /dev/null
+++ b/y2024_bot3/constants/calib_files/calibration_orin1-9971-1_cam-24-11_2024-03-24_11-52-49.json
@@ -0,0 +1,46 @@
+{
+ "node_name": "orin1",
+ "team_number": 9971,
+ "intrinsics": [
+ 649.866699,
+ 0.0,
+ 709.355713,
+ 0.0,
+ 648.893066,
+ 576.101868,
+ 0.0,
+ 0.0,
+ 1.0
+ ],
+ "fixed_extrinsics": {
+ "data": [
+ -0.014623,
+ 0.004459,
+ 0.999883,
+ 0.345385,
+ 0.997965,
+ 0.062137,
+ 0.014318,
+ 0.150131,
+ -0.062066,
+ 0.998058,
+ -0.005359,
+ 0.570236,
+ 0.0,
+ 0.0,
+ 0.0,
+ 1.0
+ ]
+ },
+ "dist_coeffs": [
+ -0.248092,
+ 0.060938,
+ 0.000313,
+ 0.00009,
+ -0.006163
+ ],
+ "calibration_timestamp": 1711306369592886702,
+ "camera_id": "24-11",
+ "camera_number": 1,
+ "reprojection_error": 1.450069
+}
\ No newline at end of file
diff --git a/y2024_bot3/constants/common.jinja2 b/y2024_bot3/constants/common.jinja2
new file mode 100644
index 0000000..809f8c8
--- /dev/null
+++ b/y2024_bot3/constants/common.jinja2
@@ -0,0 +1,16 @@
+{% set pi = 3.14159265 %}
+
+{%set zeroing_sample_size = 200 %}
+
+{# Arm #}
+{% set arm_encoder_ratio = (4.0 / 1.0) %}
+
+{%
+set arm_zero = {
+ "average_filter_size": zeroing_sample_size,
+ "one_revolution_distance": pi * 2.0 * arm_encoder_ratio,
+ "zeroing_threshold": 0.0005,
+ "moving_buffer_size": 20,
+ "allowable_encoder_error": 0.9
+}
+%}
diff --git a/y2024_bot3/constants/common.json b/y2024_bot3/constants/common.json
new file mode 100644
index 0000000..d5abec0
--- /dev/null
+++ b/y2024_bot3/constants/common.json
@@ -0,0 +1,21 @@
+"common": {
+ "arm": {
+ "zeroing_voltage": 3.0,
+ "operating_voltage": 12.0,
+ "zeroing_profile_params": {
+ "max_velocity": 0.5,
+ "max_acceleration": 3.0
+ },
+ "default_profile_params":{
+ "max_velocity": 2.0,
+ "max_acceleration": 10.0
+ },
+ "range": {
+ "lower_hard": -50,
+ "upper_hard": 50,
+ "lower": -50,
+ "upper": 50
+ },
+ "loop": {% include 'y2024_bot3/control_loops/superstructure/arm/integral_arm_plant.json' %}
+ }
+}
diff --git a/y2024_bot3/constants/constants.fbs b/y2024_bot3/constants/constants.fbs
new file mode 100644
index 0000000..99999bd
--- /dev/null
+++ b/y2024_bot3/constants/constants.fbs
@@ -0,0 +1,41 @@
+include "frc971/vision/calibration.fbs";
+include "frc971/vision/target_map.fbs";
+include "frc971/control_loops/profiled_subsystem.fbs";
+include "frc971/zeroing/constants.fbs";
+include "frc971/math/matrix.fbs";
+
+namespace y2024_bot3;
+
+table CameraConfiguration {
+ calibration:frc971.vision.calibration.CameraCalibration (id: 0);
+}
+
+table ArmPositions {
+ intake:double (id: 0);
+ idle:double (id: 1);
+ amp:double (id: 2);
+}
+
+table PotAndAbsEncoderConstants {
+ zeroing_constants:frc971.zeroing.PotAndAbsoluteEncoderZeroingConstants (id: 0);
+ potentiometer_offset:double (id: 1);
+ arm_positions:ArmPositions (id: 2);
+}
+
+table RobotConstants {
+ arm_constants:PotAndAbsEncoderConstants (id: 0);
+}
+
+// Common table for constants unrelated to the robot
+table Common {
+ target_map:frc971.vision.TargetMap (id: 0);
+ arm:frc971.control_loops.StaticZeroingSingleDOFProfiledSubsystemCommonParams (id: 1);
+}
+
+table Constants {
+ cameras:[CameraConfiguration] (id: 0);
+ robot:RobotConstants (id: 1);
+ common:Common (id: 2);
+}
+
+root_type Constants;
diff --git a/y2024_bot3/constants/constants.jinja2.json b/y2024_bot3/constants/constants.jinja2.json
new file mode 100644
index 0000000..63fad42
--- /dev/null
+++ b/y2024_bot3/constants/constants.jinja2.json
@@ -0,0 +1,8 @@
+{
+ "constants": [
+ {
+ "team": 9971,
+ "data": {% include 'y2024_bot3/constants/9971.json' %}
+ }
+ ]
+}
diff --git a/y2024_bot3/constants/constants_formatter.cc b/y2024_bot3/constants/constants_formatter.cc
new file mode 100644
index 0000000..4b2a601
--- /dev/null
+++ b/y2024_bot3/constants/constants_formatter.cc
@@ -0,0 +1,27 @@
+#include "absl/log/check.h"
+#include "absl/log/log.h"
+
+#include "aos/flatbuffers.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/util/file.h"
+#include "y2024_bot3/constants/constants_list_generated.h"
+
+int main(int argc, char **argv) {
+ ::aos::InitGoogle(&argc, &argv);
+
+ CHECK(argc == 3) << ": Expected input and output json files to be passed in.";
+
+ aos::FlatbufferDetachedBuffer<y2024_bot3::ConstantsList> constants =
+ aos::JsonFileToFlatbuffer<y2024_bot3::ConstantsList>(argv[1]);
+
+ // Make sure the file is valid json before we output a formatted version.
+ CHECK(constants.message().constants() != nullptr)
+ << ": Failed to parse " << std::string(argv[2]);
+
+ aos::util::WriteStringToFileOrDie(
+ std::string(argv[2]),
+ aos::FlatbufferToJson(constants, {.multi_line = true}));
+
+ return 0;
+}
diff --git a/y2024_bot3/constants/constants_list.fbs b/y2024_bot3/constants/constants_list.fbs
new file mode 100644
index 0000000..af2b49c
--- /dev/null
+++ b/y2024_bot3/constants/constants_list.fbs
@@ -0,0 +1,14 @@
+include "y2024_bot3/constants/constants.fbs";
+
+namespace y2024_bot3;
+
+table TeamAndConstants {
+ team:long (id: 0);
+ data:Constants (id: 1);
+}
+
+table ConstantsList {
+ constants:[TeamAndConstants] (id: 0);
+}
+
+root_type ConstantsList;
diff --git a/y2024_bot3/constants/constants_sender.cc b/y2024_bot3/constants/constants_sender.cc
new file mode 100644
index 0000000..d74f0d0
--- /dev/null
+++ b/y2024_bot3/constants/constants_sender.cc
@@ -0,0 +1,25 @@
+#include "absl/flags/flag.h"
+
+#include "aos/configuration.h"
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "frc971/constants/constants_sender_lib.h"
+#include "y2024_bot3/constants/constants_generated.h"
+#include "y2024_bot3/constants/constants_list_generated.h"
+
+ABSL_FLAG(std::string, config, "aos_config.json", "Path to the AOS config.");
+ABSL_FLAG(std::string, constants_path, "constants.json",
+ "Path to the constant file");
+
+int main(int argc, char **argv) {
+ aos::InitGoogle(&argc, &argv);
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
+ aos::ShmEventLoop event_loop(&config.message());
+ frc971::constants::ConstantSender<y2024_bot3::Constants,
+ y2024_bot3::ConstantsList>
+ constants_sender(&event_loop, absl::GetFlag(FLAGS_constants_path));
+ // Don't need to call Run().
+ return 0;
+}
diff --git a/y2024_bot3/constants/simulated_constants_sender.cc b/y2024_bot3/constants/simulated_constants_sender.cc
new file mode 100644
index 0000000..77d818a
--- /dev/null
+++ b/y2024_bot3/constants/simulated_constants_sender.cc
@@ -0,0 +1,23 @@
+#include "aos/events/simulated_event_loop.h"
+#include "aos/testing/path.h"
+#include "frc971/constants/constants_sender_lib.h"
+#include "y2024_bot3/constants/constants_generated.h"
+#include "y2024_bot3/constants/constants_list_generated.h"
+
+namespace y2024_bot3 {
+bool SendSimulationConstants(aos::SimulatedEventLoopFactory *factory, int team,
+ std::string constants_path,
+ const std::set<std::string_view> &node_names) {
+ for (const aos::Node *node : factory->nodes()) {
+ if (!node_names.empty() &&
+ !node_names.contains(node->name()->string_view())) {
+ continue;
+ }
+ std::unique_ptr<aos::EventLoop> event_loop =
+ factory->MakeEventLoop("constants_sender", node);
+ frc971::constants::ConstantSender<Constants, ConstantsList> sender(
+ event_loop.get(), constants_path, team, "/constants");
+ }
+ return true;
+}
+} // namespace y2024_bot3
diff --git a/y2024_bot3/constants/simulated_constants_sender.h b/y2024_bot3/constants/simulated_constants_sender.h
new file mode 100644
index 0000000..90b3724
--- /dev/null
+++ b/y2024_bot3/constants/simulated_constants_sender.h
@@ -0,0 +1,21 @@
+#ifndef Y2024_BOT3_CONSTANTS_SIMULATED_CONFIG_SENDER_H_
+#define Y2024_BOT3_CONSTANTS_SIMULATED_CONFIG_SENDER_H_
+
+#include <set>
+
+#include "aos/events/simulated_event_loop.h"
+#include "aos/testing/path.h"
+
+namespace y2024_bot3 {
+// Returns true, to allow this to be easily called in the initializer list of a
+// constructor.
+// If node_names is specified, we limit ourselves to sending constants on the
+// specified nodes.
+bool SendSimulationConstants(
+ aos::SimulatedEventLoopFactory *factory, int team,
+ std::string constants_path =
+ aos::testing::ArtifactPath("y2024_bot3/constants/test_constants.json"),
+ const std::set<std::string_view> &node_names = {});
+} // namespace y2024_bot3
+
+#endif // Y2024_BOT3_CONSTANTS_SIMULATED_CONFIG_SENDER_H_
diff --git a/y2024_bot3/constants/test_constants.jinja2.json b/y2024_bot3/constants/test_constants.jinja2.json
new file mode 100644
index 0000000..fdb764a
--- /dev/null
+++ b/y2024_bot3/constants/test_constants.jinja2.json
@@ -0,0 +1,8 @@
+{
+ "constants": [
+ {
+ "team": 9971,
+ "data": {% include 'y2024_bot3/constants/test_data/test_team.json' %}
+ }
+ ]
+}
diff --git a/y2024_bot3/constants/test_data/test_team.json b/y2024_bot3/constants/test_data/test_team.json
new file mode 100644
index 0000000..06286e7
--- /dev/null
+++ b/y2024_bot3/constants/test_data/test_team.json
@@ -0,0 +1,21 @@
+{% from 'y2024_bot3/constants/common.jinja2' import arm_zero %}
+
+{
+ "robot": {
+ "arm_constants": {
+ {% set _ = arm_zero.update(
+ {
+ "measured_absolute_position" : 0.0992895926495078
+ }
+ ) %}
+ "zeroing_constants": {{ arm_zero | tojson(indent=2)}},
+ "potentiometer_offset": {{ 0 }},
+ "arm_positions": {
+ "intake": 0,
+ "idle": 1,
+ "amp": 2
+ }
+ }
+ },
+ {% include 'y2024_bot3/constants/common.json' %}
+}
diff --git a/y2024_bot3/constants/validator.bzl b/y2024_bot3/constants/validator.bzl
new file mode 100644
index 0000000..7224e13
--- /dev/null
+++ b/y2024_bot3/constants/validator.bzl
@@ -0,0 +1,13 @@
+load("@aspect_bazel_lib//lib:run_binary.bzl", "run_binary")
+
+# Validates the constants.json file and outputs a formatted version.
+# TODO(max): Make this generic/template it out into frc971
+def constants_json(name, src, out):
+ run_binary(
+ name = name,
+ tool = "//y2024_bot3/constants:constants_formatter",
+ srcs = [src],
+ outs = [out],
+ args = ["$(location %s)" % (src)] + ["$(location %s)" % (out)],
+ visibility = ["//visibility:public"],
+ )
diff --git a/y2024_bot3/control_loops/BUILD b/y2024_bot3/control_loops/BUILD
new file mode 100644
index 0000000..55c0974
--- /dev/null
+++ b/y2024_bot3/control_loops/BUILD
@@ -0,0 +1,6 @@
+py_library(
+ name = "python_init",
+ srcs = ["__init__.py"],
+ visibility = ["//visibility:public"],
+ deps = ["//y2024_bot3:python_init"],
+)
diff --git a/y2024_bot3/control_loops/__init__.py b/y2024_bot3/control_loops/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2024_bot3/control_loops/__init__.py
diff --git a/y2024_bot3/control_loops/python/BUILD b/y2024_bot3/control_loops/python/BUILD
new file mode 100644
index 0000000..853719d
--- /dev/null
+++ b/y2024_bot3/control_loops/python/BUILD
@@ -0,0 +1,24 @@
+package(default_visibility = ["//y2024_bot3:__subpackages__"])
+
+py_library(
+ name = "python_init",
+ srcs = ["__init__.py"],
+ visibility = ["//visibility:public"],
+ deps = ["//y2024_bot3/control_loops:python_init"],
+)
+
+py_binary(
+ name = "arm",
+ srcs = [
+ "arm.py",
+ ],
+ legacy_create_init = False,
+ target_compatible_with = ["@platforms//cpu:x86_64"],
+ deps = [
+ ":python_init",
+ "//frc971/control_loops/python:controls",
+ "//frc971/control_loops/python:linear_system",
+ "@pip//glog",
+ "@pip//python_gflags",
+ ],
+)
diff --git a/y2024_bot3/control_loops/python/__init__.py b/y2024_bot3/control_loops/python/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2024_bot3/control_loops/python/__init__.py
diff --git a/y2024_bot3/control_loops/python/arm.py b/y2024_bot3/control_loops/python/arm.py
new file mode 100644
index 0000000..ef02be8
--- /dev/null
+++ b/y2024_bot3/control_loops/python/arm.py
@@ -0,0 +1,61 @@
+#!/usr/bin/python3
+
+from aos.util.trapezoid_profile import TrapezoidProfile
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import linear_system
+from frc971.control_loops.python import controls
+import numpy
+import sys
+from matplotlib import pylab
+import gflags
+import glog
+
+FLAGS = gflags.FLAGS
+
+try:
+ gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+except gflags.DuplicateFlagError:
+ pass
+
+gflags.DEFINE_bool('hybrid', False, 'If true, make it hybrid.')
+
+kArm = linear_system.LinearSystemParams(
+ name='Arm',
+ motor=control_loop.KrakenFOC(),
+ G=(14. / 60.) * (32. / 48.),
+ radius=36 * 0.005 / numpy.pi / 2.0,
+ mass=5.0,
+ q_pos=0.20,
+ q_vel=80.0,
+ kalman_q_pos=0.12,
+ kalman_q_vel=2.0,
+ kalman_q_voltage=8.0,
+ kalman_r_position=0.05,
+ dt=0.005,
+)
+
+
+def main(argv):
+ if FLAGS.plot:
+ R = numpy.matrix([[0.4], [0.0]])
+ linear_system.PlotKick(kArm, R)
+ linear_system.PlotMotion(kArm,
+ R,
+ max_velocity=2.0,
+ max_acceleration=15.0)
+ return
+
+ # Write the generated constants out to a file.
+ if len(argv) != 7:
+ glog.fatal(
+ 'Expected .h file name and .cc file name for the arm pivot and integral arm pivot.'
+ )
+ else:
+ namespaces = ['y2024_bot3', 'control_loops', 'superstructure', 'arm']
+ linear_system.WriteLinearSystem(kArm, argv[1:4], argv[4:7], namespaces)
+
+
+if __name__ == '__main__':
+ argv = FLAGS(sys.argv)
+ glog.init()
+ sys.exit(main(argv))
diff --git a/y2024_bot3/control_loops/superstructure/BUILD b/y2024_bot3/control_loops/superstructure/BUILD
new file mode 100644
index 0000000..bcac518
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/BUILD
@@ -0,0 +1,171 @@
+load("@com_github_google_flatbuffers//:typescript.bzl", "flatbuffer_ts_library")
+load("//aos/flatbuffers:generate.bzl", "static_flatbuffer")
+load("//tools/build_rules:js.bzl", "ts_project")
+
+package(default_visibility = ["//visibility:public"])
+
+static_flatbuffer(
+ name = "superstructure_goal_fbs",
+ srcs = [
+ "superstructure_goal.fbs",
+ ],
+ deps = [
+ "//frc971/control_loops:control_loops_fbs",
+ "//frc971/control_loops:profiled_subsystem_fbs",
+ ],
+)
+
+static_flatbuffer(
+ name = "superstructure_output_fbs",
+ srcs = [
+ "superstructure_output.fbs",
+ ],
+)
+
+static_flatbuffer(
+ name = "superstructure_status_fbs",
+ srcs = [
+ "superstructure_status.fbs",
+ ],
+ deps = [
+ "//frc971/control_loops:control_loops_fbs",
+ "//frc971/control_loops:profiled_subsystem_fbs",
+ ],
+)
+
+flatbuffer_ts_library(
+ name = "superstructure_status_ts_fbs",
+ srcs = [
+ "superstructure_status.fbs",
+ ],
+ deps = [
+ "//frc971/control_loops:control_loops_ts_fbs",
+ "//frc971/control_loops:profiled_subsystem_ts_fbs",
+ ],
+)
+
+static_flatbuffer(
+ name = "superstructure_position_fbs",
+ srcs = [
+ "superstructure_position.fbs",
+ ],
+ deps = [
+ "//frc971/control_loops:control_loops_fbs",
+ "//frc971/control_loops:profiled_subsystem_fbs",
+ ],
+)
+
+flatbuffer_ts_library(
+ name = "superstructure_position_ts_fbs",
+ srcs = [
+ "superstructure_position.fbs",
+ ],
+ deps = [
+ "//frc971/control_loops:control_loops_ts_fbs",
+ "//frc971/control_loops:profiled_subsystem_ts_fbs",
+ ],
+)
+
+static_flatbuffer(
+ name = "superstructure_can_position_fbs",
+ srcs = ["superstructure_can_position.fbs"],
+ deps = ["//frc971/control_loops:can_talonfx_fbs"],
+)
+
+flatbuffer_ts_library(
+ name = "superstructure_can_position_ts_fbs",
+ srcs = ["superstructure_can_position.fbs"],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = ["//frc971/control_loops:can_talonfx_ts_fbs"],
+)
+
+cc_library(
+ name = "superstructure_lib",
+ srcs = [
+ "superstructure.cc",
+ ],
+ hdrs = [
+ "superstructure.h",
+ ],
+ data = [],
+ deps = [
+ ":superstructure_goal_fbs",
+ ":superstructure_output_fbs",
+ ":superstructure_position_fbs",
+ ":superstructure_status_fbs",
+ "//aos:flatbuffer_merge",
+ "//aos/events:event_loop",
+ "//frc971/constants:constants_sender_lib",
+ "//frc971/control_loops:control_loop",
+ "//frc971/zeroing:absolute_encoder",
+ "//frc971/zeroing:pot_and_absolute_encoder",
+ "//y2024_bot3:constants",
+ "//y2024_bot3/constants:constants_fbs",
+ "//y2024_bot3/constants:simulated_constants_sender",
+ ],
+)
+
+cc_binary(
+ name = "superstructure",
+ srcs = [
+ "superstructure_main.cc",
+ ],
+ deps = [
+ ":superstructure_lib",
+ "//aos:init",
+ "//aos/events:shm_event_loop",
+ ],
+)
+
+cc_test(
+ name = "superstructure_lib_test",
+ srcs = [
+ "superstructure_lib_test.cc",
+ ],
+ data = [
+ "//y2024_bot3:aos_config",
+ ],
+ deps = [
+ ":superstructure_can_position_fbs",
+ ":superstructure_goal_fbs",
+ ":superstructure_lib",
+ ":superstructure_output_fbs",
+ ":superstructure_position_fbs",
+ ":superstructure_status_fbs",
+ "//aos:json_to_flatbuffer",
+ "//aos:math",
+ "//aos/events/logging:log_writer",
+ "//aos/testing:googletest",
+ "//aos/time",
+ "//frc971/control_loops:capped_test_plant",
+ "//frc971/control_loops:control_loop_test",
+ "//frc971/control_loops:position_sensor_sim",
+ "//frc971/control_loops:subsystem_simulator",
+ "//frc971/control_loops:team_number_test_environment",
+ "//y2024_bot3/control_loops/superstructure/arm:arm_plants",
+ ],
+)
+
+cc_binary(
+ name = "superstructure_replay",
+ srcs = ["superstructure_replay.cc"],
+ deps = [
+ ":superstructure_lib",
+ "//aos:configuration",
+ "//aos:init",
+ "//aos/events:simulated_event_loop",
+ "//aos/events/logging:log_reader",
+ "//aos/network:team_number",
+ ],
+)
+
+ts_project(
+ name = "superstructure_plotter",
+ srcs = ["superstructure_plotter.ts"],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ "//aos/network/www:aos_plotter",
+ "//aos/network/www:colors",
+ "//aos/network/www:proxy",
+ ],
+)
diff --git a/y2024_bot3/control_loops/superstructure/arm/BUILD b/y2024_bot3/control_loops/superstructure/arm/BUILD
new file mode 100644
index 0000000..d6d2fec
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/arm/BUILD
@@ -0,0 +1,42 @@
+package(default_visibility = ["//y2024_bot3:__subpackages__"])
+
+genrule(
+ name = "genrule_arm",
+ outs = [
+ "arm_plant.h",
+ "arm_plant.cc",
+ "arm_plant.json",
+ "integral_arm_plant.h",
+ "integral_arm_plant.cc",
+ "integral_arm_plant.json",
+ ],
+ cmd = "$(location //y2024_bot3/control_loops/python:arm) $(OUTS)",
+ target_compatible_with = ["@platforms//os:linux"],
+ tools = [
+ "//y2024_bot3/control_loops/python:arm",
+ ],
+)
+
+cc_library(
+ name = "arm_plants",
+ srcs = [
+ "arm_plant.cc",
+ "integral_arm_plant.cc",
+ ],
+ hdrs = [
+ "arm_plant.h",
+ "integral_arm_plant.h",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//frc971/control_loops:hybrid_state_feedback_loop",
+ "//frc971/control_loops:state_feedback_loop",
+ ],
+)
+
+filegroup(
+ name = "arm_json",
+ srcs = ["integral_arm_plant.json"],
+ visibility = ["//visibility:public"],
+)
diff --git a/y2024_bot3/control_loops/superstructure/superstructure.cc b/y2024_bot3/control_loops/superstructure/superstructure.cc
new file mode 100644
index 0000000..2c510ad
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure.cc
@@ -0,0 +1,111 @@
+#include "y2024_bot3/control_loops/superstructure/superstructure.h"
+
+#include <chrono>
+
+#include "aos/events/event_loop.h"
+#include "aos/flatbuffer_merge.h"
+#include "aos/network/team_number.h"
+#include "aos/time/time.h"
+#include "frc971/zeroing/wrap.h"
+
+ABSL_FLAG(bool, ignore_distance, false,
+ "If true, ignore distance when shooting and obey joystick_reader");
+
+namespace y2024_bot3::control_loops::superstructure {
+
+using ::aos::monotonic_clock;
+
+using frc971::control_loops::AbsoluteEncoderProfiledJointStatus;
+using frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus;
+using frc971::control_loops::RelativeEncoderProfiledJointStatus;
+
+Superstructure::Superstructure(::aos::EventLoop *event_loop,
+ const ::std::string &name)
+ : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+ name),
+ constants_fetcher_(event_loop),
+ robot_constants_(&constants_fetcher_.constants()),
+ joystick_state_fetcher_(
+ event_loop->MakeFetcher<aos::JoystickState>("/aos")),
+ arm_(robot_constants_->common()->arm(),
+ robot_constants_->robot()->arm_constants()->zeroing_constants()) {
+ event_loop->SetRuntimeRealtimePriority(30);
+}
+
+bool PositionNear(double position, double goal, double threshold) {
+ return std::abs(position - goal) < threshold;
+}
+
+void Superstructure::RunIteration(const Goal *unsafe_goal,
+ const Position *position,
+ aos::Sender<Output>::Builder *output,
+ aos::Sender<Status>::Builder *status) {
+ if (WasReset()) {
+ AOS_LOG(ERROR, "WPILib reset, restarting\n");
+ }
+
+ OutputT output_struct;
+
+ if (joystick_state_fetcher_.Fetch() &&
+ joystick_state_fetcher_->has_alliance()) {
+ alliance_ = joystick_state_fetcher_->alliance();
+ }
+
+ aos::FlatbufferFixedAllocatorArray<
+ frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal, 512>
+ arm_goal_buffer;
+
+ ArmStatus arm_status = ArmStatus::IDLE;
+ double arm_position =
+ robot_constants_->robot()->arm_constants()->arm_positions()->idle();
+ if (unsafe_goal != nullptr) {
+ switch (unsafe_goal->arm_position()) {
+ case PivotGoal::INTAKE:
+ arm_status = ArmStatus::INTAKE;
+ arm_position = robot_constants_->robot()
+ ->arm_constants()
+ ->arm_positions()
+ ->intake();
+ break;
+ case PivotGoal::AMP:
+ arm_status = ArmStatus::AMP;
+ arm_position =
+ robot_constants_->robot()->arm_constants()->arm_positions()->amp();
+ break;
+ default:
+ arm_position =
+ robot_constants_->robot()->arm_constants()->arm_positions()->idle();
+ }
+ }
+
+ arm_goal_buffer.Finish(
+ frc971::control_loops::CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *arm_goal_buffer.fbb(), arm_position));
+
+ const frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal
+ *arm_goal = &arm_goal_buffer.message();
+
+ // static_zeroing_single_dof_profiled_subsystem.h
+ const flatbuffers::Offset<PotAndAbsoluteEncoderProfiledJointStatus>
+ arm_offset =
+ arm_.Iterate(arm_goal, position->arm(),
+ output != nullptr ? &output_struct.arm_voltage : nullptr,
+ status->fbb());
+
+ if (output) {
+ output->CheckOk(output->Send(Output::Pack(*output->fbb(), &output_struct)));
+ }
+
+ Status::Builder status_builder = status->MakeBuilder<Status>();
+
+ const bool zeroed = arm_.zeroed();
+ const bool estopped = arm_.estopped();
+
+ status_builder.add_zeroed(zeroed);
+ status_builder.add_estopped(estopped);
+ status_builder.add_arm(arm_offset);
+ status_builder.add_arm_status(arm_status);
+
+ (void)status->Send(status_builder.Finish());
+}
+} // namespace y2024_bot3::control_loops::superstructure
diff --git a/y2024_bot3/control_loops/superstructure/superstructure.h b/y2024_bot3/control_loops/superstructure/superstructure.h
new file mode 100644
index 0000000..b7499c2
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure.h
@@ -0,0 +1,59 @@
+#ifndef Y2024_BOT3_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
+#define Y2024_BOT3_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
+
+#include "aos/events/event_loop.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/time/time.h"
+#include "frc971/constants/constants_sender_lib.h"
+#include "frc971/control_loops/control_loop.h"
+#include "frc971/zeroing/absolute_encoder.h"
+#include "frc971/zeroing/pot_and_absolute_encoder.h"
+#include "y2024_bot3/constants.h"
+#include "y2024_bot3/constants/constants_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_goal_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_output_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_position_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_status_generated.h"
+
+namespace y2024_bot3::control_loops::superstructure {
+
+class Superstructure
+ : public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
+ public:
+ using AbsoluteEncoderSubsystem =
+ ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystem<
+ ::frc971::zeroing::AbsoluteEncoderZeroingEstimator,
+ ::frc971::control_loops::AbsoluteEncoderProfiledJointStatus>;
+
+ using PotAndAbsoluteEncoderSubsystem =
+ ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystem<
+ ::frc971::zeroing::PotAndAbsoluteEncoderZeroingEstimator,
+ ::frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus>;
+
+ explicit Superstructure(::aos::EventLoop *event_loop,
+ const ::std::string &name = "/superstructure");
+
+ double robot_velocity() const;
+
+ inline const PotAndAbsoluteEncoderSubsystem &arm() const { return arm_; }
+
+ protected:
+ virtual void RunIteration(const Goal *unsafe_goal, const Position *position,
+ aos::Sender<Output>::Builder *output,
+ aos::Sender<Status>::Builder *status) override;
+
+ private:
+ frc971::constants::ConstantsFetcher<Constants> constants_fetcher_;
+ const Constants *robot_constants_;
+ aos::Fetcher<aos::JoystickState> joystick_state_fetcher_;
+
+ aos::Alliance alliance_ = aos::Alliance::kInvalid;
+
+ PotAndAbsoluteEncoderSubsystem arm_;
+
+ DISALLOW_COPY_AND_ASSIGN(Superstructure);
+};
+
+} // namespace y2024_bot3::control_loops::superstructure
+
+#endif // Y2024_BOT3_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_can_position.fbs b/y2024_bot3/control_loops/superstructure/superstructure_can_position.fbs
new file mode 100644
index 0000000..d34cd9b
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_can_position.fbs
@@ -0,0 +1,22 @@
+include "frc971/control_loops/can_talonfx.fbs";
+
+namespace y2024_bot3.control_loops.superstructure;
+
+table CANPosition {
+ // The timestamp of the measurement on the canivore clock in nanoseconds
+ // This will have less jitter than the
+ // timestamp of the message being sent out.
+ timestamp:int64 (id: 0, deprecated);
+
+ // The ctre::phoenix::StatusCode of the measurement
+ // Should be OK = 0
+ status:int (id: 1);
+
+ // CAN Position of the roller falcon
+ intake_roller:frc971.control_loops.CANTalonFX (id: 2);
+
+ // CAN Position of the arm pivot falcon
+ arm_pivot:frc971.control_loops.CANTalonFX (id: 3);
+}
+
+root_type CANPosition;
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_goal.fbs b/y2024_bot3/control_loops/superstructure/superstructure_goal.fbs
new file mode 100644
index 0000000..66ecfdf
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_goal.fbs
@@ -0,0 +1,34 @@
+include "frc971/control_loops/profiled_subsystem.fbs";
+
+namespace y2024_bot3.control_loops.superstructure;
+
+// Represents goal for the intake rollers
+// INTAKE will turn on the rollers to intake the note.
+// SCORE will turn on the rollers to shoot the note.
+// SPIT will turn on the rollers (in reverse) to spit out the note.
+enum IntakeGoal : ubyte {
+ NONE = 0,
+ INTAKE = 1,
+ SCORE = 2,
+ SPIT = 3,
+}
+
+// Represents goal for the intake arm
+// IDLE will place the arm at the resting position.
+// INTAKE will place the arm at the intake position.
+// AMP will place the arm at the amp scoring position.
+enum PivotGoal: ubyte {
+ IDLE = 0,
+ INTAKE = 1,
+ AMP = 2,
+}
+
+table Goal {
+ // Intake roller goal
+ roller_goal: IntakeGoal = NONE (id: 0);
+
+ // Arm position goal
+ arm_position: PivotGoal (id: 1);
+}
+
+root_type Goal;
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_lib_test.cc b/y2024_bot3/control_loops/superstructure/superstructure_lib_test.cc
new file mode 100644
index 0000000..d9f684c
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_lib_test.cc
@@ -0,0 +1,339 @@
+#include <chrono>
+#include <memory>
+
+#include "absl/flags/flag.h"
+#include "gtest/gtest.h"
+
+#include "aos/events/logging/log_writer.h"
+#include "frc971/control_loops/capped_test_plant.h"
+#include "frc971/control_loops/control_loop_test.h"
+#include "frc971/control_loops/position_sensor_sim.h"
+#include "frc971/control_loops/subsystem_simulator.h"
+#include "frc971/control_loops/team_number_test_environment.h"
+#include "frc971/zeroing/absolute_encoder.h"
+#include "y2024_bot3/constants/simulated_constants_sender.h"
+#include "y2024_bot3/control_loops/superstructure/arm/arm_plant.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_can_position_generated.h"
+
+ABSL_FLAG(std::string, output_folder, "",
+ "If set, logs all channels to the provided logfile.");
+
+namespace y2024_bot3::control_loops::superstructure::testing {
+
+namespace chrono = std::chrono;
+
+using ::aos::monotonic_clock;
+using ::frc971::CreateProfileParameters;
+using ::frc971::control_loops::CappedTestPlant;
+using ::frc971::control_loops::
+ CreateStaticZeroingSingleDOFProfiledSubsystemGoal;
+using ::frc971::control_loops::PositionSensorSimulator;
+using ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
+typedef Superstructure::PotAndAbsoluteEncoderSubsystem
+ PotAndAbsoluteEncoderSubsystem;
+typedef Superstructure::AbsoluteEncoderSubsystem AbsoluteEncoderSubsystem;
+using PotAndAbsoluteEncoderSimulator =
+ frc971::control_loops::SubsystemSimulator<
+ frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus,
+ PotAndAbsoluteEncoderSubsystem::State,
+ constants::Values::PotAndAbsEncoderConstants>;
+using AbsoluteEncoderSimulator = frc971::control_loops::SubsystemSimulator<
+ frc971::control_loops::AbsoluteEncoderProfiledJointStatus,
+ AbsoluteEncoderSubsystem::State,
+ constants::Values::AbsoluteEncoderConstants>;
+
+class SuperstructureSimulation {
+ public:
+ SuperstructureSimulation(::aos::EventLoop *event_loop,
+ const Constants *simulated_robot_constants,
+ chrono::nanoseconds dt)
+ : event_loop_(event_loop),
+ dt_(dt),
+ superstructure_position_sender_(
+ event_loop_->MakeSender<Position>("/superstructure")),
+ superstructure_can_position_sender_(
+ event_loop_->MakeSender<CANPosition>("/superstructure/rio")),
+ superstructure_status_fetcher_(
+ event_loop_->MakeFetcher<Status>("/superstructure")),
+ superstructure_output_fetcher_(
+ event_loop_->MakeFetcher<Output>("/superstructure")),
+ arm_(new CappedTestPlant(arm::MakeArmPlant()),
+ PositionSensorSimulator(simulated_robot_constants->robot()
+ ->arm_constants()
+ ->zeroing_constants()
+ ->one_revolution_distance()),
+ {.subsystem_params = {simulated_robot_constants->common()->arm(),
+ simulated_robot_constants->robot()
+ ->arm_constants()
+ ->zeroing_constants()},
+ .potentiometer_offset = simulated_robot_constants->robot()
+ ->arm_constants()
+ ->potentiometer_offset()},
+ frc971::constants::Range::FromFlatbuffer(
+ simulated_robot_constants->common()->arm()->range()),
+ simulated_robot_constants->robot()
+ ->arm_constants()
+ ->zeroing_constants()
+ ->measured_absolute_position(),
+ dt_)
+
+ {
+ phased_loop_handle_ = event_loop_->AddPhasedLoop(
+ [this](int) {
+ // Skip this the first time.
+ if (!first_) {
+ EXPECT_TRUE(superstructure_output_fetcher_.Fetch());
+ EXPECT_TRUE(superstructure_status_fetcher_.Fetch());
+ }
+ first_ = false;
+ SendPositionMessage();
+ },
+ dt);
+ }
+
+ // Sends a queue message with the position of the superstructure.
+ void SendPositionMessage() {
+ ::aos::Sender<Position>::Builder builder =
+ superstructure_position_sender_.MakeBuilder();
+
+ frc971::PotAndAbsolutePosition::Builder arm_builder =
+ builder.MakeBuilder<frc971::PotAndAbsolutePosition>();
+ flatbuffers::Offset<frc971::PotAndAbsolutePosition> arm_offset =
+ arm_.encoder()->GetSensorValues(&arm_builder);
+
+ Position::Builder position_builder = builder.MakeBuilder<Position>();
+
+ position_builder.add_arm(arm_offset);
+
+ CHECK_EQ(builder.Send(position_builder.Finish()),
+ aos::RawSender::Error::kOk);
+ }
+
+ private:
+ ::aos::EventLoop *event_loop_;
+ const chrono::nanoseconds dt_;
+ ::aos::PhasedLoopHandler *phased_loop_handle_ = nullptr;
+
+ ::aos::Sender<Position> superstructure_position_sender_;
+ ::aos::Sender<CANPosition> superstructure_can_position_sender_;
+ ::aos::Fetcher<Status> superstructure_status_fetcher_;
+ ::aos::Fetcher<Output> superstructure_output_fetcher_;
+
+ PotAndAbsoluteEncoderSimulator arm_;
+
+ bool first_ = true;
+};
+
+class SuperstructureTest : public ::frc971::testing::ControlLoopTest {
+ public:
+ SuperstructureTest()
+ : ::frc971::testing::ControlLoopTest(
+ aos::configuration::ReadConfig("y2024_bot3/aos_config.json"),
+ std::chrono::microseconds(5000)),
+ simulated_constants_dummy_(SendSimulationConstants(
+ event_loop_factory(), 9971,
+ "y2024_bot3/constants/test_constants.json")),
+ roborio_(aos::configuration::GetNode(configuration(), "roborio")),
+ logger_pi_(aos::configuration::GetNode(configuration(), "logger")),
+ superstructure_event_loop(MakeEventLoop("Superstructure", roborio_)),
+ superstructure_(superstructure_event_loop.get()),
+ test_event_loop_(MakeEventLoop("test", roborio_)),
+ constants_fetcher_(test_event_loop_.get()),
+ simulated_robot_constants_(&constants_fetcher_.constants()),
+ superstructure_goal_fetcher_(
+ test_event_loop_->MakeFetcher<Goal>("/superstructure")),
+ superstructure_goal_sender_(
+ test_event_loop_->MakeSender<Goal>("/superstructure")),
+ superstructure_status_fetcher_(
+ test_event_loop_->MakeFetcher<Status>("/superstructure")),
+ superstructure_output_fetcher_(
+ test_event_loop_->MakeFetcher<Output>("/superstructure")),
+ superstructure_position_fetcher_(
+ test_event_loop_->MakeFetcher<Position>("/superstructure")),
+ superstructure_position_sender_(
+ test_event_loop_->MakeSender<Position>("/superstructure")),
+ superstructure_can_position_sender_(
+ test_event_loop_->MakeSender<CANPosition>("/superstructure/rio")),
+ superstructure_plant_event_loop_(MakeEventLoop("plant", roborio_)),
+ superstructure_plant_(superstructure_plant_event_loop_.get(),
+ simulated_robot_constants_, dt()) {
+ set_team_id(frc971::control_loops::testing::kTeamNumber);
+
+ SetEnabled(true);
+
+ if (!absl::GetFlag(FLAGS_output_folder).empty()) {
+ unlink(absl::GetFlag(FLAGS_output_folder).c_str());
+ logger_event_loop_ = MakeEventLoop("logger", roborio_);
+ logger_ = std::make_unique<aos::logger::Logger>(logger_event_loop_.get());
+ logger_->StartLoggingOnRun(absl::GetFlag(FLAGS_output_folder));
+ }
+ }
+
+ void VerifyNearGoal() {
+ superstructure_goal_fetcher_.Fetch();
+ superstructure_status_fetcher_.Fetch();
+ superstructure_output_fetcher_.Fetch();
+
+ ASSERT_FALSE(superstructure_status_fetcher_->estopped());
+
+ ASSERT_TRUE(superstructure_goal_fetcher_.get() != nullptr) << ": No goal";
+ ASSERT_TRUE(superstructure_status_fetcher_.get() != nullptr)
+ << ": No status";
+ ASSERT_TRUE(superstructure_output_fetcher_.get() != nullptr)
+ << ": No output";
+
+ double set_point;
+ auto arm_positions =
+ simulated_robot_constants_->robot()->arm_constants()->arm_positions();
+
+ switch (superstructure_goal_fetcher_->arm_position()) {
+ case PivotGoal::IDLE:
+ set_point = arm_positions->idle();
+ break;
+ case PivotGoal::INTAKE:
+ set_point = arm_positions->intake();
+ break;
+ case PivotGoal::AMP:
+ set_point = arm_positions->amp();
+ break;
+ default:
+ LOG(FATAL) << "PivotGoal is not IDLE, INTAKE, or AMP";
+ }
+
+ EXPECT_NEAR(
+ set_point,
+ superstructure_status_fetcher_->arm()->unprofiled_goal_position(),
+ 0.03);
+ }
+
+ void CheckIfZeroed() {
+ superstructure_status_fetcher_.Fetch();
+ ASSERT_TRUE(superstructure_status_fetcher_.get()->zeroed());
+ }
+
+ void WaitUntilZeroed() {
+ int i = 0;
+ do {
+ i++;
+ RunFor(dt());
+ superstructure_status_fetcher_.Fetch();
+ // 2 Seconds
+
+ ASSERT_LE(i, 2.0 / ::aos::time::DurationInSeconds(dt()));
+
+ // Since there is a delay when sending running, make sure we have a
+ // status before checking it.
+ } while (superstructure_status_fetcher_.get() == nullptr ||
+ !superstructure_status_fetcher_.get()->zeroed());
+ }
+
+ void WaitUntilNear() {}
+
+ const bool simulated_constants_dummy_;
+
+ const aos::Node *const roborio_;
+ const aos::Node *const logger_pi_;
+
+ ::std::unique_ptr<::aos::EventLoop> superstructure_event_loop;
+ ::y2024_bot3::control_loops::superstructure::Superstructure superstructure_;
+ ::std::unique_ptr<::aos::EventLoop> test_event_loop_;
+ ::aos::PhasedLoopHandler *phased_loop_handle_ = nullptr;
+
+ frc971::constants::ConstantsFetcher<Constants> constants_fetcher_;
+ const Constants *simulated_robot_constants_;
+
+ ::aos::Fetcher<Goal> superstructure_goal_fetcher_;
+ ::aos::Sender<Goal> superstructure_goal_sender_;
+ ::aos::Fetcher<Status> superstructure_status_fetcher_;
+ ::aos::Fetcher<Output> superstructure_output_fetcher_;
+ ::aos::Fetcher<Position> superstructure_position_fetcher_;
+ ::aos::Sender<Position> superstructure_position_sender_;
+ ::aos::Sender<CANPosition> superstructure_can_position_sender_;
+
+ ::std::unique_ptr<::aos::EventLoop> superstructure_plant_event_loop_;
+ SuperstructureSimulation superstructure_plant_;
+
+ std::unique_ptr<aos::EventLoop> logger_event_loop_;
+ std::unique_ptr<aos::logger::Logger> logger_;
+
+ const ::std::vector<::Eigen::Matrix<double, 3, 1>> points_;
+};
+
+// Tests that the superstructure does nothing when the goal is to remain
+// still.
+TEST_F(SuperstructureTest, DoesNothing) {
+ SetEnabled(true);
+ WaitUntilZeroed();
+
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+
+ ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
+ }
+ RunFor(chrono::seconds(10));
+
+ VerifyNearGoal();
+}
+
+// Tests that the loop zeroes when run for a while without a goal.
+TEST_F(SuperstructureTest, ZeroNoGoal) {
+ SetEnabled(true);
+ WaitUntilZeroed();
+ RunFor(chrono::seconds(2));
+}
+
+// Tests that running disabled works
+TEST_F(SuperstructureTest, DisableTest) {
+ RunFor(chrono::seconds(2));
+ CheckIfZeroed();
+}
+
+TEST_F(SuperstructureTest, ArmPivotMovement) {
+ SetEnabled(true);
+ WaitUntilZeroed();
+
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+ goal_builder.add_arm_position(PivotGoal::INTAKE);
+
+ ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
+ }
+ RunFor(chrono::seconds(20));
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_status_fetcher_->arm_status(), ArmStatus::INTAKE);
+
+ VerifyNearGoal();
+
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+ goal_builder.add_arm_position(PivotGoal::AMP);
+
+ ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
+ }
+ RunFor(chrono::seconds(10));
+
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_status_fetcher_->arm_status(), ArmStatus::AMP);
+
+ VerifyNearGoal();
+
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+ goal_builder.add_arm_position(PivotGoal::IDLE);
+
+ ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
+ }
+ RunFor(chrono::seconds(10));
+
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_status_fetcher_->arm_status(), ArmStatus::IDLE);
+
+ VerifyNearGoal();
+}
+
+} // namespace y2024_bot3::control_loops::superstructure::testing
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_main.cc b/y2024_bot3/control_loops/superstructure/superstructure_main.cc
new file mode 100644
index 0000000..a7d048c
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_main.cc
@@ -0,0 +1,25 @@
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure.h"
+
+ABSL_FLAG(std::string, arm_trajectories, "arm_trajectories_generated.bfbs",
+ "The path to the generated arm trajectories bfbs file.");
+
+using y2024_bot3::control_loops::superstructure::Superstructure;
+
+int main(int argc, char **argv) {
+ ::aos::InitGoogle(&argc, &argv);
+
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig("aos_config.json");
+
+ ::aos::ShmEventLoop event_loop(&config.message());
+
+ frc971::constants::WaitForConstants<y2024_bot3::Constants>(&config.message());
+
+ Superstructure superstructure(&event_loop);
+
+ event_loop.Run();
+
+ return 0;
+}
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_output.fbs b/y2024_bot3/control_loops/superstructure/superstructure_output.fbs
new file mode 100644
index 0000000..faaa21e
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_output.fbs
@@ -0,0 +1,11 @@
+namespace y2024_bot3.control_loops.superstructure;
+
+table Output {
+ // Roller voltage, positive is for intake and scoring
+ roller_voltage: double (id: 0);
+
+ // Arm voltage, positive is moving arm up
+ arm_voltage: double (id: 1);
+}
+
+root_type Output;
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_plotter.ts b/y2024_bot3/control_loops/superstructure/superstructure_plotter.ts
new file mode 100644
index 0000000..f3c90aa
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_plotter.ts
@@ -0,0 +1,117 @@
+// Provides a plot for debugging robot state-related issues.
+import {AosPlotter, MessageHandler} from '../../../aos/network/www/aos_plotter';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from '../../../aos/network/www/colors';
+import * as proxy from '../../../aos/network/www/proxy';
+
+import Connection = proxy.Connection;
+
+const TIME = AosPlotter.TIME;
+const DEFAULT_WIDTH = AosPlotter.DEFAULT_WIDTH * 2;
+const DEFAULT_HEIGHT = AosPlotter.DEFAULT_HEIGHT * 1;
+
+// plot static zeroing single dof subsystem (generic function used by specific subsystem plotters)
+function plotSzsdofSubsystem(
+ name: string, plotter: AosPlotter, element: Element, position: MessageHandler, positionName: string,
+ status: MessageHandler, statusName: string, output: MessageHandler, outputName: string, hasPot:boolean = true): void {
+ {
+ const positionPlot =
+ plotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
+ positionPlot.plot.getAxisLabels().setTitle(name + ' Position');
+ positionPlot.plot.getAxisLabels().setXLabel(TIME);
+ positionPlot.plot.getAxisLabels().setYLabel('Position [rad,m]');
+ positionPlot.addMessageLine(position, [positionName, 'encoder'])
+ .setColor(RED);
+ positionPlot.addMessageLine(position, [positionName, 'absolute_encoder'])
+ .setColor(GREEN);
+ if (hasPot) {
+ positionPlot.addMessageLine(position, [positionName, 'pot'])
+ .setColor(BLUE);
+ }
+ positionPlot
+ .addMessageLine(status, [statusName, 'estimator_state', 'position'])
+ .setColor(BROWN);
+ positionPlot.addMessageLine(status, [statusName, 'position'])
+ .setColor(WHITE);
+ }
+ {
+ const statesPlot =
+ plotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ statesPlot.plot.getAxisLabels().setTitle(name + ' State');
+ statesPlot.plot.getAxisLabels().setXLabel(TIME);
+ statesPlot.plot.getAxisLabels().setYLabel('[bool,ZeroingError]');
+ statesPlot.addMessageLine(status, [statusName, 'estopped']).setColor(RED);
+ statesPlot.addMessageLine(status, [statusName, 'zeroed']).setColor(GREEN);
+ statesPlot
+ .addMessageLine(status, [statusName, 'estimator_state', 'errors[]'])
+ .setColor(BLUE)
+ .setDrawLine(false);
+ }
+ {
+ const positionConvergencePlot =
+ plotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
+ positionConvergencePlot.plot.getAxisLabels().setTitle(name + ' Position Goals');
+ positionConvergencePlot.plot.getAxisLabels().setXLabel(TIME);
+ positionConvergencePlot.plot.getAxisLabels().setYLabel('[rad,m]');
+ positionConvergencePlot.addMessageLine(status, [statusName, 'position'])
+ .setColor(RED);
+ positionConvergencePlot.addMessageLine(status, [statusName, 'goal_position'])
+ .setColor(GREEN);
+ positionConvergencePlot
+ .addMessageLine(status, [statusName, 'unprofiled_goal_position'])
+ .setColor(BROWN);
+ }
+ {
+ const velocityConvergencePlot =
+ plotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
+ velocityConvergencePlot.plot.getAxisLabels().setTitle(name + ' Velocity Goals');
+ velocityConvergencePlot.plot.getAxisLabels().setXLabel(TIME);
+ velocityConvergencePlot.plot.getAxisLabels().setYLabel('[rad,m]');
+ velocityConvergencePlot.addMessageLine(status, [statusName, 'velocity'])
+ .setColor(RED);
+ velocityConvergencePlot.addMessageLine(status, [statusName, 'calculated_velocity'])
+ .setColor(RED).setDrawLine(false);
+ velocityConvergencePlot.addMessageLine(status, [statusName, 'goal_velocity'])
+ .setColor(GREEN);
+ velocityConvergencePlot
+ .addMessageLine(status, [statusName, 'unprofiled_goal_velocity'])
+ .setColor(BROWN);
+ }
+ {
+ const outputPlot =
+ plotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
+ outputPlot.plot.getAxisLabels().setTitle(name + ' Outputs');
+ outputPlot.plot.getAxisLabels().setXLabel(TIME);
+ outputPlot.plot.getAxisLabels().setYLabel('[volts]');
+ outputPlot.addMessageLine(output, [outputName])
+ .setColor(RED);
+ outputPlot.addMessageLine(status, [statusName, 'voltage_error'])
+ .setColor(GREEN);
+ outputPlot.addMessageLine(status, [statusName, 'position_power'])
+ .setColor(BLUE);
+ outputPlot.addMessageLine(status, [statusName, 'velocity_power'])
+ .setColor(BROWN);
+ outputPlot.addMessageLine(status, [statusName, 'feedforwards_power'])
+ .setColor(WHITE);
+ }
+}
+
+export function plotSuperstructure(conn: Connection, element: Element): void {
+ const aosPlotter = new AosPlotter(conn);
+ const status = aosPlotter.addMessageSource(
+ '/superstructure', 'y2024_bot3.control_loops.superstructure.Status');
+ const robotState = aosPlotter.addMessageSource('/aos', 'aos.RobotState');
+
+ {
+ const robotStatePlot =
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT]);
+ robotStatePlot.plot.getAxisLabels().setTitle('Robot State Plot');
+ robotStatePlot.plot.getAxisLabels().setXLabel(TIME);
+ robotStatePlot.plot.getAxisLabels().setYLabel('[bool]');
+ robotStatePlot.addMessageLine(robotState, ['outputs_enabled'])
+ .setColor(RED);
+ robotStatePlot.addMessageLine(status, ['zeroed'])
+ .setColor(GREEN);
+ robotStatePlot.addMessageLine(status, ['estopped'])
+ .setColor(BLUE);
+ }
+}
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_position.fbs b/y2024_bot3/control_loops/superstructure/superstructure_position.fbs
new file mode 100644
index 0000000..6f2614b
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_position.fbs
@@ -0,0 +1,14 @@
+include "frc971/control_loops/control_loops.fbs";
+include "frc971/control_loops/profiled_subsystem.fbs";
+
+namespace y2024_bot3.control_loops.superstructure;
+
+table Position {
+ // Zero for the intake position value is horizontal, positive is up.
+ arm:frc971.PotAndAbsolutePosition (id: 0);
+
+ // Beambreak for the intake, 1 means note is present.
+ intake_beambreak:bool (id: 1);
+}
+
+root_type Position;
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_replay.cc b/y2024_bot3/control_loops/superstructure/superstructure_replay.cc
new file mode 100644
index 0000000..1058f4f
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_replay.cc
@@ -0,0 +1,75 @@
+// This binary allows us to replay the superstructure code over existing
+// logfile. When you run this code, it generates a new logfile with the data all
+// replayed, so that it can then be run through the plotting tool or analyzed
+// in some other way. The original superstructure status data will be on the
+// /original/superstructure channel.
+#include "absl/flags/flag.h"
+
+#include "aos/events/logging/log_reader.h"
+#include "aos/events/logging/log_writer.h"
+#include "aos/events/simulated_event_loop.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/logging/log_message_generated.h"
+#include "aos/network/team_number.h"
+#include "y2024_bot3/constants.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure.h"
+
+ABSL_FLAG(int32_t, team, 971, "Team number to use for logfile replay.");
+ABSL_FLAG(std::string, output_folder, "/tmp/superstructure_replay/",
+ "Logs all channels to the provided logfile.");
+
+int main(int argc, char **argv) {
+ aos::InitGoogle(&argc, &argv);
+
+ aos::network::OverrideTeamNumber(absl::GetFlag(FLAGS_team));
+
+ // open logfiles
+ aos::logger::LogReader reader(
+ aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
+ // TODO(james): Actually enforce not sending on the same buses as the logfile
+ // spews out.
+ reader.RemapLoggedChannel("/superstructure",
+ "y2024_bot3.control_loops.superstructure.Status");
+ reader.RemapLoggedChannel("/superstructure",
+ "y2024_bot3.control_loops.superstructure.Output");
+
+ aos::SimulatedEventLoopFactory factory(reader.configuration());
+ reader.Register(&factory);
+
+ aos::NodeEventLoopFactory *roborio =
+ factory.GetNodeEventLoopFactory("roborio");
+
+ unlink(absl::GetFlag(FLAGS_output_folder).c_str());
+ std::unique_ptr<aos::EventLoop> logger_event_loop =
+ roborio->MakeEventLoop("logger");
+ auto logger = std::make_unique<aos::logger::Logger>(logger_event_loop.get());
+ logger->StartLoggingOnRun(absl::GetFlag(FLAGS_output_folder));
+
+ roborio->OnStartup([roborio]() {
+ roborio->AlwaysStart<
+ y2024_bot3::control_loops::superstructure::Superstructure>(
+ "superstructure");
+ });
+
+ std::unique_ptr<aos::EventLoop> print_loop = roborio->MakeEventLoop("print");
+ print_loop->SkipAosLog();
+ print_loop->MakeWatcher(
+ "/aos", [&print_loop](const aos::logging::LogMessageFbs &msg) {
+ LOG(INFO) << print_loop->context().monotonic_event_time << " "
+ << aos::FlatbufferToJson(&msg);
+ });
+ print_loop->MakeWatcher(
+ "/superstructure",
+ [&](const y2024_bot3::control_loops::superstructure::Status &status) {
+ if (status.estopped()) {
+ LOG(ERROR) << "Estopped";
+ }
+ });
+
+ factory.Run();
+
+ reader.Deregister();
+
+ return 0;
+}
diff --git a/y2024_bot3/control_loops/superstructure/superstructure_status.fbs b/y2024_bot3/control_loops/superstructure/superstructure_status.fbs
new file mode 100644
index 0000000..407af5f
--- /dev/null
+++ b/y2024_bot3/control_loops/superstructure/superstructure_status.fbs
@@ -0,0 +1,38 @@
+include "frc971/control_loops/control_loops.fbs";
+include "frc971/control_loops/profiled_subsystem.fbs";
+
+namespace y2024_bot3.control_loops.superstructure;
+
+// Equivalent to IntakeGoal enum in goal flatbuffer
+enum IntakeRollerStatus : ubyte {
+ NONE = 0,
+ INTAKE = 1,
+ SCORE = 2,
+ SPIT = 3,
+}
+
+// Equivalent to PivotGoal enum in goal flatbuffer
+enum ArmStatus: ubyte {
+ IDLE = 0,
+ INTAKE = 1,
+ AMP = 2,
+}
+
+table Status {
+ // All subsystems know their location.
+ zeroed:bool (id: 0);
+
+ // If true, we have aborted. This is the or of all subsystem estops.
+ estopped:bool (id: 1);
+
+ // Estimated Angles + Velocities of the Intake
+ arm:frc971.control_loops.PotAndAbsoluteEncoderProfiledJointStatus (id: 2);
+
+ // Tells us what IntakeGoal is
+ intake_roller_status: IntakeRollerStatus (id: 3);
+
+ // Tells us what PivotGoal is
+ arm_status: ArmStatus (id: 4);
+}
+
+root_type Status;
diff --git a/y2024_bot3/copy_logs.sh b/y2024_bot3/copy_logs.sh
new file mode 100755
index 0000000..806460f
--- /dev/null
+++ b/y2024_bot3/copy_logs.sh
@@ -0,0 +1,29 @@
+#!/bin/bash
+
+# Helper script to copy most recent logs off of the pis
+
+set -e
+
+ROBOT_PREFIX="99" # ..71 (Should be one of 79, 89, 99, or 9)
+PI_LIST="1 2" # Should be some set of {1,2,3,4,5,6}
+
+LOG_FILE_PATH=/media/sda1/fbs_log-current
+if [[ -z $1 || ! -d $1 ]]; then
+ echo "Please specify the base directory to store the logs ('$1' not found)"
+ exit -1
+fi
+
+# Create output directory based on given directory + a timestamp
+OUTPUT_DIR=$1"/"`date +"%Y-%m-%dT%H-%M-%S"`
+mkdir ${OUTPUT_DIR}
+
+echo "Copying logs from the robot ${ROBOT_PREFIX}71 and pis ${PI_LIST}"
+echo "Storing logs in folder ${OUTPUT_DIR}"
+
+for pi in $PI_LIST; do
+ echo "========================================================"
+ echo "Copying logs from pi-${ROBOT_PREFIX}71-$pi"
+ echo "========================================================"
+ scp -r pi@10.${ROBOT_PREFIX}.71.10${pi}:${LOG_FILE_PATH} ${OUTPUT_DIR}/fbs_log-pi${pi}
+done
+
diff --git a/y2024_bot3/joystick_reader.cc b/y2024_bot3/joystick_reader.cc
new file mode 100644
index 0000000..4b88402
--- /dev/null
+++ b/y2024_bot3/joystick_reader.cc
@@ -0,0 +1,63 @@
+#include <unistd.h>
+
+#include <cmath>
+#include <cstdio>
+#include <cstring>
+
+#include "absl/flags/flag.h"
+
+#include "aos/actions/actions.h"
+#include "aos/init.h"
+#include "aos/logging/logging.h"
+#include "aos/network/team_number.h"
+#include "aos/util/log_interval.h"
+#include "frc971/autonomous/base_autonomous_actor.h"
+#include "frc971/constants/constants_sender_lib.h"
+#include "frc971/control_loops/drivetrain/localizer_generated.h"
+#include "frc971/control_loops/profiled_subsystem_generated.h"
+#include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h"
+#include "frc971/input/action_joystick_input.h"
+#include "frc971/input/driver_station_data.h"
+#include "frc971/input/drivetrain_input.h"
+#include "frc971/input/joystick_input.h"
+#include "frc971/input/redundant_joystick_data.h"
+#include "frc971/zeroing/wrap.h"
+#include "y2024_bot3/constants/constants_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_goal_static.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_status_static.h"
+
+using frc971::CreateProfileParameters;
+using frc971::input::driver_station::ButtonLocation;
+using frc971::input::driver_station::ControlBit;
+using frc971::input::driver_station::JoystickAxis;
+using frc971::input::driver_station::POVLocation;
+
+namespace y2024_bot3::input::joysticks {
+
+namespace superstructure = y2024_bot3::control_loops::superstructure;
+
+// ButtonLocation constants go here
+
+class Reader : public ::frc971::input::ActionJoystickInput {};
+} // namespace y2024_bot3::input::joysticks
+
+int main(int argc, char **argv) {
+ ::aos::InitGoogle(&argc, &argv);
+
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig("aos_config.json");
+ frc971::constants::WaitForConstants<y2024_bot3::Constants>(&config.message());
+
+ ::aos::ShmEventLoop constant_fetcher_event_loop(&config.message());
+ frc971::constants::ConstantsFetcher<y2024_bot3::Constants> constants_fetcher(
+ &constant_fetcher_event_loop);
+ const y2024_bot3::Constants *robot_constants = &constants_fetcher.constants();
+
+ ::aos::ShmEventLoop event_loop(&config.message());
+ (void)robot_constants;
+ //::y2024_bot3::input::joysticks::Reader reader(&event_loop, robot_constants);
+
+ event_loop.Run();
+
+ return 0;
+}
diff --git a/y2024_bot3/log_web_proxy.sh b/y2024_bot3/log_web_proxy.sh
new file mode 100755
index 0000000..f97bafe
--- /dev/null
+++ b/y2024_bot3/log_web_proxy.sh
@@ -0,0 +1 @@
+./aos/network/log_web_proxy_main --data_dir=y2024_bot3/www $@
diff --git a/y2024_bot3/orin/BUILD b/y2024_bot3/orin/BUILD
new file mode 100644
index 0000000..c8b899b
--- /dev/null
+++ b/y2024_bot3/orin/BUILD
@@ -0,0 +1,16 @@
+cc_binary(
+ name = "can_logger",
+ srcs = [
+ "can_logger_main.cc",
+ ],
+ target_compatible_with = ["@platforms//cpu:arm64"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//aos:init",
+ "//aos/events:shm_event_loop",
+ "//aos/time",
+ "//frc971/can_logger:can_logger_lib",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
+ ],
+)
diff --git a/y2024_bot3/orin/can_logger_main.cc b/y2024_bot3/orin/can_logger_main.cc
new file mode 100644
index 0000000..dcfec69
--- /dev/null
+++ b/y2024_bot3/orin/can_logger_main.cc
@@ -0,0 +1,18 @@
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "frc971/can_logger/can_logger.h"
+
+int main(int argc, char **argv) {
+ ::aos::InitGoogle(&argc, &argv);
+
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig("aos_config.json");
+
+ ::aos::ShmEventLoop event_loop(&config.message());
+
+ frc971::can_logger::CanLogger cana_logger(&event_loop, "/can/cana", "cana");
+
+ event_loop.Run();
+
+ return 0;
+}
diff --git a/y2024_bot3/vision/BUILD b/y2024_bot3/vision/BUILD
new file mode 100644
index 0000000..b55d35d
--- /dev/null
+++ b/y2024_bot3/vision/BUILD
@@ -0,0 +1,54 @@
+filegroup(
+ name = "image_streamer_start",
+ srcs = ["image_streamer_start.sh"],
+ visibility = ["//visibility:public"],
+)
+
+cc_binary(
+ name = "apriltag_detector",
+ srcs = [
+ "apriltag_detector.cc",
+ "vision_util.cc",
+ "vision_util.h",
+ ],
+ features = ["cuda"],
+ target_compatible_with = ["@platforms//cpu:arm64"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//aos:configuration",
+ "//aos:init",
+ "//aos/events:shm_event_loop",
+ "//frc971/orin:gpu_apriltag_lib",
+ "//third_party:cudart",
+ "//third_party/apriltag",
+ "//y2024_bot3/constants:constants_fbs",
+ "@com_github_nvidia_cccl//:cccl",
+ "@com_google_absl//absl/flags:flag",
+ "@com_google_absl//absl/log",
+ "@com_google_absl//absl/log:check",
+ ],
+)
+
+cc_binary(
+ name = "viewer",
+ srcs = [
+ "viewer.cc",
+ "vision_util.cc",
+ "vision_util.h",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = [
+ "//y2024_bot3:__subpackages__",
+ ],
+ deps = [
+ "//aos:init",
+ "//aos:json_to_flatbuffer",
+ "//aos/events:shm_event_loop",
+ "//frc971/constants:constants_sender_lib",
+ "//frc971/vision:vision_fbs",
+ "//frc971/vision:vision_util_lib",
+ "//third_party:opencv",
+ "//y2024_bot3/constants:constants_fbs",
+ "@com_google_absl//absl/strings",
+ ],
+)
diff --git a/y2024_bot3/vision/apriltag_detector.cc b/y2024_bot3/vision/apriltag_detector.cc
new file mode 100644
index 0000000..2c73c58
--- /dev/null
+++ b/y2024_bot3/vision/apriltag_detector.cc
@@ -0,0 +1,54 @@
+
+#include <string>
+
+#include "absl/flags/flag.h"
+
+#include "aos/init.h"
+#include "frc971/orin/gpu_apriltag.h"
+#include "y2024_bot3/constants/constants_generated.h"
+#include "y2024_bot3/vision/vision_util.h"
+
+ABSL_FLAG(std::string, channel, "/camera", "Channel name");
+ABSL_FLAG(std::string, config, "aos_config.json",
+ "Path to the config file to use.");
+
+void GpuApriltagDetector() {
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
+
+ frc971::constants::WaitForConstants<y2024_bot3::Constants>(&config.message());
+
+ aos::ShmEventLoop event_loop(&config.message());
+
+ const frc971::constants::ConstantsFetcher<y2024_bot3::Constants>
+ calibration_data(&event_loop);
+
+ CHECK(absl::GetFlag(FLAGS_channel).length() == 8);
+ int camera_id = std::stoi(absl::GetFlag(FLAGS_channel).substr(7, 1));
+ const frc971::vision::calibration::CameraCalibration *calibration =
+ y2024_bot3::vision::FindCameraCalibration(
+ calibration_data.constants(),
+ event_loop.node()->name()->string_view(), camera_id);
+
+ frc971::apriltag::ApriltagDetector detector(
+ &event_loop, absl::GetFlag(FLAGS_channel), calibration);
+
+ // TODO(austin): Figure out our core pinning strategy.
+ // event_loop.SetRuntimeAffinity(aos::MakeCpusetFromCpus({5}));
+
+ LOG(INFO) << "Setting scheduler priority";
+ struct sched_param param;
+ param.sched_priority = 21;
+ PCHECK(sched_setscheduler(0, SCHED_FIFO, ¶m) == 0);
+
+ LOG(INFO) << "Running event loop";
+ // TODO(austin): Pre-warm it...
+ event_loop.Run();
+} // namespace frc971::apriltag
+
+int main(int argc, char **argv) {
+ aos::InitGoogle(&argc, &argv);
+ GpuApriltagDetector();
+
+ return 0;
+}
diff --git a/y2024_bot3/vision/image_streamer_start.sh b/y2024_bot3/vision/image_streamer_start.sh
new file mode 100755
index 0000000..48d9da7
--- /dev/null
+++ b/y2024_bot3/vision/image_streamer_start.sh
@@ -0,0 +1,22 @@
+#!/bin/bash
+
+# Some configurations to avoid dropping frames
+# 640x480@30fps, 400x300@60fps.
+# Bitrate 500000-1500000
+WIDTH=640
+HEIGHT=480
+BITRATE=1500000
+LISTEN_ON="/camera/downsized"
+# Don't interfere with field webpage
+STREAMING_PORT=1181
+
+# Handle weirdness with openssl and gstreamer
+export OPENSSL_CONF=""
+
+# Enable for verbose logging
+#export GST_DEBUG=4
+
+export LD_LIBRARY_PATH=/usr/lib/aarch64-linux-gnu/gstreamer-1.0
+
+exec ./image_streamer --width=$WIDTH --height=$HEIGHT --bitrate=$BITRATE --listen_on=$LISTEN_ON --config=aos_config.json --streaming_port=$STREAMING_PORT
+
diff --git a/y2024_bot3/vision/maps/BUILD b/y2024_bot3/vision/maps/BUILD
new file mode 100644
index 0000000..38191a4
--- /dev/null
+++ b/y2024_bot3/vision/maps/BUILD
@@ -0,0 +1,7 @@
+filegroup(
+ name = "maps",
+ srcs = glob([
+ "*.json",
+ ]),
+ visibility = ["//visibility:public"],
+)
diff --git a/y2024_bot3/vision/maps/target_map.json b/y2024_bot3/vision/maps/target_map.json
new file mode 100644
index 0000000..2a8dfef
--- /dev/null
+++ b/y2024_bot3/vision/maps/target_map.json
@@ -0,0 +1,236 @@
+{
+/* Targets have positive Z axis pointing into the board, positive X to the right
+ when looking at the board, and positive Y is down when looking at the board.
+ This means that you will get an identity rotation from the camera to target
+ frame when the target is upright, flat, and centered in the camera's view.
+
+ The global frame as the origin at the center of the field, positive X points
+ at the red driver's station, and positive Z points straight up.
+ */
+ "target_poses": [
+ {
+ "id": 1,
+ "position": {
+ "x": 6.809,
+ "y": -3.860,
+ "z": 1.361
+ },
+ "orientation": {
+ "w": 0.1830127,
+ "x": -0.1830127,
+ "y": 0.6830127,
+ "z": -0.6830127
+ }
+ },
+ {
+ "id": 2,
+ "position": {
+ "x": 7.915,
+ "y": -3.223,
+ "z": 1.361
+ },
+ "orientation": {
+ "w": 0.1830127,
+ "x": -0.1830127,
+ "y": 0.6830127,
+ "z": -0.6830127
+ }
+ },
+ {
+ "id": 3,
+ "position": {
+ "x": 8.309,
+ "y": 0.877,
+ "z": 1.456
+ },
+ "orientation": {
+ "w": 0.5,
+ "x": -0.5,
+ "y": 0.5,
+ "z": -0.5
+ }
+ },
+ {
+ "id": 4,
+ "position": {
+ "x": 8.309,
+ "y": 1.442,
+ "z": 1.456
+ },
+ "orientation": {
+ "w": 0.5,
+ "x": -0.5,
+ "y": 0.5,
+ "z": -0.5
+ }
+ },
+ {
+ "id": 5,
+ "position": {
+ "x": 6.428,
+ "y": 4.099,
+ "z": 1.361
+ },
+ "orientation": {
+ "w": 0.7071068,
+ "x": -0.7071068,
+ "y": 0.0,
+ "z": 0.0
+ }
+ },
+ {
+ "id": 6,
+ "position": {
+ "x": -6.430,
+ "y": 4.099,
+ "z": 1.361
+ },
+ "orientation": {
+ "w": 0.7071068,
+ "x": -0.7071068,
+ "y": 0.0,
+ "z": 0.0
+ }
+ },
+ {
+ "id": 7,
+ "position": {
+ "x": -8.309,
+ "y": 1.442,
+ "z": 1.474
+ },
+ "orientation": {
+ "w": 0.5,
+ "x": -0.5,
+ "y": -0.5,
+ "z": 0.5
+ }
+ },
+ {
+ "id": 8,
+ "position": {
+ "x": -8.309,
+ "y": 0.877,
+ "z": 1.474
+ },
+ "orientation": {
+ "w": 0.5,
+ "x": -0.5,
+ "y": -0.5,
+ "z": 0.5
+ }
+ },
+ {
+ "id": 9,
+ "position": {
+ "x": -7.915,
+ "y": -3.223,
+ "z": 1.361
+ },
+ "orientation": {
+ "w": 0.1830127,
+ "x": -0.1830127,
+ "y": -0.6830127,
+ "z": 0.6830127
+ }
+ },
+ {
+ "id": 10,
+ "position": {
+ "x": -6.809,
+ "y": -3.860,
+ "z": 1.361
+ },
+ "orientation": {
+ "w": 0.1830127,
+ "x": -0.1830127,
+ "y": -0.6830127,
+ "z": 0.6830127
+ }
+ },
+ {
+ "id": 11,
+ "position": {
+ "x": 3.629,
+ "y": -0.393,
+ "z": 1.326
+ },
+ "orientation": {
+ "w": 0.6830127,
+ "x": -0.6830127,
+ "y": -0.1830127,
+ "z": 0.1830127
+ }
+ },
+ {
+ "id": 12,
+ "position": {
+ "x": 3.630,
+ "y": 0.392,
+ "z": 1.326
+ },
+ "orientation": {
+ "w": 0.1830127,
+ "x": -0.1830127,
+ "y": -0.6830127,
+ "z": 0.6830127
+ }
+ },
+ {
+ "id": 13,
+ "position": {
+ "x": 2.949,
+ "y": -0.000,
+ "z": 1.326
+ },
+ "orientation": {
+ "w": 0.5,
+ "x": -0.5,
+ "y": 0.5,
+ "z": -0.5
+ }
+ },
+ {
+ "id": 14,
+ "position": {
+ "x": -2.949,
+ "y": -0.000,
+ "z": 1.326
+ },
+ "orientation": {
+ "w": 0.5,
+ "x": -0.5,
+ "y": -0.5,
+ "z": 0.5
+ }
+ },
+ {
+ "id": 15,
+ "position": {
+ "x": -3.629,
+ "y": 0.393,
+ "z": 1.326
+ },
+ "orientation": {
+ "w": 0.1830127,
+ "x": -0.1830127,
+ "y": 0.6830127,
+ "z": -0.6830127
+ }
+ },
+ {
+ "id": 16,
+ "position": {
+ "x": -3.630,
+ "y": -0.392,
+ "z": 1.326
+ },
+ "orientation": {
+ "w": 0.6830127,
+ "x": -0.6830127,
+ "y": 0.1830127,
+ "z": -0.1830127
+ }
+ }
+ ]
+}
diff --git a/y2024_bot3/vision/viewer.cc b/y2024_bot3/vision/viewer.cc
new file mode 100644
index 0000000..2d99fd5
--- /dev/null
+++ b/y2024_bot3/vision/viewer.cc
@@ -0,0 +1,122 @@
+#include "absl/strings/match.h"
+#include <opencv2/calib3d.hpp>
+#include <opencv2/highgui/highgui.hpp>
+#include <opencv2/imgproc.hpp>
+
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/time/time.h"
+#include "frc971/constants/constants_sender_lib.h"
+#include "frc971/vision/vision_generated.h"
+#include "frc971/vision/vision_util_lib.h"
+#include "y2024_bot3/vision/vision_util.h"
+
+ABSL_FLAG(std::string, capture, "",
+ "If set, capture a single image and save it to this filename.");
+ABSL_FLAG(std::string, channel, "/camera", "Channel name for the image.");
+ABSL_FLAG(std::string, config, "aos_config.json",
+ "Path to the config file to use.");
+ABSL_FLAG(int32_t, rate, 100, "Time in milliseconds to wait between images");
+ABSL_FLAG(double, scale, 1.0, "Scale factor for images being displayed");
+
+namespace y2024_bot3::vision {
+namespace {
+
+using frc971::vision::CameraImage;
+
+bool DisplayLoop(const cv::Mat intrinsics, const cv::Mat dist_coeffs,
+ aos::Fetcher<CameraImage> *image_fetcher) {
+ const CameraImage *image;
+
+ // Read next image
+ if (!image_fetcher->Fetch()) {
+ VLOG(2) << "Couldn't fetch next image";
+ return true;
+ }
+ image = image_fetcher->get();
+ CHECK(image != nullptr) << "Couldn't read image";
+
+ // Create color image:
+ cv::Mat image_color_mat(cv::Size(image->cols(), image->rows()), CV_8UC2,
+ (void *)image->data()->data());
+ cv::Mat bgr_image(cv::Size(image->cols(), image->rows()), CV_8UC3);
+ cv::cvtColor(image_color_mat, bgr_image, cv::COLOR_YUV2BGR_YUYV);
+
+ if (!absl::GetFlag(FLAGS_capture).empty()) {
+ if (absl::EndsWith(absl::GetFlag(FLAGS_capture), ".bfbs")) {
+ aos::WriteFlatbufferToFile(absl::GetFlag(FLAGS_capture),
+ image_fetcher->CopyFlatBuffer());
+ } else {
+ cv::imwrite(absl::GetFlag(FLAGS_capture), bgr_image);
+ }
+
+ return false;
+ }
+
+ cv::Mat undistorted_image;
+ cv::undistort(bgr_image, undistorted_image, intrinsics, dist_coeffs);
+ if (absl::GetFlag(FLAGS_scale) != 1.0) {
+ cv::resize(undistorted_image, undistorted_image, cv::Size(),
+ absl::GetFlag(FLAGS_scale), absl::GetFlag(FLAGS_scale));
+ }
+ cv::imshow("Display", undistorted_image);
+
+ int keystroke = cv::waitKey(1);
+ if ((keystroke & 0xFF) == static_cast<int>('c')) {
+ // Convert again, to get clean image
+ cv::cvtColor(image_color_mat, bgr_image, cv::COLOR_YUV2BGR_YUYV);
+ std::stringstream name;
+ name << "capture-" << aos::realtime_clock::now() << ".png";
+ cv::imwrite(name.str(), bgr_image);
+ LOG(INFO) << "Saved image file: " << name.str();
+ } else if ((keystroke & 0xFF) == static_cast<int>('q')) {
+ return false;
+ }
+ return true;
+}
+
+void ViewerMain() {
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig(absl::GetFlag(FLAGS_config));
+
+ frc971::constants::WaitForConstants<y2024_bot3::Constants>(&config.message());
+
+ aos::ShmEventLoop event_loop(&config.message());
+
+ frc971::constants::ConstantsFetcher<y2024_bot3::Constants> constants_fetcher(
+ &event_loop);
+ CHECK(absl::GetFlag(FLAGS_channel).length() == 8);
+ int camera_id = std::stoi(absl::GetFlag(FLAGS_channel).substr(7, 1));
+ const auto *calibration_data = FindCameraCalibration(
+ constants_fetcher.constants(), event_loop.node()->name()->string_view(),
+ camera_id);
+ const cv::Mat intrinsics = frc971::vision::CameraIntrinsics(calibration_data);
+ const cv::Mat dist_coeffs =
+ frc971::vision::CameraDistCoeffs(calibration_data);
+
+ aos::Fetcher<CameraImage> image_fetcher =
+ event_loop.MakeFetcher<CameraImage>(absl::GetFlag(FLAGS_channel));
+
+ // Run the display loop
+ event_loop.AddPhasedLoop(
+ [&](int) {
+ if (!DisplayLoop(intrinsics, dist_coeffs, &image_fetcher)) {
+ LOG(INFO) << "Calling event_loop Exit";
+ event_loop.Exit();
+ };
+ },
+ ::std::chrono::milliseconds(absl::GetFlag(FLAGS_rate)));
+
+ event_loop.Run();
+
+ image_fetcher = aos::Fetcher<CameraImage>();
+}
+
+} // namespace
+} // namespace y2024_bot3::vision
+
+int main(int argc, char **argv) {
+ aos::InitGoogle(&argc, &argv);
+ y2024_bot3::vision::ViewerMain();
+}
diff --git a/y2024_bot3/vision/vision_util.cc b/y2024_bot3/vision/vision_util.cc
new file mode 100644
index 0000000..0f99849
--- /dev/null
+++ b/y2024_bot3/vision/vision_util.cc
@@ -0,0 +1,49 @@
+#include "y2024_bot3/vision/vision_util.h"
+
+#include "absl/log/check.h"
+#include "absl/log/log.h"
+
+namespace y2024_bot3::vision {
+
+// Store a list of ordered cameras as you progress around the robot/box of orins
+std::vector<CameraNode> CreateNodeList() {
+ std::vector<CameraNode> list;
+
+ list.push_back({.node_name = "imu", .camera_number = 0});
+ list.push_back({.node_name = "imu", .camera_number = 1});
+ list.push_back({.node_name = "orin1", .camera_number = 1});
+ list.push_back({.node_name = "orin1", .camera_number = 0});
+
+ return list;
+}
+
+// From the node_list, create a numbering scheme from 0 to 3
+std::map<std::string, int> CreateOrderingMap(
+ std::vector<CameraNode> &node_list) {
+ std::map<std::string, int> map;
+
+ for (uint i = 0; i < node_list.size(); i++) {
+ map.insert({node_list.at(i).camera_name(), i});
+ }
+
+ return map;
+}
+
+const frc971::vision::calibration::CameraCalibration *FindCameraCalibration(
+ const y2024_bot3::Constants &calibration_data, std::string_view node_name,
+ int camera_number) {
+ CHECK(calibration_data.has_cameras());
+ for (const y2024_bot3::CameraConfiguration *candidate :
+ *calibration_data.cameras()) {
+ CHECK(candidate->has_calibration());
+ if (candidate->calibration()->node_name()->string_view() != node_name ||
+ candidate->calibration()->camera_number() != camera_number) {
+ continue;
+ }
+ return candidate->calibration();
+ }
+ LOG(FATAL) << ": Failed to find camera calibration for " << node_name
+ << " and camera number " << camera_number;
+}
+
+} // namespace y2024_bot3::vision
diff --git a/y2024_bot3/vision/vision_util.h b/y2024_bot3/vision/vision_util.h
new file mode 100644
index 0000000..fc0f29c
--- /dev/null
+++ b/y2024_bot3/vision/vision_util.h
@@ -0,0 +1,41 @@
+#ifndef Y2024_BOT3_VISION_VISION_UTIL_H_
+#define Y2024_BOT3_VISION_VISION_UTIL_H_
+#include <map>
+#include <string_view>
+
+#include "opencv2/imgproc.hpp"
+
+#include "y2024_bot3/constants/constants_generated.h"
+
+namespace y2024_bot3::vision {
+
+// Generate unique colors for each camera
+const auto kOrinColors = std::map<std::string, cv::Scalar>{
+ {"/orin1/camera0", cv::Scalar(255, 0, 255)},
+ {"/orin1/camera1", cv::Scalar(255, 255, 0)},
+ {"/imu/camera0", cv::Scalar(0, 255, 255)},
+ {"/imu/camera1", cv::Scalar(255, 165, 0)},
+};
+
+// Structure to store node name (e.g., orin1, imu), number, and a usable string
+struct CameraNode {
+ std::string node_name;
+ int camera_number;
+
+ inline const std::string camera_name() const {
+ return "/" + node_name + "/camera" + std::to_string(camera_number);
+ }
+};
+
+std::vector<CameraNode> CreateNodeList();
+
+std::map<std::string, int> CreateOrderingMap(
+ std::vector<CameraNode> &node_list);
+
+const frc971::vision::calibration::CameraCalibration *FindCameraCalibration(
+ const y2024_bot3::Constants &calibration_data, std::string_view node_name,
+ int camera_number);
+
+} // namespace y2024_bot3::vision
+
+#endif // Y2024_BOT3_VISION_VISION_UTIL_H_
diff --git a/y2024_bot3/wpilib_interface.cc b/y2024_bot3/wpilib_interface.cc
new file mode 100644
index 0000000..b6066e3
--- /dev/null
+++ b/y2024_bot3/wpilib_interface.cc
@@ -0,0 +1,249 @@
+#include <unistd.h>
+
+#include <array>
+#include <chrono>
+#include <cinttypes>
+#include <cstdio>
+#include <cstring>
+#include <functional>
+#include <memory>
+#include <mutex>
+#include <thread>
+
+#include "absl/flags/flag.h"
+
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/DriverStation.h"
+#include "frc971/wpilib/ahal/Encoder.h"
+#include "frc971/wpilib/ahal/TalonFX.h"
+#include "frc971/wpilib/ahal/VictorSP.h"
+#undef ERROR
+
+#include "ctre/phoenix/cci/Diagnostics_CCI.h"
+
+#include "aos/commonmath.h"
+#include "aos/containers/sized_array.h"
+#include "aos/events/event_loop.h"
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "aos/logging/logging.h"
+#include "aos/realtime.h"
+#include "aos/time/time.h"
+#include "aos/util/log_interval.h"
+#include "aos/util/phased_loop.h"
+#include "aos/util/wrapping_counter.h"
+#include "frc971/can_configuration_generated.h"
+#include "frc971/constants/constants_sender_lib.h"
+#include "frc971/input/robot_state_generated.h"
+#include "frc971/queues/gyro_generated.h"
+#include "frc971/wpilib/buffered_pcm.h"
+#include "frc971/wpilib/buffered_solenoid.h"
+#include "frc971/wpilib/can_sensor_reader.h"
+#include "frc971/wpilib/dma.h"
+#include "frc971/wpilib/encoder_and_potentiometer.h"
+#include "frc971/wpilib/generic_can_writer.h"
+#include "frc971/wpilib/joystick_sender.h"
+#include "frc971/wpilib/logging_generated.h"
+#include "frc971/wpilib/loop_output_handler.h"
+#include "frc971/wpilib/pdp_fetcher.h"
+#include "frc971/wpilib/sensor_reader.h"
+#include "frc971/wpilib/talonfx.h"
+#include "frc971/wpilib/wpilib_robot_base.h"
+#include "y2024_bot3/constants.h"
+#include "y2024_bot3/constants/constants_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_can_position_static.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_output_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_position_generated.h"
+#include "y2024_bot3/control_loops/superstructure/superstructure_position_static.h"
+
+ABSL_FLAG(bool, ctre_diag_server, false,
+ "If true, enable the diagnostics server for interacting with "
+ "devices on the CAN bus using Phoenix Tuner");
+
+using ::aos::monotonic_clock;
+using ::frc971::CANConfiguration;
+using ::frc971::wpilib::TalonFX;
+using ::y2024_bot3::constants::Values;
+namespace superstructure = ::y2024_bot3::control_loops::superstructure;
+namespace chrono = ::std::chrono;
+using std::make_unique;
+
+namespace y2024_bot3::wpilib {
+namespace {
+
+constexpr double kMaxBringupPower = 12.0;
+
+constexpr double kMaxFastEncoderPulsesPerSecond = std::max({
+ 1000000 // arbitrary number because we deleted all the stuff in this array
+});
+
+static_assert(kMaxFastEncoderPulsesPerSecond <= 1300000,
+ "fast encoders are too fast");
+
+} // namespace
+
+// Class to send position messages with sensor readings to our loops.
+class SensorReader : public ::frc971::wpilib::SensorReader {
+ public:
+ SensorReader(::aos::ShmEventLoop *event_loop,
+ const Constants *robot_constants)
+ : ::frc971::wpilib::SensorReader(event_loop),
+ robot_constants_(robot_constants),
+ superstructure_position_sender_(
+ event_loop->MakeSender<superstructure::PositionStatic>(
+ "/superstructure")) {
+ UpdateFastEncoderFilterHz(kMaxFastEncoderPulsesPerSecond);
+ event_loop->SetRuntimeAffinity(aos::MakeCpusetFromCpus({0}));
+ };
+ void Start() override { AddToDMA(&imu_yaw_rate_reader_); }
+
+ void set_yaw_rate_input(::std::unique_ptr<frc::DigitalInput> sensor) {
+ imu_yaw_rate_input_ = ::std::move(sensor);
+ imu_yaw_rate_reader_.set_input(imu_yaw_rate_input_.get());
+ }
+
+ void RunIteration() override {
+ aos::Sender<superstructure::PositionStatic>::StaticBuilder builder =
+ superstructure_position_sender_.MakeStaticBuilder();
+
+ builder.CheckOk(builder.Send());
+
+ {
+ auto builder = gyro_sender_.MakeBuilder();
+ ::frc971::sensors::GyroReading::Builder gyro_reading_builder =
+ builder.MakeBuilder<::frc971::sensors::GyroReading>();
+
+ builder.CheckOk(builder.Send(gyro_reading_builder.Finish()));
+ }
+ }
+
+ private:
+ const Constants *robot_constants_;
+
+ aos::Sender<superstructure::PositionStatic> superstructure_position_sender_;
+ ::aos::Sender<::frc971::sensors::GyroReading> gyro_sender_;
+
+ std::unique_ptr<frc::DigitalInput> imu_yaw_rate_input_;
+
+ frc971::wpilib::DMAPulseWidthReader imu_yaw_rate_reader_;
+};
+
+class WPILibRobot : public ::frc971::wpilib::WPILibRobotBase {
+ public:
+ ::std::unique_ptr<frc::Encoder> make_encoder(int index) {
+ return make_unique<frc::Encoder>(10 + index * 2, 11 + index * 2, false,
+ frc::Encoder::k4X);
+ }
+
+ void Run() override {
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig("aos_config.json");
+
+ frc971::constants::WaitForConstants<y2024_bot3::Constants>(
+ &config.message());
+
+ ::aos::ShmEventLoop constant_fetcher_event_loop(&config.message());
+ frc971::constants::ConstantsFetcher<Constants> constants_fetcher(
+ &constant_fetcher_event_loop);
+ const Constants *robot_constants = &constants_fetcher.constants();
+
+ AddLoop(&constant_fetcher_event_loop);
+
+ // Thread 1.
+ ::aos::ShmEventLoop joystick_sender_event_loop(&config.message());
+ ::frc971::wpilib::JoystickSender joystick_sender(
+ &joystick_sender_event_loop);
+ AddLoop(&joystick_sender_event_loop);
+
+ // Thread 2.
+ ::aos::ShmEventLoop pdp_fetcher_event_loop(&config.message());
+ ::frc971::wpilib::PDPFetcher pdp_fetcher(&pdp_fetcher_event_loop);
+ AddLoop(&pdp_fetcher_event_loop);
+
+ // Thread 3.
+ ::aos::ShmEventLoop sensor_reader_event_loop(&config.message());
+ SensorReader sensor_reader(&sensor_reader_event_loop, robot_constants);
+ sensor_reader.set_pwm_trigger(false);
+ sensor_reader.set_yaw_rate_input(make_unique<frc::DigitalInput>(25));
+
+ AddLoop(&sensor_reader_event_loop);
+
+ // Thread 4.
+ // Set up CAN.
+ if (!absl::GetFlag(FLAGS_ctre_diag_server)) {
+ c_Phoenix_Diagnostics_SetSecondsToStart(-1);
+ c_Phoenix_Diagnostics_Dispose();
+ }
+
+ std::vector<ctre::phoenix6::BaseStatusSignal *> canivore_signal_registry;
+ std::vector<ctre::phoenix6::BaseStatusSignal *> rio_signal_registry;
+
+ ::aos::ShmEventLoop can_sensor_reader_event_loop(&config.message());
+ can_sensor_reader_event_loop.set_name("CANSensorReader");
+
+ ::aos::ShmEventLoop rio_sensor_reader_event_loop(&config.message());
+ rio_sensor_reader_event_loop.set_name("RioSensorReader");
+
+ // Creating list of talonfx for CANSensorReader
+ std::vector<std::shared_ptr<TalonFX>> canivore_talonfxs;
+ std::vector<std::shared_ptr<TalonFX>> rio_talonfxs;
+
+ aos::Sender<y2024_bot3::control_loops::superstructure::CANPositionStatic>
+ superstructure_can_position_sender =
+ can_sensor_reader_event_loop.MakeSender<
+ y2024_bot3::control_loops::superstructure::CANPositionStatic>(
+ "/superstructure/canivore");
+
+ aos::Sender<y2024_bot3::control_loops::superstructure::CANPositionStatic>
+ superstructure_rio_position_sender =
+ rio_sensor_reader_event_loop.MakeSender<
+ y2024_bot3::control_loops::superstructure::CANPositionStatic>(
+ "/superstructure/rio");
+
+ frc971::wpilib::CANSensorReader rio_can_sensor_reader(
+ &rio_sensor_reader_event_loop, std::move(rio_signal_registry),
+ rio_talonfxs,
+ [&superstructure_rio_position_sender](
+ ctre::phoenix::StatusCode status) {
+ aos::Sender<
+ y2024_bot3::control_loops::superstructure::CANPositionStatic>::
+ StaticBuilder superstructure_can_builder =
+ superstructure_rio_position_sender.MakeStaticBuilder();
+
+ superstructure_can_builder->set_status(static_cast<int>(status));
+ superstructure_can_builder.CheckOk(superstructure_can_builder.Send());
+ },
+ frc971::wpilib::CANSensorReader::SignalSync::kNoSync);
+
+ AddLoop(&can_sensor_reader_event_loop);
+ AddLoop(&rio_sensor_reader_event_loop);
+
+ // Thread 5.
+ ::aos::ShmEventLoop can_output_event_loop(&config.message());
+ can_output_event_loop.set_name("CANOutputWriter");
+
+ frc971::wpilib::GenericCANWriter<control_loops::superstructure::Output>
+ can_superstructure_writer(
+ &can_output_event_loop,
+ [](const control_loops::superstructure::Output &output,
+ const std::map<std::string_view, std::shared_ptr<TalonFX>>
+ &talonfx_map) {
+ (void)output;
+ (void)talonfx_map;
+ });
+
+ can_output_event_loop.MakeWatcher(
+ "/roborio", [&can_superstructure_writer](
+ const frc971::CANConfiguration &configuration) {
+ can_superstructure_writer.HandleCANConfiguration(configuration);
+ });
+
+ AddLoop(&can_output_event_loop);
+
+ RunLoops();
+ }
+};
+
+} // namespace y2024_bot3::wpilib
+
+AOS_ROBOT_CLASS(::y2024_bot3::wpilib::WPILibRobot);
diff --git a/y2024_bot3/www/BUILD b/y2024_bot3/www/BUILD
new file mode 100644
index 0000000..51d7c8f
--- /dev/null
+++ b/y2024_bot3/www/BUILD
@@ -0,0 +1,68 @@
+load("//frc971/downloader:downloader.bzl", "aos_downloader_dir")
+load("//tools/build_rules:js.bzl", "rollup_bundle", "ts_project")
+
+filegroup(
+ name = "files",
+ srcs = glob([
+ "**/*.html",
+ "**/*.css",
+ "**/*.png",
+ ]) + ["2024_bot3.png"],
+ visibility = ["//visibility:public"],
+)
+
+genrule(
+ name = "2024_bot3_field_png",
+ srcs = ["//third_party/y2024/field:pictures"],
+ outs = ["2024_bot3.png"],
+ cmd = "cp third_party/y2024/field/2024.png $@",
+)
+
+ts_project(
+ name = "field_main",
+ srcs = [
+ "constants.ts",
+ "field_handler.ts",
+ "field_main.ts",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ "//aos/network:connect_ts_fbs",
+ "//aos/network:message_bridge_client_ts_fbs",
+ "//aos/network:message_bridge_server_ts_fbs",
+ "//aos/network:web_proxy_ts_fbs",
+ "//aos/network/www:proxy",
+ "//frc971/control_loops:control_loops_ts_fbs",
+ "//frc971/control_loops/drivetrain:drivetrain_can_position_ts_fbs",
+ "//frc971/control_loops/drivetrain:drivetrain_position_ts_fbs",
+ "//frc971/control_loops/drivetrain:drivetrain_status_ts_fbs",
+ "//frc971/control_loops/drivetrain/localization:localizer_output_ts_fbs",
+ "//frc971/vision:target_map_ts_fbs",
+ "//y2024_bot3/control_loops/superstructure:superstructure_position_ts_fbs",
+ "//y2024_bot3/control_loops/superstructure:superstructure_status_ts_fbs",
+ "@com_github_google_flatbuffers//ts:flatbuffers_ts",
+ ],
+)
+
+rollup_bundle(
+ name = "field_main_bundle",
+ entry_point = "field_main.ts",
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//y2024_bot3:__subpackages__"],
+ deps = [
+ ":field_main",
+ ],
+)
+
+aos_downloader_dir(
+ name = "www_files",
+ srcs = [
+ ":field_main_bundle.min.js",
+ ":files",
+ "//frc971/analysis:plot_index_bundle.min.js",
+ "//frc971/www:starter_files",
+ ],
+ dir = "www",
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+)
diff --git a/y2024_bot3/www/constants.ts b/y2024_bot3/www/constants.ts
new file mode 100644
index 0000000..97d6e28
--- /dev/null
+++ b/y2024_bot3/www/constants.ts
@@ -0,0 +1,8 @@
+// Conversion constants to meters
+export const IN_TO_M = 0.0254;
+export const FT_TO_M = 0.3048;
+// Dimensions of the field in meters
+// Numbers are slightly hand-tuned to match the PNG that we are using.
+export const FIELD_WIDTH = 26 * FT_TO_M + 11.25 * IN_TO_M;
+export const FIELD_LENGTH = 54 * FT_TO_M + 3.25 * IN_TO_M;
+
diff --git a/y2024_bot3/www/field.html b/y2024_bot3/www/field.html
new file mode 100644
index 0000000..04fb5c1
--- /dev/null
+++ b/y2024_bot3/www/field.html
@@ -0,0 +1,101 @@
+<html>
+
+<head>
+ <script src="field_main_bundle.min.js" defer></script>
+ <link rel="stylesheet" href="styles.css">
+</head>
+
+<body>
+ <div style="display: grid;
+ grid-template-columns: auto auto auto; gap: 5px;">
+ <div>
+ <div id="field"> </div>
+ <div id="legend"> </div>
+ <h3>Zeroing Faults:</h3>
+ <p id="zeroing_faults"> NA </p>
+ </div>
+ <div>
+ <table>
+ <tr>
+ <th colspan="2" style="text-align: center;">Robot State</th>
+ </tr>
+ <tr>
+ <td>X</td>
+ <td id="x"> NA </td>
+ </tr>
+ <tr>
+ <td>Y</td>
+ <td id="y"> NA </td>
+ </tr>
+ <tr>
+ <td>Theta</td>
+ <td id="theta"> NA </td>
+ </tr>
+ </table>
+ <table>
+ <tr>
+ <th colspan="2" style="text-align: center;">Images</th>
+ </tr>
+ <tr>
+ <td> Images Accepted </td>
+ <td id="images_accepted"> NA </td>
+ </tr>
+ </table>
+ <table>
+ <tr>
+ <th colspan="2" style="text-align: center;">Superstructure States</th>
+ </tr>
+ <tr>
+ <td style="font-weight: bold;">Superstructure State</td>
+ <td id="superstructure_state" style="font-weight: bold;"> NA </td>
+ </tr>
+ </table>
+ </div>
+ <div>
+ <table>
+ <tr>
+ <th colspan="2" style="text-align: center;">Subsystems</th>
+ </tr>
+ </table>
+ <table>
+ <tr>
+ <th colspan="2" style="text-align: center;"> Drivetrain Encoder Positions </th>
+ </tr>
+ <tr>
+ <td> Left Encoder Position</td>
+ <td id="left_drivetrain_encoder"> NA </td>
+ </tr>
+ <tr>
+ <td> Right Encoder Position</td>
+ <td id="right_drivetrain_encoder"> NA </td>
+ </tr>
+ <tr>
+ <td> Right Front Falcon CAN Position</td>
+ <td id="falcon_right_front"> NA </td>
+ </tr>
+ <tr>
+ <td> Right Back Falcon CAN Position</td>
+ <td id="falcon_right_back"> NA </td>
+ </tr>
+ <tr>
+ <td> Left Front Falcon CAN Position</td>
+ <td id="falcon_left_front"> NA </td>
+ </tr>
+ <tr>
+ <td> Left Back Falcon CAN Position</td>
+ <td id="falcon_left_back"> NA </td>
+ </tr>
+ </table>
+ </div>
+ </div>
+ <div id="message_bridge_status">
+ <div>
+ <div>Node</div>
+ <div>Client</div>
+ <div>Server</div>
+ </div>
+ </div>
+ <div id="vision_readouts"> </div>
+</body>
+
+</html>
\ No newline at end of file
diff --git a/y2024_bot3/www/field_handler.ts b/y2024_bot3/www/field_handler.ts
new file mode 100644
index 0000000..5b243ef
--- /dev/null
+++ b/y2024_bot3/www/field_handler.ts
@@ -0,0 +1,347 @@
+import {ByteBuffer} from 'flatbuffers'
+import {ClientStatistics} from '../../aos/network/message_bridge_client_generated'
+import {ServerStatistics, State as ConnectionState} from '../../aos/network/message_bridge_server_generated'
+import {Connection} from '../../aos/network/www/proxy'
+import {ZeroingError} from '../../frc971/control_loops/control_loops_generated'
+import {Position as DrivetrainPosition} from '../../frc971/control_loops/drivetrain/drivetrain_position_generated'
+import {CANPosition as DrivetrainCANPosition} from '../../frc971/control_loops/drivetrain/drivetrain_can_position_generated'
+import {Status as DrivetrainStatus} from '../../frc971/control_loops/drivetrain/drivetrain_status_generated'
+import {Position as SuperstructurePosition} from '../control_loops/superstructure/superstructure_position_generated'
+import {Status as SuperstructureStatus} from '../control_loops/superstructure/superstructure_status_generated'
+import {TargetMap} from '../../frc971/vision/target_map_generated'
+
+
+import {FIELD_LENGTH, FIELD_WIDTH, FT_TO_M, IN_TO_M} from './constants';
+
+// (0,0) is field center, +X is toward red DS
+const FIELD_SIDE_Y = FIELD_WIDTH / 2;
+const FIELD_EDGE_X = FIELD_LENGTH / 2;
+
+const ROBOT_WIDTH = 29 * IN_TO_M;
+const ROBOT_LENGTH = 32 * IN_TO_M;
+
+const CAMERA_COLORS = ['#ff00ff', '#ffff00', '#00ffff', '#ffa500'];
+const CAMERAS = ['/orin1/camera0', '/orin1/camera1', '/imu/camera0', '/imu/camera1'];
+
+export class FieldHandler {
+ private canvas = document.createElement('canvas');
+ private superstructureStatus: SuperstructureStatus|null = null;
+ private superstructurePosition: SuperstructurePosition|null = null;
+
+ // Image information indexed by timestamp (seconds since the epoch), so that
+ // we can stop displaying images after a certain amount of time.
+ private x: HTMLElement = (document.getElementById('x') as HTMLElement);
+ private y: HTMLElement = (document.getElementById('y') as HTMLElement);
+ private theta: HTMLElement =
+ (document.getElementById('theta') as HTMLElement);
+
+ private imagesAcceptedCounter: HTMLElement =
+ (document.getElementById('images_accepted') as HTMLElement);
+ // HTML elements for rejection reasons for individual cameras. Indices
+ // corresponding to RejectionReason enum values will be for those reasons. The
+ // final row will account for images rejected by the aprilrobotics detector
+ // instead of the localizer.
+ private rejectionReasonCells: HTMLElement[][] = [];
+ private messageBridgeDiv: HTMLElement =
+ (document.getElementById('message_bridge_status') as HTMLElement);
+ private clientStatuses = new Map<string, HTMLElement>();
+ private serverStatuses = new Map<string, HTMLElement>();
+
+ private fieldImage: HTMLImageElement = new Image();
+
+ private zeroingFaults: HTMLElement =
+ (document.getElementById('zeroing_faults') as HTMLElement);
+
+ private leftDrivetrainEncoder: HTMLElement =
+ (document.getElementById('left_drivetrain_encoder') as HTMLElement);
+ private rightDrivetrainEncoder: HTMLElement =
+ (document.getElementById('right_drivetrain_encoder') as HTMLElement);
+ private falconRightFrontPosition: HTMLElement =
+ (document.getElementById('falcon_right_front') as HTMLElement);
+ private falconRightBackPosition: HTMLElement =
+ (document.getElementById('falcon_right_back') as HTMLElement);
+ private falconLeftFrontPosition: HTMLElement =
+ (document.getElementById('falcon_left_front') as HTMLElement);
+ private falconLeftBackPosition: HTMLElement =
+ (document.getElementById('falcon_left_back') as HTMLElement);
+
+ constructor(private readonly connection: Connection) {
+ (document.getElementById('field') as HTMLElement).appendChild(this.canvas);
+
+ this.fieldImage.src = '2024.png';
+
+ // Construct a table header.
+ {
+ const row = document.createElement('div');
+ const nameCell = document.createElement('div');
+ nameCell.innerHTML = 'Rejection Reason';
+ row.appendChild(nameCell);
+ for (const camera of CAMERAS) {
+ const nodeCell = document.createElement('div');
+ nodeCell.innerHTML = camera;
+ row.appendChild(nodeCell);
+ }
+ document.getElementById('vision_readouts').appendChild(row);
+ }
+
+ // Add rejection reason row for aprilrobotics rejections.
+ {
+ const row = document.createElement('div');
+ const nameCell = document.createElement('div');
+ nameCell.innerHTML = 'Rejected by aprilrobotics';
+ row.appendChild(nameCell);
+ this.rejectionReasonCells.push([]);
+ for (const camera of CAMERAS) {
+ const valueCell = document.createElement('div');
+ valueCell.innerHTML = 'NA';
+ this.rejectionReasonCells[this.rejectionReasonCells.length - 1].push(
+ valueCell);
+ row.appendChild(valueCell);
+ }
+ document.getElementById('vision_readouts').appendChild(row);
+ }
+
+ for (let ii = 0; ii < CAMERA_COLORS.length; ++ii) {
+ const legendEntry = document.createElement('div');
+ legendEntry.style.color = CAMERA_COLORS[ii];
+ legendEntry.innerHTML = CAMERAS[ii];
+ document.getElementById('legend').appendChild(legendEntry);
+ }
+
+ this.connection.addConfigHandler(() => {
+ // Visualization message is reliable so that we can see *all* the vision
+ // matches.
+
+ for (const camera in CAMERAS) {
+ // Make unreliable to reduce network spam.
+ this.connection.addHandler(
+ CAMERAS[camera], 'frc971.vision.TargetMap', (data) => {
+ this.handleCameraTargetMap(camera, data);
+ });
+ }
+
+ this.connection.addHandler(
+ '/superstructure', "y2024_bot3.control_loops.superstructure.Status",
+ (data) => {
+ this.handleSuperstructureStatus(data)
+ });
+ this.connection.addHandler(
+ '/superstructure', "y2024_bot3.control_loops.superstructure.Positon",
+ (data) => {
+ this.handleSuperstructurePosition(data)
+ });
+ this.connection.addHandler(
+ '/aos', 'aos.message_bridge.ServerStatistics',
+ (data) => {this.handleServerStatistics(data)});
+ this.connection.addHandler(
+ '/aos', 'aos.message_bridge.ClientStatistics',
+ (data) => {this.handleClientStatistics(data)});
+ });
+ }
+ private handleCameraTargetMap(pi: string, data: Uint8Array): void {
+ const fbBuffer = new ByteBuffer(data);
+ const targetMap = TargetMap.getRootAsTargetMap(fbBuffer);
+ this.rejectionReasonCells[this.rejectionReasonCells.length - 1][pi]
+ .innerHTML = targetMap.rejections().toString();
+ }
+
+ private handleSuperstructureStatus(data: Uint8Array): void {
+ const fbBuffer = new ByteBuffer(data);
+ this.superstructureStatus = SuperstructureStatus.getRootAsStatus(fbBuffer);
+ }
+
+ private handleSuperstructurePosition(data: Uint8Array): void {
+ const fbBuffer = new ByteBuffer(data);
+ this.superstructurePosition = SuperstructurePosition.getRootAsPosition(fbBuffer);
+ }
+
+ private populateNodeConnections(nodeName: string): void {
+ const row = document.createElement('div');
+ this.messageBridgeDiv.appendChild(row);
+ const nodeDiv = document.createElement('div');
+ nodeDiv.innerHTML = nodeName;
+ row.appendChild(nodeDiv);
+ const clientDiv = document.createElement('div');
+ clientDiv.innerHTML = 'N/A';
+ row.appendChild(clientDiv);
+ const serverDiv = document.createElement('div');
+ serverDiv.innerHTML = 'N/A';
+ row.appendChild(serverDiv);
+ this.serverStatuses.set(nodeName, serverDiv);
+ this.clientStatuses.set(nodeName, clientDiv);
+ }
+
+ private setCurrentNodeState(element: HTMLElement, state: ConnectionState):
+ void {
+ if (state === ConnectionState.CONNECTED) {
+ element.innerHTML = ConnectionState[state];
+ element.classList.remove('faulted');
+ element.classList.add('connected');
+ } else {
+ element.innerHTML = ConnectionState[state];
+ element.classList.remove('connected');
+ element.classList.add('faulted');
+ }
+ }
+
+ private handleServerStatistics(data: Uint8Array): void {
+ const fbBuffer = new ByteBuffer(data);
+ const serverStatistics =
+ ServerStatistics.getRootAsServerStatistics(fbBuffer);
+
+ for (let ii = 0; ii < serverStatistics.connectionsLength(); ++ii) {
+ const connection = serverStatistics.connections(ii);
+ const nodeName = connection.node().name();
+ if (!this.serverStatuses.has(nodeName)) {
+ this.populateNodeConnections(nodeName);
+ }
+ this.setCurrentNodeState(
+ this.serverStatuses.get(nodeName), connection.state());
+ }
+ }
+
+ private handleClientStatistics(data: Uint8Array): void {
+ const fbBuffer = new ByteBuffer(data);
+ const clientStatistics =
+ ClientStatistics.getRootAsClientStatistics(fbBuffer);
+
+ for (let ii = 0; ii < clientStatistics.connectionsLength(); ++ii) {
+ const connection = clientStatistics.connections(ii);
+ const nodeName = connection.node().name();
+ if (!this.clientStatuses.has(nodeName)) {
+ this.populateNodeConnections(nodeName);
+ }
+ this.setCurrentNodeState(
+ this.clientStatuses.get(nodeName), connection.state());
+ }
+ }
+
+ drawField(): void {
+ const ctx = this.canvas.getContext('2d');
+ ctx.save();
+ ctx.scale(1.0, -1.0);
+ ctx.drawImage(
+ this.fieldImage, 0, 0, this.fieldImage.width, this.fieldImage.height,
+ -FIELD_EDGE_X, -FIELD_SIDE_Y, FIELD_LENGTH, FIELD_WIDTH);
+ ctx.restore();
+ }
+
+ drawCamera(x: number, y: number, theta: number, color: string = 'blue'):
+ void {
+ const ctx = this.canvas.getContext('2d');
+ ctx.save();
+ ctx.translate(x, y);
+ ctx.rotate(theta);
+ ctx.strokeStyle = color;
+ ctx.beginPath();
+ ctx.moveTo(0.5, 0.5);
+ ctx.lineTo(0, 0);
+ ctx.lineTo(0.5, -0.5);
+ ctx.stroke();
+ ctx.beginPath();
+ ctx.arc(0, 0, 0.25, -Math.PI / 4, Math.PI / 4);
+ ctx.stroke();
+ ctx.restore();
+ }
+
+ drawRobot(
+ x: number, y: number, theta: number, color: string = 'blue',
+ dashed: boolean = false): void {
+ const ctx = this.canvas.getContext('2d');
+ ctx.save();
+ ctx.translate(x, y);
+ ctx.rotate(theta);
+ ctx.strokeStyle = color;
+ ctx.lineWidth = ROBOT_WIDTH / 10.0;
+ if (dashed) {
+ ctx.setLineDash([0.05, 0.05]);
+ } else {
+ // Empty array = solid line.
+ ctx.setLineDash([]);
+ }
+ ctx.rect(-ROBOT_LENGTH / 2, -ROBOT_WIDTH / 2, ROBOT_LENGTH, ROBOT_WIDTH);
+ ctx.stroke();
+
+ // Draw line indicating which direction is forwards on the robot.
+ ctx.beginPath();
+ ctx.moveTo(0, 0);
+ ctx.lineTo(ROBOT_LENGTH / 2.0, 0);
+ ctx.stroke();
+
+ ctx.restore();
+}
+
+ setZeroing(div: HTMLElement): void {
+ div.innerHTML = 'zeroing';
+ div.classList.remove('faulted');
+ div.classList.add('zeroing');
+ div.classList.remove('near');
+ }
+
+ setEstopped(div: HTMLElement): void {
+ div.innerHTML = 'estopped';
+ div.classList.add('faulted');
+ div.classList.remove('zeroing');
+ div.classList.remove('near');
+ }
+
+ setTargetValue(
+ div: HTMLElement, target: number, val: number, tolerance: number): void {
+ div.innerHTML = val.toFixed(4);
+ div.classList.remove('faulted');
+ div.classList.remove('zeroing');
+ if (Math.abs(target - val) < tolerance) {
+ div.classList.add('near');
+ } else {
+ div.classList.remove('near');
+ }
+ }
+
+ setValue(div: HTMLElement, val: number): void {
+ div.innerHTML = val.toFixed(4);
+ div.classList.remove('faulted');
+ div.classList.remove('zeroing');
+ div.classList.remove('near');
+ }
+
+ setBoolean(div: HTMLElement, triggered: boolean): void {
+ div.innerHTML = ((triggered) ? "TRUE" : "FALSE")
+ div.className = '';
+ if (triggered) {
+ div.classList.add('lightgreen');
+ } else {
+ div.classList.add('lightcoral');
+ }
+ }
+
+ draw(): void {
+ this.reset();
+ this.drawField();
+
+ window.requestAnimationFrame(() => this.draw());
+ }
+
+ reset(): void {
+ const ctx = this.canvas.getContext('2d');
+ // Empty space from the canvas boundary to the image
+ const IMAGE_PADDING = 10;
+ ctx.setTransform(1, 0, 0, 1, 0, 0);
+ const size = window.innerHeight * 0.9;
+ ctx.canvas.height = size;
+ const width = size / 2 + 20;
+ ctx.canvas.width = width;
+ ctx.clearRect(0, 0, size, width);
+
+ // Translate to center of display.
+ ctx.translate(width / 2, size / 2);
+ // Coordinate system is:
+ // x -> forward.
+ // y -> to the left.
+ ctx.rotate(-Math.PI / 2);
+ ctx.scale(1, -1);
+
+ const M_TO_PX = (size - IMAGE_PADDING) / FIELD_LENGTH;
+ ctx.scale(M_TO_PX, M_TO_PX);
+ ctx.lineWidth = 1 / M_TO_PX;
+ }
+}
diff --git a/y2024_bot3/www/field_main.ts b/y2024_bot3/www/field_main.ts
new file mode 100644
index 0000000..ef8b99d
--- /dev/null
+++ b/y2024_bot3/www/field_main.ts
@@ -0,0 +1,11 @@
+import {Connection} from '../../aos/network/www/proxy';
+
+import {FieldHandler} from './field_handler';
+
+const conn = new Connection();
+
+conn.connect();
+
+const fieldHandler = new FieldHandler(conn);
+
+fieldHandler.draw();
diff --git a/y2024_bot3/www/index.html b/y2024_bot3/www/index.html
new file mode 100644
index 0000000..98ecf42
--- /dev/null
+++ b/y2024_bot3/www/index.html
@@ -0,0 +1,7 @@
+<html>
+ <body>
+ <a href="field.html">Field Visualization</a><br>
+ <a href="plotter.html">Plots</a><br>
+ <a href="starter.html">AOS Starter Status</a>
+ </body>
+</html>
diff --git a/y2024_bot3/www/plotter.html b/y2024_bot3/www/plotter.html
new file mode 100644
index 0000000..86f5aa8
--- /dev/null
+++ b/y2024_bot3/www/plotter.html
@@ -0,0 +1,8 @@
+<html>
+ <head>
+ <script src="plot_index_bundle.min.js" defer></script>
+ <link rel="stylesheet" href="styles.css">
+ </head>
+ <body>
+ </body>
+</html>
diff --git a/y2024_bot3/y2024_bot3.json b/y2024_bot3/y2024_bot3.json
new file mode 100644
index 0000000..aea954c
--- /dev/null
+++ b/y2024_bot3/y2024_bot3.json
@@ -0,0 +1,19 @@
+{
+ "channel_storage_duration": 10000000000,
+ "maps": [
+ {
+ "match": {
+ "name": "/aos",
+ "type": "aos.RobotState"
+ },
+ "rename": {
+ "name": "/roborio/aos"
+ }
+ }
+ ],
+ "imports": [
+ "y2024_bot3_roborio.json",
+ "y2024_bot3_imu.json",
+ "y2024_bot3_orin1.json",
+ ]
+}
diff --git a/y2024_bot3/y2024_bot3_imu.json b/y2024_bot3/y2024_bot3_imu.json
new file mode 100644
index 0000000..9473c59
--- /dev/null
+++ b/y2024_bot3/y2024_bot3_imu.json
@@ -0,0 +1,547 @@
+{
+ "channels": [
+ {
+ "name": "/imu/aos",
+ "type": "aos.util.FilesystemStatus",
+ "source_node": "imu",
+ "frequency": 2
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.JoystickState",
+ "source_node": "imu",
+ "frequency": 100,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "orin1"
+ ],
+ "destination_nodes": [
+ {
+ "name": "orin1",
+ "priority": 5,
+ "time_to_live": 50000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ]
+ }
+ ]
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/orin1/imu/aos/aos-JoystickState",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "imu",
+ "logger": "NOT_LOGGED",
+ "frequency": 300,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.timing.Report",
+ "source_node": "imu",
+ "frequency": 50,
+ "num_senders": 30,
+ "max_size": 10912
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.logging.LogMessageFbs",
+ "source_node": "imu",
+ "frequency": 200,
+ "num_senders": 30
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.starter.Status",
+ "source_node": "imu",
+ "frequency": 50,
+ "num_senders": 20,
+ "max_size": 6144
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.starter.StarterRpc",
+ "source_node": "imu",
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.message_bridge.ServerStatistics",
+ "source_node": "imu",
+ "max_size": 2048,
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.message_bridge.ClientStatistics",
+ "source_node": "imu",
+ "frequency": 20,
+ "num_senders": 2
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.logging.DynamicLogCommand",
+ "source_node": "imu",
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.message_bridge.Timestamp",
+ "source_node": "imu",
+ "frequency": 15,
+ "num_senders": 2,
+ "logger_nodes": [
+ "roborio"
+ ],
+ "max_size": 400,
+ "destination_nodes": [
+ {
+ "name": "roborio",
+ "priority": 1,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/roborio/imu/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "imu",
+ "max_size": 208
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.starter.StarterRpc",
+ "source_node": "roborio",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "imu",
+ "priority": 5,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-starter-StarterRpc",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "roborio",
+ "logger": "NOT_LOGGED",
+ "frequency": 20,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/imu/camera0",
+ "type": "frc971.vision.CameraImage",
+ "source_node": "imu",
+ "channel_storage_duration": 1000000000,
+ "frequency": 70,
+ "max_size": 4752384,
+ "num_readers": 6,
+ "read_method": "PIN",
+ "num_senders": 18
+ },
+ {
+ "name": "/imu/camera1",
+ "type": "frc971.vision.CameraImage",
+ "source_node": "imu",
+ "channel_storage_duration": 1000000000,
+ "frequency": 70,
+ "max_size": 4752384,
+ "num_readers": 6,
+ "read_method": "PIN",
+ "num_senders": 18
+ },
+ {
+ "name": "/imu/camera0",
+ "type": "foxglove.CompressedImage",
+ "source_node": "imu",
+ "logger": "NOT_LOGGED",
+ "channel_storage_duration": 1000000000,
+ "frequency": 70,
+ "max_size": 622384
+ },
+ {
+ "name": "/imu/camera1",
+ "type": "foxglove.CompressedImage",
+ "source_node": "imu",
+ "logger": "NOT_LOGGED",
+ "channel_storage_duration": 1000000000,
+ "frequency": 70,
+ "max_size": 622384
+ },
+ {
+ "name": "/imu/camera0",
+ "type": "foxglove.ImageAnnotations",
+ "source_node": "imu",
+ "frequency": 70,
+ "max_size": 50000
+ },
+ {
+ "name": "/imu/camera1",
+ "type": "foxglove.ImageAnnotations",
+ "source_node": "imu",
+ "frequency": 70,
+ "max_size": 50000
+ },
+ {
+ "name": "/imu/camera0",
+ "type": "frc971.vision.TargetMap",
+ "source_node": "imu",
+ "frequency": 70,
+ "num_senders": 2,
+ "max_size": 1024
+ },
+ {
+ "name": "/imu/camera1",
+ "type": "frc971.vision.TargetMap",
+ "source_node": "imu",
+ "frequency": 70,
+ "num_senders": 2,
+ "max_size": 1024
+ },
+ {
+ "name": "/imu",
+ "type": "frc971.imu.DualImu",
+ "source_node": "imu",
+ "frequency": 1100,
+ "num_senders": 1,
+ "max_size": 496
+ },
+ {
+ "name": "/imu",
+ "type": "frc971.imu.CanTranslatorStatus",
+ "source_node": "imu",
+ "frequency": 1000,
+ "num_senders": 1,
+ "max_size": 200
+ },
+ {
+ "name": "/can/cana",
+ "type": "frc971.can_logger.CanFrame",
+ "source_node": "imu",
+ "frequency": 9000,
+ "channel_storage_duration": 7000000000,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/imu",
+ "type": "frc971.imu.DualImuBlenderStatus",
+ "source_node": "imu",
+ "frequency": 1100,
+ "num_senders": 1,
+ "max_size": 200
+ },
+ {
+ "name": "/imu/hardware_monitor",
+ "type": "frc971.orin.HardwareStats",
+ "source_node": "imu",
+ "frequency": 2
+ },
+ {
+ "name": "/imu/constants",
+ "type": "y2024_bot3.Constants",
+ "source_node": "imu",
+ "frequency": 1,
+ "num_senders": 2,
+ "max_size": 65536
+ }
+ ],
+ "applications": [
+ {
+ "name": "message_bridge_client",
+ "args": [
+ "--rt_priority=16",
+ "--sinit_max_init_timeout=5000",
+ "--rmem=8388608"
+ ],
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "irq_affinity",
+ "executable_name": "irq_affinity",
+ "user": "root",
+ "args": ["--user=pi", "--irq_config=orin_irq_config.json"],
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "filesystem_monitor",
+ "executable_name": "filesystem_monitor",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "hardware_monitor",
+ "executable_name": "hardware_monitor",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "joystick_republish",
+ "executable_name": "joystick_republish",
+ "user": "pi",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "message_bridge_server",
+ "executable_name": "message_bridge_server",
+ "user": "pi",
+ "args": [
+ "--rt_priority=16",
+ "--force_wmem_max=131072"
+ ],
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "imu_can_logger",
+ "executable_name": "can_logger",
+ "args": [
+ "--priority=59",
+ "--affinity=5"
+ ],
+ "nodes": [
+ "imu"
+ ]
+ },
+ // TODO(max): Update the channel value with whatever channel the IMU is on.
+ {
+ "name": "can_translator",
+ "executable_name": "can_translator",
+ "args": [
+ "--channel=/can/cana"
+ ],
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "dual_imu_blender",
+ "executable_name": "dual_imu_blender",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "web_proxy",
+ "executable_name": "web_proxy_main",
+ "args": [
+ "--min_ice_port=5800",
+ "--max_ice_port=5810"
+ ],
+ "user": "pi",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "foxglove_websocket",
+ "user": "pi",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "constants_sender",
+ "autorestart": false,
+ "user": "pi",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "image_logger",
+ "executable_name": "image_logger",
+ "args": [
+ "--rotate_every",
+ "30.0",
+ "--direct",
+ "--flush_size=4194304"
+ ],
+ "user": "pi",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "foxglove_websocket",
+ "user": "pi",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "foxglove_image_converter0",
+ "executable_name": "foxglove_image_converter",
+ "user": "pi",
+ "args": [
+ "--channel", "/camera0"
+ ],
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "foxglove_image_converter1",
+ "executable_name": "foxglove_image_converter",
+ "user": "pi",
+ "args": [
+ "--channel", "/camera1"
+ ],
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "constants_sender",
+ "autorestart": false,
+ "user": "pi",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "argus_monitor_imu",
+ "executable_name": "argus_monitor",
+ "args": [
+ "/imu/camera0",
+ "frc971.vision.TargetMap",
+ "/imu/camera1",
+ "frc971.vision.TargetMap",
+ ],
+ "user": "pi",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "argus_camera0",
+ "executable_name": "argus_camera",
+ "args": [
+ "--camera=0",
+ "--channel=/camera0"
+ ],
+ "user": "pi",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "argus_camera1",
+ "executable_name": "argus_camera",
+ "args": [
+ "--camera=1",
+ "--channel=/camera1"
+ ],
+ "user": "pi",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "apriltag_detector0",
+ "executable_name": "apriltag_detector",
+ "args": [
+ "--channel=/camera0"
+ ],
+ "user": "pi",
+ "nodes": [
+ "imu"
+ ]
+ },
+ {
+ "name": "apriltag_detector1",
+ "executable_name": "apriltag_detector",
+ "args": [
+ "--channel=/camera1"
+ ],
+ "user": "pi",
+ "nodes": [
+ "imu"
+ ]
+ }
+ ],
+ "maps": [
+ {
+ "match": {
+ "name": "/constants*",
+ "source_node": "imu"
+ },
+ "rename": {
+ "name": "/imu/constants"
+ }
+ },
+ {
+ "match": {
+ "name": "/aos*",
+ "source_node": "imu"
+ },
+ "rename": {
+ "name": "/imu/aos"
+ }
+ },
+ {
+ "match": {
+ "name": "/camera*",
+ "source_node": "imu"
+ },
+ "rename": {
+ "name": "/imu/camera"
+ }
+ },
+ {
+ "match": {
+ "name": "/hardware_monitor*",
+ "source_node": "imu"
+ },
+ "rename": {
+ "name": "/imu/hardware_monitor"
+ }
+ }
+ ],
+ "nodes": [
+ {
+ "name": "imu",
+ "hostname": "orin2",
+ "hostnames": [
+ "orin-971-2",
+ "orin-7971-2",
+ "orin-8971-2",
+ "orin-9971-2"
+ ],
+ "port": 9971
+ },
+ {
+ "name": "roborio"
+ },
+ {
+ "name": "orin1"
+ }
+ ]
+}
diff --git a/y2024_bot3/y2024_bot3_orin1.json b/y2024_bot3/y2024_bot3_orin1.json
new file mode 100644
index 0000000..8d5085e
--- /dev/null
+++ b/y2024_bot3/y2024_bot3_orin1.json
@@ -0,0 +1,493 @@
+{
+ "channels": [
+ {
+ "name": "/orin1/aos",
+ "type": "aos.util.FilesystemStatus",
+ "source_node": "orin1",
+ "frequency": 2
+ },
+ {
+ "name": "/orin1/aos",
+ "type": "aos.timing.Report",
+ "source_node": "orin1",
+ "frequency": 50,
+ "num_senders": 30,
+ "max_size": 8192
+ },
+ {
+ "name": "/orin1/aos",
+ "type": "aos.logging.LogMessageFbs",
+ "source_node": "orin1",
+ "frequency": 200,
+ "num_senders": 30
+ },
+ {
+ "name": "/orin1/aos",
+ "type": "aos.starter.Status",
+ "source_node": "orin1",
+ "frequency": 50,
+ "num_senders": 20,
+ "max_size": 4096
+ },
+ {
+ "name": "/orin1/aos",
+ "type": "aos.starter.StarterRpc",
+ "source_node": "orin1",
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/orin1/aos",
+ "type": "aos.message_bridge.ServerStatistics",
+ "source_node": "orin1",
+ "max_size": 2048,
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/orin1/aos",
+ "type": "aos.message_bridge.ClientStatistics",
+ "source_node": "orin1",
+ "frequency": 20,
+ "num_senders": 2
+ },
+ {
+ "name": "/orin1/aos",
+ "type": "aos.logging.DynamicLogCommand",
+ "source_node": "orin1",
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/orin1/aos",
+ "type": "aos.message_bridge.Timestamp",
+ "source_node": "orin1",
+ "frequency": 15,
+ "num_senders": 2,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "max_size": 200,
+ "destination_nodes": [
+ {
+ "name": "imu",
+ "priority": 1,
+ "time_to_live": 5000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "orin1"
+ ]
+ }
+ ]
+ },
+ {
+ "name": "/orin1/aos/remote_timestamps/imu/orin1/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "orin1",
+ "max_size": 208
+ },
+ {
+ "name": "/imu/aos",
+ "type": "aos.message_bridge.Timestamp",
+ "source_node": "imu",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "orin1"
+ ],
+ "destination_nodes": [
+ {
+ "name": "orin1",
+ "priority": 1,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/orin1/imu/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "imu",
+ "max_size": 208
+ },
+ {
+ "name": "/orin1/camera0",
+ "type": "frc971.vision.CameraImage",
+ "source_node": "orin1",
+ "channel_storage_duration": 1000000000,
+ "frequency": 70,
+ "max_size": 4752384,
+ "num_readers": 6,
+ "read_method": "PIN",
+ "num_senders": 18
+ },
+ {
+ "name": "/orin1/camera1",
+ "type": "frc971.vision.CameraImage",
+ "source_node": "orin1",
+ "channel_storage_duration": 1000000000,
+ "frequency": 70,
+ "max_size": 4752384,
+ "num_readers": 6,
+ "read_method": "PIN",
+ "num_senders": 18
+ },
+ {
+ "name": "/orin1/camera0",
+ "type": "foxglove.CompressedImage",
+ "source_node": "orin1",
+ "logger": "NOT_LOGGED",
+ "channel_storage_duration": 1000000000,
+ "frequency": 70,
+ "max_size": 622384
+ },
+ {
+ "name": "/orin1/camera1",
+ "type": "foxglove.CompressedImage",
+ "source_node": "orin1",
+ "logger": "NOT_LOGGED",
+ "channel_storage_duration": 1000000000,
+ "frequency": 70,
+ "max_size": 622384
+ },
+ {
+ "name": "/orin1/camera0",
+ "type": "foxglove.ImageAnnotations",
+ "source_node": "orin1",
+ "frequency": 70,
+ "max_size": 50000
+ },
+ {
+ "name": "/orin1/camera1",
+ "type": "foxglove.ImageAnnotations",
+ "source_node": "orin1",
+ "frequency": 70,
+ "max_size": 50000
+ },
+ {
+ "name": "/orin1/camera0",
+ "type": "frc971.vision.TargetMap",
+ "source_node": "orin1",
+ "frequency": 70,
+ "num_senders": 2,
+ "max_size": 1024,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "imu",
+ "priority": 4,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "orin1"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/orin1/camera1",
+ "type": "frc971.vision.TargetMap",
+ "source_node": "orin1",
+ "frequency": 70,
+ "num_senders": 2,
+ "max_size": 1024,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "imu",
+ "priority": 4,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "orin1"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/orin1/aos/remote_timestamps/imu/orin1/camera0/frc971-vision-TargetMap",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 80,
+ "source_node": "orin1",
+ "max_size": 208
+ },
+ {
+ "name": "/orin1/aos/remote_timestamps/imu/orin1/camera1/frc971-vision-TargetMap",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 80,
+ "source_node": "orin1",
+ "max_size": 208
+ },
+ {
+ "name": "/orin1/hardware_monitor",
+ "type": "frc971.orin.HardwareStats",
+ "source_node": "orin1",
+ "frequency": 2
+ },
+ {
+ "name": "/orin1/constants",
+ "type": "y2024_bot3.Constants",
+ "source_node": "orin1",
+ "frequency": 1,
+ "num_senders": 2,
+ "max_size": 65536
+ }
+ ],
+ "applications": [
+ {
+ "name": "message_bridge_client",
+ "executable_name": "message_bridge_client",
+ "args": [
+ "--rt_priority=16",
+ "--sinit_max_init_timeout=5000",
+ "--rmem=8388608"
+ ],
+ "user": "pi",
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "irq_affinity",
+ "executable_name": "irq_affinity",
+ "user": "root",
+ "args": ["--user=pi", "--irq_config=orin_irq_config.json"],
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "filesystem_monitor",
+ "executable_name": "filesystem_monitor",
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "hardware_monitor",
+ "executable_name": "hardware_monitor",
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "message_bridge_server",
+ "executable_name": "message_bridge_server",
+ "args": [
+ "--rt_priority=16",
+ "--force_wmem_max=131072"
+ ],
+ "user": "pi",
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "web_proxy",
+ "executable_name": "web_proxy_main",
+ "user": "pi",
+ "args": [
+ "--min_ice_port=5800",
+ "--max_ice_port=5810"
+ ],
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "image_logger",
+ "executable_name": "image_logger",
+ "args": [
+ "--rotate_every",
+ "30.0",
+ "--direct",
+ "--flush_size=4194304"
+ ],
+ "user": "pi",
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "foxglove_websocket",
+ "user": "pi",
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "foxglove_image_converter0",
+ "executable_name": "foxglove_image_converter",
+ "user": "pi",
+ "args": [
+ "--channel", "/camera0"
+ ],
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "foxglove_image_converter1",
+ "executable_name": "foxglove_image_converter",
+ "user": "pi",
+ "args": [
+ "--channel", "/camera1"
+ ],
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "constants_sender",
+ "autorestart": false,
+ "user": "pi",
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "argus_monitor_orin1",
+ "executable_name": "argus_monitor",
+ "args": [
+ "/orin1/camera0",
+ "frc971.vision.TargetMap",
+ "/orin1/camera1",
+ "frc971.vision.TargetMap",
+ ],
+ "user": "pi",
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "argus_camera0",
+ "executable_name": "argus_camera",
+ "args": [
+ "--camera=0",
+ "--channel=/camera0"
+ ],
+ "user": "pi",
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "argus_camera1",
+ "executable_name": "argus_camera",
+ "args": [
+ "--camera=1",
+ "--channel=/camera1"
+ ],
+ "user": "pi",
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "apriltag_detector0",
+ "executable_name": "apriltag_detector",
+ "args": [
+ "--channel=/camera0"
+ ],
+ "user": "pi",
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "apriltag_detector1",
+ "executable_name": "apriltag_detector",
+ "args": [
+ "--channel=/camera1"
+ ],
+ "user": "pi",
+ "nodes": [
+ "orin1"
+ ]
+ },
+ {
+ "name": "image_streamer",
+ "executable_name": "image_streamer",
+ "args": [
+ "--device=/dev/uvcvideo",
+ "--height=480",
+ "--width=640",
+ "--nopublish_images",
+ "--exposure=0",
+ "--framerate=30",
+ "--streaming_port=1181",
+ "--bitrate=1000000",
+ "--data_dir=/home/pi/bin/image_streamer_www"
+ ],
+ "user": "pi",
+ "nodes": [
+ "orin1"
+ ]
+ }
+ ],
+ "maps": [
+ {
+ "match": {
+ "name": "/aos*",
+ "source_node": "orin1"
+ },
+ "rename": {
+ "name": "/orin1/aos"
+ }
+ },
+ {
+ "match": {
+ "name": "/constants*",
+ "source_node": "orin1"
+ },
+ "rename": {
+ "name": "/orin1/constants"
+ }
+ },
+ {
+ "match": {
+ "name": "/camera*",
+ "source_node": "orin1"
+ },
+ "rename": {
+ "name": "/orin1/camera"
+ }
+ },
+ {
+ "match": {
+ "name": "/hardware_monitor*",
+ "source_node": "orin1"
+ },
+ "rename": {
+ "name": "/orin1/hardware_monitor"
+ }
+ }
+ ],
+ "nodes": [
+ {
+ "name": "orin1",
+ "hostname": "orin1",
+ "hostnames": [
+ "orin-971-1",
+ "orin-7971-1",
+ "orin-8971-1",
+ "orin-9971-1"
+ ],
+ "port": 9971
+ },
+ {
+ "name": "imu"
+ }
+ ]
+}
diff --git a/y2024_bot3/y2024_bot3_roborio.json b/y2024_bot3/y2024_bot3_roborio.json
new file mode 100644
index 0000000..ea5e547
--- /dev/null
+++ b/y2024_bot3/y2024_bot3_roborio.json
@@ -0,0 +1,336 @@
+{
+ "channels": [
+ {
+ "name": "/roborio/aos",
+ "type": "aos.JoystickState",
+ "source_node": "roborio",
+ "frequency": 100,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "imu",
+ "priority": 5,
+ "time_to_live": 50000000
+ }
+ ]
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "frc971.PDPValues",
+ "source_node": "roborio",
+ "frequency": 55,
+ "max_size": 368
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.RobotState",
+ "source_node": "roborio",
+ "frequency": 250
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.timing.Report",
+ "source_node": "roborio",
+ "frequency": 50,
+ "num_senders": 30,
+ "max_size": 8192
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.logging.LogMessageFbs",
+ "source_node": "roborio",
+ "frequency": 500,
+ "max_size": 1000,
+ "num_senders": 20
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.starter.Status",
+ "source_node": "roborio",
+ "frequency": 50,
+ "num_senders": 20,
+ "max_size": 2000
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.starter.StarterRpc",
+ "source_node": "roborio",
+ "frequency": 10,
+ "max_size": 400,
+ "num_senders": 2
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.message_bridge.ServerStatistics",
+ "source_node": "roborio",
+ "max_size": 2048,
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.message_bridge.ClientStatistics",
+ "source_node": "roborio",
+ "frequency": 20,
+ "max_size": 2000,
+ "num_senders": 2
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.logging.DynamicLogCommand",
+ "source_node": "roborio",
+ "frequency": 10,
+ "num_senders": 2
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-message_bridge-Timestamp",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 20,
+ "source_node": "roborio",
+ "max_size": 208
+ },
+ {
+ "name": "/roborio/aos",
+ "type": "aos.message_bridge.Timestamp",
+ "source_node": "roborio",
+ "frequency": 15,
+ "num_senders": 2,
+ "max_size": 512,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "imu",
+ "priority": 1,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/superstructure",
+ "type": "y2024_bot3.control_loops.superstructure.Goal",
+ "source_node": "roborio",
+ "frequency": 250,
+ "max_size": 512
+ },
+ {
+ "name": "/superstructure",
+ "type": "y2024_bot3.control_loops.superstructure.Status",
+ "source_node": "roborio",
+ "frequency": 400,
+ "max_size": 2048,
+ "num_senders": 2
+ },
+ {
+ "name": "/superstructure",
+ "type": "y2024_bot3.control_loops.superstructure.Output",
+ "source_node": "roborio",
+ "frequency": 250,
+ "num_senders": 2,
+ "max_size": 224
+ },
+ {
+ "name": "/superstructure",
+ "type": "y2024_bot3.control_loops.superstructure.Position",
+ "source_node": "roborio",
+ "frequency": 250,
+ "num_senders": 2,
+ "max_size": 448
+ },
+ {
+ "name": "/superstructure/canivore",
+ "type": "y2024_bot3.control_loops.superstructure.CANPosition",
+ "source_node": "roborio",
+ "frequency": 220,
+ "num_senders": 2,
+ "max_size": 1024
+ },
+ {
+ "name": "/superstructure/rio",
+ "type": "y2024_bot3.control_loops.superstructure.CANPosition",
+ "source_node": "roborio",
+ "frequency": 220,
+ "num_senders": 2,
+ "max_size": 1024
+ },
+ {
+ "name": "/can",
+ "type": "frc971.can_logger.CanFrame",
+ "source_node": "roborio",
+ "frequency": 6000,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/roborio",
+ "type": "frc971.CANConfiguration",
+ "source_node": "roborio",
+ "frequency": 2
+ },
+ {
+ "name": "/roborio/constants",
+ "type": "y2024_bot3.Constants",
+ "source_node": "roborio",
+ "frequency": 1,
+ "num_senders": 2,
+ "max_size": 65536
+ }
+ ],
+ "applications": [
+ {
+ "name": "trajectory_generator",
+ "executable_name": "trajectory_generator",
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "superstructure",
+ "executable_name": "superstructure",
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "roborio_irq_affinity",
+ "executable_name": "irq_affinity",
+ "args": [
+ "--irq_config=/home/admin/bin/roborio_irq_config.json"
+ ],
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "joystick_reader",
+ "executable_name": "joystick_reader",
+ "args": [
+ "--nodie_on_malloc"
+ ],
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "wpilib_interface",
+ "executable_name": "wpilib_interface",
+ "args": [
+ "--nodie_on_malloc"
+ ],
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "roborio_web_proxy",
+ "executable_name": "web_proxy_main",
+ "args": [
+ "--min_ice_port=5800",
+ "--max_ice_port=5810"
+ ],
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "roborio_message_bridge_client",
+ "executable_name": "message_bridge_client",
+ "args": [
+ "--rt_priority=16",
+ "--sinit_max_init_timeout=5000",
+ "--rmem=2097152"
+ ],
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "roborio_message_bridge_server",
+ "executable_name": "message_bridge_server",
+ "args": [
+ "--rt_priority=16",
+ "--force_wmem_max=131072"
+ ],
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "logger",
+ "executable_name": "logger_main",
+ "args": [
+ "--snappy_compress",
+ "--logging_folder=/home/admin/logs/",
+ "--rotate_every", "30.0"
+ ],
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "constants_sender_roborio",
+ "executable_name": "constants_sender",
+ "autorestart": false,
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
+ "name": "roborio_can_logger",
+ "executable_name": "can_logger",
+ "autostart": false,
+ "args": [
+ "--poll"
+ ],
+ "nodes": [
+ "roborio"
+ ]
+ }
+ ],
+ "maps": [
+ {
+ "match": {
+ "name": "/constants*",
+ "source_node": "roborio"
+ },
+ "rename": {
+ "name": "/roborio/constants"
+ }
+ },
+ {
+ "match": {
+ "name": "/aos*",
+ "source_node": "roborio"
+ },
+ "rename": {
+ "name": "/roborio/aos"
+ }
+ }
+ ],
+ "nodes": [
+ {
+ "name": "roborio",
+ "hostname": "roborio",
+ "hostnames": [
+ "roboRIO-971-FRC",
+ "roboRIO-6971-FRC",
+ "roboRIO-7971-FRC",
+ "roboRIO-8971-FRC",
+ "roboRIO-9971-FRC"
+ ],
+ "port": 9971
+ },
+ {
+ "name": "imu"
+ }
+ ]
+}
diff --git a/y2024_swerve/BUILD b/y2024_swerve/BUILD
index e432358..2357c6e 100644
--- a/y2024_swerve/BUILD
+++ b/y2024_swerve/BUILD
@@ -32,6 +32,7 @@
"//aos/starter:irq_affinity",
":wpilib_interface",
":swerve_publisher",
+ "//y2024_swerve/control_loops:swerve_control_loops",
"//frc971/can_logger",
"//aos/network:message_bridge_client",
"//aos/network:message_bridge_server",
diff --git a/y2024_swerve/constants/BUILD b/y2024_swerve/constants/BUILD
index 42cff81..ae707f3 100644
--- a/y2024_swerve/constants/BUILD
+++ b/y2024_swerve/constants/BUILD
@@ -26,6 +26,7 @@
"common.jinja2",
"common.json",
"//y2024_swerve/constants/calib_files",
+ "//y2024_swerve/control_loops/drivetrain:rotation_json",
"//y2024_swerve/vision/maps",
],
parameters = {},
@@ -41,6 +42,7 @@
"common.jinja2",
"common.json",
"//y2024_swerve/constants/calib_files",
+ "//y2024_swerve/control_loops/drivetrain:rotation_json",
"//y2024_swerve/vision/maps",
],
parameters = {},
diff --git a/y2024_swerve/constants/common.json b/y2024_swerve/constants/common.json
index 393b7b9..300e5f6 100644
--- a/y2024_swerve/constants/common.json
+++ b/y2024_swerve/constants/common.json
@@ -3,5 +3,24 @@
{% set pi = 3.141592653589793 %}
"relative_encoder_scale": {{ 2.0 * pi / 4096 }},
"absolute_encoder_scale": {{ 2.0 * pi }}
+ },
+ "rotation": {
+ "zeroing_voltage": 3.0,
+ "operating_voltage": 12.0,
+ "zeroing_profile_params": {
+ "max_velocity": 0.5,
+ "max_acceleration": 3.0
+ },
+ "default_profile_params":{
+ "max_velocity": 12.0,
+ "max_acceleration": 55.0
+ },
+ "range": {
+ "lower_hard": -inf,
+ "upper_hard": inf,
+ "lower": -inf,
+ "upper": inf
+ },
+ "loop": {% include 'y2024_swerve/control_loops/drivetrain/integral_rotation_plant.json' %}
}
}
diff --git a/y2024_swerve/control_loops/BUILD b/y2024_swerve/control_loops/BUILD
index 67fa349..0417af9 100644
--- a/y2024_swerve/control_loops/BUILD
+++ b/y2024_swerve/control_loops/BUILD
@@ -1,5 +1,21 @@
load("//tools/build_rules:js.bzl", "ts_project")
+cc_binary(
+ name = "swerve_control_loops",
+ srcs = [
+ "swerve_control_loops_main.cc",
+ ],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//aos:init",
+ "//aos/events:shm_event_loop",
+ "//aos/time",
+ "//frc971/constants:constants_sender_lib",
+ "//frc971/control_loops/swerve:swerve_control_loops",
+ "//y2024_swerve/constants:constants_fbs",
+ ],
+)
+
ts_project(
name = "swerve_plotter",
srcs = ["swerve_plotter.ts"],
diff --git a/y2024_swerve/control_loops/drivetrain/BUILD b/y2024_swerve/control_loops/drivetrain/BUILD
new file mode 100644
index 0000000..544cf49
--- /dev/null
+++ b/y2024_swerve/control_loops/drivetrain/BUILD
@@ -0,0 +1,22 @@
+genrule(
+ name = "genrule_rotation",
+ outs = [
+ "rotation_plant.h",
+ "rotation_plant.cc",
+ "rotation_plant.json",
+ "integral_rotation_plant.h",
+ "integral_rotation_plant.cc",
+ "integral_rotation_plant.json",
+ ],
+ cmd = "$(location //y2024_swerve/control_loops/python:rotation) $(OUTS)",
+ target_compatible_with = ["@platforms//os:linux"],
+ tools = [
+ "//y2024_swerve/control_loops/python:rotation",
+ ],
+)
+
+filegroup(
+ name = "rotation_json",
+ srcs = ["integral_rotation_plant.json"],
+ visibility = ["//visibility:public"],
+)
diff --git a/y2024_swerve/control_loops/python/BUILD b/y2024_swerve/control_loops/python/BUILD
new file mode 100644
index 0000000..0a6e2c6
--- /dev/null
+++ b/y2024_swerve/control_loops/python/BUILD
@@ -0,0 +1,14 @@
+py_binary(
+ name = "rotation",
+ srcs = [
+ "rotation.py",
+ ],
+ target_compatible_with = ["@platforms//cpu:x86_64"],
+ visibility = ["//y2024_swerve:__subpackages__"],
+ deps = [
+ "//frc971/control_loops/python:angular_system_current",
+ "//frc971/control_loops/python:controls",
+ "@pip//glog",
+ "@pip//python_gflags",
+ ],
+)
diff --git a/y2024_swerve/control_loops/python/rotation.py b/y2024_swerve/control_loops/python/rotation.py
new file mode 100644
index 0000000..a75ed5b
--- /dev/null
+++ b/y2024_swerve/control_loops/python/rotation.py
@@ -0,0 +1,57 @@
+#!/usr/bin/python3
+
+from aos.util.trapezoid_profile import TrapezoidProfile
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import angular_system_current
+from frc971.control_loops.python import controls
+import numpy
+import sys
+from matplotlib import pylab
+import gflags
+import glog
+import matplotlib
+
+FLAGS = gflags.FLAGS
+
+try:
+ gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+except gflags.DuplicateFlagError:
+ pass
+
+kRotation = angular_system_current.AngularSystemCurrentParams(
+ name='Rotation',
+ motor=control_loop.KrakenFOC(),
+ G=9.0 / 24.0 * 14.0 / 72.0,
+ J=3.1 / 1000.0,
+ q_pos=0.05,
+ q_vel=20.0,
+ kalman_q_pos=0.12,
+ kalman_q_vel=2.0,
+ kalman_q_voltage=4.0,
+ kalman_r_position=0.05,
+ radius=25 * 0.0254,
+ wrap_point=2.0 * numpy.pi)
+
+
+def main(argv):
+ if FLAGS.plot:
+ R = numpy.matrix([[numpy.pi / 2.0], [0.0]])
+ angular_system_current.PlotKick(kRotation, R)
+ angular_system_current.PlotMotion(kRotation, R)
+ return
+
+ # Write the generated constants out to a file.
+ if len(argv) != 7:
+ glog.fatal(
+ 'Expected .h file name and .cc file name for the wrist and integral wrist.'
+ )
+ else:
+ namespaces = ['y2024_swerve', 'control_loops', 'drivetrain']
+ angular_system_current.WriteAngularSystemCurrent(
+ kRotation, argv[1:4], argv[4:7], namespaces)
+
+
+if __name__ == '__main__':
+ argv = FLAGS(sys.argv)
+ glog.init()
+ sys.exit(main(argv))
diff --git a/y2024_swerve/control_loops/swerve_control_loops_main.cc b/y2024_swerve/control_loops/swerve_control_loops_main.cc
new file mode 100644
index 0000000..813744a
--- /dev/null
+++ b/y2024_swerve/control_loops/swerve_control_loops_main.cc
@@ -0,0 +1,30 @@
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "frc971/constants/constants_sender_lib.h"
+#include "frc971/control_loops/swerve/swerve_control_loops.h"
+#include "y2024_swerve/constants/constants_generated.h"
+
+using frc971::control_loops::swerve::SwerveControlLoops;
+
+int main(int argc, char **argv) {
+ ::aos::InitGoogle(&argc, &argv);
+
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig("aos_config.json");
+
+ frc971::constants::WaitForConstants<y2024_swerve::Constants>(
+ &config.message());
+
+ ::aos::ShmEventLoop event_loop(&config.message());
+
+ frc971::constants::ConstantsFetcher<y2024_swerve::Constants> constants(
+ &event_loop);
+
+ SwerveControlLoops swerve_control_loops(
+ &event_loop, constants.constants().common()->rotation(),
+ constants.constants().robot()->swerve_zeroing(), "/drivetrain");
+
+ event_loop.Run();
+
+ return 0;
+}
diff --git a/y2024_swerve/y2024_swerve_roborio.json b/y2024_swerve/y2024_swerve_roborio.json
index 705370d..adf528d 100644
--- a/y2024_swerve/y2024_swerve_roborio.json
+++ b/y2024_swerve/y2024_swerve_roborio.json
@@ -305,8 +305,7 @@
"name": "wpilib_interface",
"executable_name": "wpilib_interface",
"args": [
- "--nodie_on_malloc",
- "--ctre_diag_server"
+ "--nodie_on_malloc"
],
"nodes": [
"roborio"