Merge "Adding a few more calibration files"
diff --git a/.gitignore b/.gitignore
index 8eeac66..f881856 100644
--- a/.gitignore
+++ b/.gitignore
@@ -9,6 +9,7 @@
# The scraping library uses looks for this config file by default,
# you don't want to get that checked in
/scouting_config.json
+/scouting.db
# Hide vagrant's files that unfortunately make it into the source tree when you
# run "vagrant up".
diff --git a/BUILD b/BUILD
index d2113f2..0d79e19 100644
--- a/BUILD
+++ b/BUILD
@@ -21,6 +21,8 @@
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_matches_for_team //scouting/webserver/requests/messages:request_matches_for_team_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_all_matches_response //scouting/webserver/requests/messages:request_all_matches_response_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_all_matches //scouting/webserver/requests/messages:request_all_matches_go_fbs
+# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/refresh_match_list //scouting/webserver/requests/messages:refresh_match_list_go_fbs
+# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/refresh_match_list_response //scouting/webserver/requests/messages:refresh_match_list_response_go_fbs
gazelle(
name = "gazelle",
diff --git a/WORKSPACE b/WORKSPACE
index acda914..f574965 100644
--- a/WORKSPACE
+++ b/WORKSPACE
@@ -12,6 +12,10 @@
apache2_debs = "files",
)
load(
+ "//debian:postgresql_amd64.bzl",
+ postgresql_amd64_debs = "files",
+)
+load(
"//debian:patch.bzl",
patch_debs = "files",
)
@@ -93,6 +97,8 @@
generate_repositories_for_debs(apache2_debs)
+generate_repositories_for_debs(postgresql_amd64_debs)
+
generate_repositories_for_debs(patch_debs)
generate_repositories_for_debs(pandoc_debs)
@@ -525,6 +531,13 @@
)
http_archive(
+ name = "postgresql_amd64",
+ build_file = "@//debian:postgresql_amd64.BUILD",
+ sha256 = "2b8bb77deaf58f798c296ce31ee7a32781395d55e05dcddc8a7da7e827f38d7f",
+ url = "https://www.frc971.org/Build-Dependencies/postgresql_amd64.tar.gz",
+)
+
+http_archive(
name = "patch",
build_file = "@//debian:patch.BUILD",
sha256 = "b5ce139648a2e04f5585948ddad2fdae24dd4ee7976ac5a22d6ae7bd5674631e",
@@ -752,7 +765,7 @@
# I'm sure there is a better path, but that works...
yarn_install(
name = "npm",
- frozen_lockfile = False,
+ frozen_lockfile = True,
package_json = "//:package.json",
symlink_node_modules = False,
yarn_lock = "//:yarn.lock",
@@ -1057,3 +1070,20 @@
"https://github.com/bazelbuild/buildtools/archive/refs/tags/4.2.4.tar.gz",
],
)
+
+http_archive(
+ name = "rules_pkg",
+ patch_args = ["-p1"],
+ patches = [
+ "//third_party:rules_pkg/0001-Fix-tree-artifacts.patch",
+ ],
+ sha256 = "62eeb544ff1ef41d786e329e1536c1d541bb9bcad27ae984d57f18f314018e66",
+ urls = [
+ "https://mirror.bazel.build/github.com/bazelbuild/rules_pkg/releases/download/0.6.0/rules_pkg-0.6.0.tar.gz",
+ "https://github.com/bazelbuild/rules_pkg/releases/download/0.6.0/rules_pkg-0.6.0.tar.gz",
+ ],
+)
+
+load("@rules_pkg//:deps.bzl", "rules_pkg_dependencies")
+
+rules_pkg_dependencies()
diff --git a/aos/events/logging/logfile_sorting.cc b/aos/events/logging/logfile_sorting.cc
index 1e7c817..a506850 100644
--- a/aos/events/logging/logfile_sorting.cc
+++ b/aos/events/logging/logfile_sorting.cc
@@ -1037,6 +1037,13 @@
next_boot_time.oldest_local_unreliable_monotonic_timestamp;
}
}
+
+ // Skip anything without a time in it.
+ if (boot_time.oldest_remote_unreliable_monotonic_timestamp ==
+ aos::monotonic_clock::max_time) {
+ continue;
+ }
+
source_boot_times.emplace_back(
std::make_tuple(boot_time_list.first, boot_time, max_boot_time));
@@ -1214,6 +1221,9 @@
std::vector<std::pair<std::string, BootPairTimes>>
destination_boot_times;
for (const auto &source_boot_uuid : source_node.second) {
+ CHECK_NE(source_boot_uuid.second
+ .oldest_remote_unreliable_monotonic_timestamp,
+ monotonic_clock::max_time);
destination_boot_times.emplace_back(source_boot_uuid);
}
diff --git a/aos/starter/BUILD b/aos/starter/BUILD
index 2186421..280a1c2 100644
--- a/aos/starter/BUILD
+++ b/aos/starter/BUILD
@@ -33,6 +33,7 @@
"//aos/events:event_loop",
"//aos/events:shm_event_loop",
"//aos/util:scoped_pipe",
+ "@boringssl//:crypto",
"@com_github_google_glog//:glog",
],
)
diff --git a/aos/starter/starter.fbs b/aos/starter/starter.fbs
index 4b66833..1fd990e 100644
--- a/aos/starter/starter.fbs
+++ b/aos/starter/starter.fbs
@@ -45,7 +45,10 @@
EXECV_ERR,
// Failed to change to the requested group
- SET_GRP_ERR
+ SET_GRP_ERR,
+
+ // Failed to either find the binary or open it for reading.
+ RESOLVE_ERR,
}
table Status {
@@ -73,6 +76,12 @@
// Indicates the reason the application is not running. Only valid if
// application is STOPPED.
last_stop_reason: LastStopReason (id: 6);
+
+ binary_sha256: string (id: 7);
+
+ // Resolved path to the binary executed. May be absolute or relative to the
+ // working directory of starter.
+ full_path: string (id: 8);
}
root_type Status;
diff --git a/aos/starter/starter_demo.py b/aos/starter/starter_demo.py
index 571e848..f8fa520 100755
--- a/aos/starter/starter_demo.py
+++ b/aos/starter/starter_demo.py
@@ -50,6 +50,6 @@
destination = f"{tmpdir}/aos/events/{basename}"
os.makedirs(os.path.dirname(destination), exist_ok=True)
shutil.copy(config, destination)
- shutil.copy(config, f"{tmpdir}/config.{suffix}")
+ shutil.copy(config, f"{tmpdir}/aos_config.{suffix}")
args = [tmpdir + "/starterd"]
subprocess.run(args, check=True, cwd=tmpdir)
diff --git a/aos/starter/subprocess.cc b/aos/starter/subprocess.cc
index c1eb618..76a22f2 100644
--- a/aos/starter/subprocess.cc
+++ b/aos/starter/subprocess.cc
@@ -6,7 +6,9 @@
#include <sys/types.h>
#include <sys/wait.h>
+#include "absl/strings/str_split.h"
#include "glog/logging.h"
+#include "openssl/sha.h"
namespace aos::starter {
@@ -92,6 +94,12 @@
start_timer_->Disable();
restart_timer_->Disable();
+ if (!UpdatePathAndChecksum()) {
+ stop_reason_ = aos::starter::LastStopReason::RESOLVE_ERR;
+ MaybeQueueRestart();
+ return;
+ }
+
status_pipes_ = util::ScopedPipe::MakePipe();
if (capture_stdout_) {
@@ -198,15 +206,15 @@
}
// argv[0] should be the program name
- args_.insert(args_.begin(), path_);
+ args_.insert(args_.begin(), full_path_);
std::vector<char *> cargs = CArgs();
- execvp(path_.c_str(), cargs.data());
+ execv(full_path_.c_str(), cargs.data());
// If we got here, something went wrong
status_pipes_.write->Write(
static_cast<uint32_t>(aos::starter::LastStopReason::EXECV_ERR));
- PLOG(WARNING) << "Could not execute " << name_ << " (" << path_ << ')';
+ PLOG(WARNING) << "Could not execute " << name_ << " (" << full_path_ << ')';
_exit(EXIT_FAILURE);
}
@@ -296,6 +304,15 @@
on_change_();
}
+void Application::MaybeQueueRestart() {
+ if (autorestart()) {
+ QueueStart();
+ } else {
+ status_ = aos::starter::State::STOPPED;
+ on_change_();
+ }
+}
+
std::vector<char *> Application::CArgs() {
std::vector<char *> cargs;
std::transform(args_.begin(), args_.end(), std::back_inserter(cargs),
@@ -345,10 +362,70 @@
}
}
+bool Application::UpdatePathAndChecksum() {
+ int fin = -1;
+ std::string test_path;
+ if (path_.find('/') != std::string::npos) {
+ test_path = path_;
+ fin = open(path_.c_str(), O_RDONLY);
+ } else {
+ char *path = secure_getenv("PATH");
+ for (std::string_view path_cmp : absl::StrSplit(path, ':')) {
+ test_path = absl::StrCat(path_cmp, "/", path_);
+ fin = open(test_path.c_str(), O_RDONLY);
+ if (fin != -1) break;
+ }
+ }
+ if (fin == -1) {
+ PLOG(WARNING) << "Failed to open binary '" << path_ << "' as file";
+ return false;
+ }
+
+ full_path_ = std::move(test_path);
+
+ // Hash iteratively to avoid reading the entire binary into memory
+ constexpr std::size_t kReadSize = 1024 * 16;
+
+ SHA256_CTX ctx;
+ CHECK_EQ(SHA256_Init(&ctx), 1);
+
+ std::array<uint8_t, kReadSize> buf;
+
+ while (true) {
+ const ssize_t result = read(fin, buf.data(), kReadSize);
+ PCHECK(result != -1);
+ if (result == 0) {
+ break;
+ } else {
+ CHECK_EQ(SHA256_Update(&ctx, buf.data(), result), 1);
+ }
+ }
+ PCHECK(close(fin) == 0);
+
+ std::array<uint8_t, SHA256_DIGEST_LENGTH> hash_buf;
+ CHECK_EQ(SHA256_Final(hash_buf.data(), &ctx), 1);
+
+ static constexpr std::string_view kHexTable = "0123456789abcdef";
+
+ static_assert(hash_buf.size() * 2 == kSha256HexStrSize);
+ for (std::size_t i = 0; i < hash_buf.size(); ++i) {
+ checksum_[i * 2] = kHexTable[(hash_buf[i] & 0xF0U) >> 4U];
+ checksum_[i * 2 + 1] = kHexTable[hash_buf[i] & 0x0FU];
+ }
+
+ return true;
+}
+
flatbuffers::Offset<aos::starter::ApplicationStatus>
Application::PopulateStatus(flatbuffers::FlatBufferBuilder *builder) {
CHECK_NOTNULL(builder);
auto name_fbs = builder->CreateString(name_);
+ auto full_path_fbs = builder->CreateString(full_path_);
+ flatbuffers::Offset<flatbuffers::String> binary_sha256_fbs;
+ if (pid_ != -1) {
+ binary_sha256_fbs =
+ builder->CreateString(checksum_.data(), checksum_.size());
+ }
aos::starter::ApplicationStatus::Builder status_builder(*builder);
status_builder.add_name(name_fbs);
@@ -360,6 +437,8 @@
if (pid_ != -1) {
status_builder.add_pid(pid_);
status_builder.add_id(id_);
+ status_builder.add_binary_sha256(binary_sha256_fbs);
+ status_builder.add_full_path(full_path_fbs);
}
status_builder.add_last_start_time(start_time_.time_since_epoch().count());
return status_builder.Finish();
@@ -441,12 +520,7 @@
LOG(WARNING) << "Failed to start '" << name_ << "' on pid " << pid_
<< " : Exited with status " << exit_code_.value();
}
- if (autorestart()) {
- QueueStart();
- } else {
- status_ = aos::starter::State::STOPPED;
- on_change_();
- }
+ MaybeQueueRestart();
break;
}
case aos::starter::State::RUNNING: {
@@ -458,12 +532,7 @@
<< " exited unexpectedly with status "
<< exit_code_.value();
}
- if (autorestart()) {
- QueueStart();
- } else {
- status_ = aos::starter::State::STOPPED;
- on_change_();
- }
+ MaybeQueueRestart();
break;
}
case aos::starter::State::STOPPING: {
diff --git a/aos/starter/subprocess.h b/aos/starter/subprocess.h
index 9ee9e31..ed4d0dd 100644
--- a/aos/starter/subprocess.h
+++ b/aos/starter/subprocess.h
@@ -75,6 +75,8 @@
bool autorestart() const { return autorestart_; }
+ std::string_view full_path() const { return full_path_; }
+
const std::string &GetStdout();
const std::string &GetStderr();
std::optional<int> exit_code() const { return exit_code_; }
@@ -91,6 +93,9 @@
void QueueStart();
+ // Queues start if autorestart set, otherwise moves state to stopped.
+ void MaybeQueueRestart();
+
// Copy flatbuffer vector of strings to vector of std::string.
static std::vector<std::string> FbsVectorToVector(
const flatbuffers::Vector<flatbuffers::Offset<flatbuffers::String>> &v);
@@ -106,11 +111,21 @@
// call).
std::vector<char *> CArgs();
+ // Resolves the path to the binary from the PATH environment variable. On
+ // success, updates full_path_ to the absolute path to the binary and the
+ // checksum_ to the hex-encoded sha256 hash of the file; returns true. On
+ // failure, returns false.
+ bool UpdatePathAndChecksum();
+
// Next unique id for all applications
static inline uint64_t next_id_ = 0;
+ static constexpr size_t kSha256HexStrSize = 256 / CHAR_BIT * 2;
+
std::string name_;
std::string path_;
+ std::string full_path_;
+ std::array<char, kSha256HexStrSize> checksum_{"DEADBEEF"};
std::vector<std::string> args_;
std::string user_name_;
std::optional<uid_t> user_;
diff --git a/aos/starter/subprocess_test.cc b/aos/starter/subprocess_test.cc
index 93fbf6a..ede39f8 100644
--- a/aos/starter/subprocess_test.cc
+++ b/aos/starter/subprocess_test.cc
@@ -49,6 +49,9 @@
event_loop.Run();
+ EXPECT_TRUE(echo_stdout.full_path() == "/bin/echo" ||
+ echo_stdout.full_path() == "/usr/bin/echo")
+ << echo_stdout.full_path();
ASSERT_EQ("abcdef\n", echo_stdout.GetStdout());
ASSERT_TRUE(echo_stdout.GetStderr().empty());
EXPECT_TRUE(observed_stopped);
diff --git a/debian/BUILD b/debian/BUILD
index 2aeabf2..3f13244 100644
--- a/debian/BUILD
+++ b/debian/BUILD
@@ -7,6 +7,10 @@
apache2_debs = "files",
)
load(
+ ":postgresql_amd64.bzl",
+ postgresql_amd64_debs = "files",
+)
+load(
":patch.bzl",
patch_debs = "files",
)
@@ -173,6 +177,28 @@
)
download_packages(
+ name = "download_postgresql_deps",
+ excludes = [
+ "adduser",
+ "debconf",
+ "debconf-2.0",
+ "libsystemd0",
+ "lsb-base",
+ "libstdc++6",
+ "libc-bin",
+ "libc-l10n",
+ "netbase",
+ "ucf",
+ "locales",
+ "locales-all",
+ ],
+ packages = [
+ "postgresql",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+)
+
+download_packages(
name = "download_patch_deps",
packages = [
"patch",
@@ -287,6 +313,12 @@
)
generate_deb_tarball(
+ name = "postgresql_amd64",
+ files = postgresql_amd64_debs,
+ target_compatible_with = ["@platforms//os:linux"],
+)
+
+generate_deb_tarball(
name = "patch",
files = patch_debs,
target_compatible_with = ["@platforms//os:linux"],
diff --git a/debian/postgresql_amd64.BUILD b/debian/postgresql_amd64.BUILD
new file mode 100644
index 0000000..c2f8331
--- /dev/null
+++ b/debian/postgresql_amd64.BUILD
@@ -0,0 +1,56 @@
+load("@bazel_skylib//rules:write_file.bzl", "write_file")
+
+TEMPLATE = """\
+#!/bin/bash
+
+# --- begin runfiles.bash initialization v2 ---
+# Copy-pasted from the Bazel Bash runfiles library v2.
+set -uo pipefail; f=bazel_tools/tools/bash/runfiles/runfiles.bash
+source "${RUNFILES_DIR:-/dev/null}/$f" 2>/dev/null || \
+ source "$(grep -sm1 "^$f " "${RUNFILES_MANIFEST_FILE:-/dev/null}" | cut -f2- -d' ')" 2>/dev/null || \
+ source "$0.runfiles/$f" 2>/dev/null || \
+ source "$(grep -sm1 "^$f " "$0.runfiles_manifest" | cut -f2- -d' ')" 2>/dev/null || \
+ source "$(grep -sm1 "^$f " "$0.exe.runfiles_manifest" | cut -f2- -d' ')" 2>/dev/null || \
+ { echo>&2 "ERROR: cannot find $f"; exit 1; }; f=; set -e
+# --- end runfiles.bash initialization v2 ---
+
+add_ld_library_path_for() {
+ local file="$1"
+ local dir
+ local resolved_file
+ if ! resolved_file="$(rlocation "postgresql_amd64/$file")"; then
+ echo "Couldn't find file postgresql_amd64/${file}" >&2
+ exit 1
+ fi
+ dir="$(dirname "${resolved_file}")"
+ export LD_LIBRARY_PATH="${dir}${LD_LIBRARY_PATH:+:$LD_LIBRARY_PATH}"
+}
+
+add_ld_library_path_for usr/lib/x86_64-linux-gnu/libbsd.so.0.11.3
+add_ld_library_path_for lib/x86_64-linux-gnu/libreadline.so.8.1
+
+exec $(rlocation postgresql_amd64/usr/lib/postgresql/13/bin/%s) "$@"
+"""
+
+[(
+ write_file(
+ name = "generate_%s_wrapper" % binary,
+ out = "%s.sh" % binary,
+ content = [TEMPLATE % binary],
+ ),
+ sh_binary(
+ name = binary,
+ srcs = ["%s.sh" % binary],
+ data = glob([
+ "usr/lib/**/*",
+ "lib/**/*",
+ ]),
+ visibility = ["//visibility:public"],
+ deps = [
+ "@bazel_tools//tools/bash/runfiles",
+ ],
+ ),
+) for binary in (
+ "postgres",
+ "initdb",
+)]
diff --git a/debian/postgresql_amd64.bzl b/debian/postgresql_amd64.bzl
new file mode 100644
index 0000000..6fc9ba5
--- /dev/null
+++ b/debian/postgresql_amd64.bzl
@@ -0,0 +1,39 @@
+files = {
+ "libbsd0_0.11.3-1_amd64.deb": "284a7b8dcfcad74770f57360721365317448b38ab773db542bf630e94e60c13e",
+ "libedit2_3.1-20191231-2+b1_amd64.deb": "ac545f6ad10ba791aca24b09255ad1d6d943e6bc7c5511d5998e104aee51c943",
+ "libffi7_3.3-6_amd64.deb": "30ca89bfddae5fa6e0a2a044f22b6e50cd17c4bc6bc850c579819aeab7101f0f",
+ "libgdbm-compat4_1.19-2_amd64.deb": "e62caed68b0ffaa03b5fa539d6fdc08c4151f66236d5878949bead0b71b7bb09",
+ "libgdbm6_1.19-2_amd64.deb": "e54cfe4d8b8f209bb7df31a404ce040f7c2f9b1045114a927a7e1061cdf90727",
+ "libgnutls30_3.7.1-5_amd64.deb": "20b0189b72ad4c791cf5b280c111d41ce071a04dab0e9a9d7daa9504a7a7b543",
+ "libhogweed6_3.7.3-1_amd64.deb": "6aab2e892cdb2dfba45707601bc6c3b19aa228f70ae5841017f14c3b0ca3d22f",
+ "libicu67_67.1-7_amd64.deb": "2bf5c46254f527865bfd6368e1120908755fa57d83634bd7d316c9b3cfd57303",
+ "libidn2-0_2.3.0-5_amd64.deb": "cb80cd769171537bafbb4a16c12ec427065795946b3415781bc9792e92d60b59",
+ "libldap-2.4-2_2.4.57+dfsg-3_amd64.deb": "4186d0d3f086202d391da49d1bb5ced6dde5eafba1dbcffef9a8e1238a7ef7c3",
+ "libllvm11_11.0.1-2_amd64.deb": "eaff3c8dd6039af90b8b6bdbf33433e35d8c808a7aa195d0e3800ef5e61affff",
+ "libmd0_1.0.3-3_amd64.deb": "9e425b3c128b69126d95e61998e1b5ef74e862dd1fc953d91eebcc315aea62ea",
+ "libnettle8_3.7.3-1_amd64.deb": "e4f8ec31ed14518b241eb7b423ad5ed3f4a4e8ac50aae72c9fd475c569582764",
+ "libp11-kit0_0.23.22-1_amd64.deb": "bfef5f31ee1c730e56e16bb62cc5ff8372185106c75bf1ed1756c96703019457",
+ "libperl5.32_5.32.1-4+deb11u2_amd64.deb": "224cafe65968deb83168113b74dff2d2f13b115a41d99eb209ed3b8f981df0b3",
+ "libpq5_13.5-0+deb11u1_amd64.deb": "0bfa1dc24e1275963961efdcc6d2ff4d2eec390d7acd5a6aee3162569ae1886c",
+ "libreadline8_8.1-1_amd64.deb": "162ba9fdcde81b5502953ed4d84b24e8ad4e380bbd02990ab1a0e3edffca3c22",
+ "libsasl2-2_2.1.27+dfsg-2.1+deb11u1_amd64.deb": "2e86ab7a3329aad4b7350a9b067fe8f80b680302f2f82d94f73f9bf075404460",
+ "libsasl2-modules-db_2.1.27+dfsg-2.1+deb11u1_amd64.deb": "122bf3de4ca0ec873bc35bdde1f21ec9d91ace4f5245c3b1240e077f866e1ae9",
+ "libtasn1-6_4.16.0-2_amd64.deb": "fd7a200100298c2556e67bdc1a5faf5cf21c3136fa47f381d7e9769233ee88a1",
+ "libtinfo6_6.2+20201114-2_amd64.deb": "aeaf942c71ecc0ed081efdead1a1de304dcd513a9fc06791f26992e76986597b",
+ "libunistring2_0.9.10-4_amd64.deb": "654433ad02d3a8b05c1683c6c29a224500bf343039c34dcec4e5e9515345e3d4",
+ "libuuid1_2.36.1-8+deb11u1_amd64.deb": "31250af4dd3b7d1519326a9a6764d1466a93d8f498cf6545058761ebc38b2823",
+ "libxml2_2.9.10+dfsg-6.7_amd64.deb": "023296a15e1a28607609cb15c7ca0dd8a25160f3e89a0da58368319c7e17d4e0",
+ "libxslt1.1_1.1.34-4_amd64.deb": "17eb62d8973867b61e7f8b21b5c16ed33e151799656e49caf670081707853fb8",
+ "libz3-4_4.8.10-1_amd64.deb": "7a38c2dd985eb9315857588ee06ff297e2b16de159dec85bd2777a43ebe9f458",
+ "openssl_1.1.1k-1+deb11u1_amd64.deb": "ed998755dabb96ffe107c2d41ce685ecbb4fa200f7825ff82c1092f8334bf3cb",
+ "perl-modules-5.32_5.32.1-4+deb11u2_all.deb": "6fa15be322c3c89ec4a07d704ad58d4a2d1aabf866135a859f6d8d58c59e9df4",
+ "perl_5.32.1-4+deb11u2_amd64.deb": "1cebc4516ed7c240b812c7bdd7e6ea0810f513152717ca17ce139ee0dfbc7b0d",
+ "postgresql-13_13.5-0+deb11u1_amd64.deb": "e475540f43756dc1c64de0a8a3b33f2c0e45b39610f091afbfe3b6ef72573c7b",
+ "postgresql-client-13_13.5-0+deb11u1_amd64.deb": "cd1779abafdee712d9ea4ebae62d873b61540fd76beab1cc86e604c12813d005",
+ "postgresql-client-common_225_all.deb": "a867f301751692f9ad127c1dd921c3bce7f3969bdf58c6bf38c57303d1b51d2c",
+ "postgresql-common_225_all.deb": "90216c317fd9f247d8fb1597fb4677cbdf2bbb83811213ce4344a44820449e66",
+ "postgresql_13+225_all.deb": "c8791bd0fd7cce76341cbd2c6ba98991a206441fe948534394239e95d102b4b8",
+ "readline-common_8.1-1_all.deb": "3f947176ef949f93e4ad5d76c067d33fa97cf90b62ee0748acb4f5f64790edc8",
+ "ssl-cert_1.1.0+nmu1_all.deb": "6f3b0c20b0a37b2b196d832910a754cf784f96854daa02a16f4ac46d366cdcb8",
+ "tzdata_2021a-1+deb11u2_all.deb": "4a34cbe17d391e6351386f3530b7ffd096c2cc8582e970f745addc636fa7c397",
+}
diff --git a/frc971/analysis/BUILD b/frc971/analysis/BUILD
index 20f1a01..9deec64 100644
--- a/frc971/analysis/BUILD
+++ b/frc971/analysis/BUILD
@@ -55,8 +55,10 @@
"//y2022/control_loops/superstructure:catapult_plotter",
"//y2022/control_loops/superstructure:climber_plotter",
"//y2022/control_loops/superstructure:intake_plotter",
+ "//y2022/control_loops/superstructure:superstructure_plotter",
"//y2022/control_loops/superstructure:turret_plotter",
"//y2022/localizer:localizer_plotter",
+ "//y2022/vision:vision_plotter",
],
)
diff --git a/frc971/analysis/plot_index.ts b/frc971/analysis/plot_index.ts
index f56a6bf..1c364c5 100644
--- a/frc971/analysis/plot_index.ts
+++ b/frc971/analysis/plot_index.ts
@@ -42,14 +42,18 @@
'org_frc971/y2021_bot3/control_loops/superstructure/superstructure_plotter';
import {plotTurret as plot2022Turret} from
'org_frc971/y2022/control_loops/superstructure/turret_plotter'
+import {plotSuperstructure as plot2022Superstructure} from
+ 'org_frc971/y2022/control_loops/superstructure/superstructure_plotter'
import {plotCatapult as plot2022Catapult} from
'org_frc971/y2022/control_loops/superstructure/catapult_plotter'
-import {plotIntake as plot2022Intake} from
+import {plotIntakeFront as plot2022IntakeFront, plotIntakeBack as plot2022IntakeBack} from
'org_frc971/y2022/control_loops/superstructure/intake_plotter'
import {plotClimber as plot2022Climber} from
'org_frc971/y2022/control_loops/superstructure/climber_plotter'
import {plotLocalizer as plot2022Localizer} from
'org_frc971/y2022/localizer/localizer_plotter'
+import {plotVision as plot2022Vision} from
+ 'org_frc971/y2022/vision/vision_plotter'
import {plotDemo} from 'org_frc971/aos/network/www/demo_plot';
import {plotData} from 'org_frc971/frc971/analysis/plot_data_utils';
@@ -116,8 +120,11 @@
['2020 Turret', new PlotState(plotDiv, plot2020Turret)],
['2020 Localizer', new PlotState(plotDiv, plot2020Localizer)],
['2022 Localizer', new PlotState(plotDiv, plot2022Localizer)],
+ ['2022 Vision', new PlotState(plotDiv, plot2022Vision)],
+ ['2022 Superstructure', new PlotState(plotDiv, plot2022Superstructure)],
['2022 Catapult', new PlotState(plotDiv, plot2022Catapult)],
- ['2022 Intake', new PlotState(plotDiv, plot2022Intake)],
+ ['2022 Intake Front', new PlotState(plotDiv, plot2022IntakeFront)],
+ ['2022 Intake Back', new PlotState(plotDiv, plot2022IntakeBack)],
['2022 Climber', new PlotState(plotDiv, plot2022Climber)],
['2022 Turret', new PlotState(plotDiv, plot2022Turret)],
['C++ Plotter', new PlotState(plotDiv, plotData)],
diff --git a/frc971/control_loops/aiming/BUILD b/frc971/control_loops/aiming/BUILD
new file mode 100644
index 0000000..f779b8e
--- /dev/null
+++ b/frc971/control_loops/aiming/BUILD
@@ -0,0 +1,22 @@
+cc_library(
+ name = "aiming",
+ srcs = ["aiming.cc"],
+ hdrs = ["aiming.h"],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//aos/logging",
+ "//frc971:constants",
+ "//frc971/control_loops:pose",
+ ],
+)
+
+cc_test(
+ name = "aiming_test",
+ srcs = ["aiming_test.cc"],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ ":aiming",
+ "//aos/testing:googletest",
+ ],
+)
diff --git a/frc971/control_loops/aiming/aiming.cc b/frc971/control_loops/aiming/aiming.cc
new file mode 100644
index 0000000..8229e13
--- /dev/null
+++ b/frc971/control_loops/aiming/aiming.cc
@@ -0,0 +1,132 @@
+#include "frc971/control_loops/aiming/aiming.h"
+
+#include "glog/logging.h"
+
+namespace frc971::control_loops::aiming {
+
+// Shooting-on-the-fly concept:
+// The current way that we manage shooting-on-the fly endeavors to be reasonably
+// simple, until we get a chance to see how the actual dynamics play out.
+// Essentially, we assume that the robot's velocity will represent a constant
+// offset to the ball's velocity over the entire trajectory to the goal and
+// then offset the target that we are pointing at based on that.
+// Let us assume that, if the robot shoots while not moving, regardless of shot
+// distance, the ball's average speed-over-ground to the target will be a
+// constant s_shot (this implies that if the robot is driving straight towards
+// the target, the actual ball speed-over-ground will be greater than s_shot).
+// We will define things in the robot's coordinate frame. We will be shooting
+// at a target that is at position (target_x, target_y) in the robot frame. The
+// robot is travelling at (v_robot_x, v_robot_y). In order to shoot the ball,
+// we need to generate some virtual target (virtual_x, virtual_y) that we will
+// shoot at as if we were standing still. The total time-of-flight to that
+// target will be t_shot = norm2(virtual_x, virtual_y) / s_shot.
+// we will have virtual_x + v_robot_x * t_shot = target_x, and the same
+// for y. This gives us three equations and three unknowns (virtual_x,
+// virtual_y, and t_shot), and given appropriate assumptions, can be solved
+// analytically. However, doing so is obnoxious and given appropriate functions
+// for t_shot may not be feasible. As such, instead of actually solving the
+// equation analytically, we will use an iterative solution where we maintain
+// a current virtual target estimate. We start with this estimate as if the
+// robot is stationary. We then use this estimate to calculate t_shot, and
+// calculate the next value for the virtual target.
+
+namespace {
+// This implements the iteration in the described shooting-on-the-fly algorithm.
+// robot_pose: Current robot pose.
+// robot_velocity: Current robot velocity, in the absolute field frame.
+// target_pose: Absolute goal Pose.
+// current_virtual_pose: Current estimate of where we want to shoot at.
+// ball_speed_over_ground: Approximate ground speed of the ball that we are
+// shooting.
+Pose IterateVirtualGoal(const Pose &robot_pose,
+ const Eigen::Vector3d &robot_velocity,
+ const Pose &target_pose,
+ const Pose ¤t_virtual_pose,
+ double ball_speed_over_ground) {
+ const double air_time = current_virtual_pose.Rebase(&robot_pose).xy_norm() /
+ ball_speed_over_ground;
+ const Eigen::Vector3d virtual_target =
+ target_pose.abs_pos() - air_time * robot_velocity;
+ return Pose(virtual_target, target_pose.abs_theta());
+}
+} // namespace
+
+TurretGoal AimerGoal(const ShotConfig &config, const RobotState &state) {
+ TurretGoal result;
+ // This code manages compensating the goal turret heading for the robot's
+ // current velocity, to allow for shooting on-the-fly.
+ // This works by solving for the correct turret angle numerically, since while
+ // we technically could do it analytically, doing so would both make it hard
+ // to make small changes (since it would force us to redo the math) and be
+ // error-prone since it'd be easy to make typos or other minor math errors.
+ Pose virtual_goal;
+ {
+ result.target_distance = config.goal.Rebase(&state.pose).xy_norm();
+ virtual_goal = config.goal;
+ if (config.mode == ShotMode::kShootOnTheFly) {
+ for (int ii = 0; ii < 3; ++ii) {
+ virtual_goal = IterateVirtualGoal(
+ state.pose, {state.velocity(0), state.velocity(1), 0}, config.goal,
+ virtual_goal, config.ball_speed_over_ground);
+ }
+ VLOG(1) << "Shooting-on-the-fly target position: "
+ << virtual_goal.abs_pos().transpose();
+ }
+ virtual_goal = virtual_goal.Rebase(&state.pose);
+ }
+
+ const double heading_to_goal = virtual_goal.heading();
+ result.virtual_shot_distance = virtual_goal.xy_norm();
+
+ // The following code all works to calculate what the rate of turn of the
+ // turret should be. The code only accounts for the rate of turn if we are
+ // aiming at a static target, which should be close enough to correct that it
+ // doesn't matter that it fails to account for the
+ // shooting-on-the-fly compensation.
+ const double rel_x = virtual_goal.rel_pos().x();
+ const double rel_y = virtual_goal.rel_pos().y();
+ const double squared_norm = rel_x * rel_x + rel_y * rel_y;
+ // rel_xdot and rel_ydot are the derivatives (with respect to time) of rel_x
+ // and rel_y. Since these are in the robot's coordinate frame, and since we
+ // are ignoring lateral velocity for this exercise, rel_ydot is zero, and
+ // rel_xdot is just the inverse of the robot's velocity.
+ // Note that rel_x and rel_y are in the robot frame.
+ const double rel_xdot = -Eigen::Vector2d(std::cos(state.pose.rel_theta()),
+ std::sin(state.pose.rel_theta()))
+ .dot(state.velocity);
+ const double rel_ydot = 0.0;
+
+ // If squared_norm gets to be too close to zero, just zero out the relevant
+ // term to prevent NaNs. Note that this doesn't address the chattering that
+ // would likely occur if we were to get excessively close to the target.
+ // Note that x and y terms are swapped relative to what you would normally see
+ // in the derivative of atan because xdot and ydot are the derivatives of
+ // robot_pos and we are working with the atan of (target_pos - robot_pos).
+ const double atan_diff =
+ (squared_norm < 1e-3) ? 0.0 : (rel_x * rel_ydot - rel_y * rel_xdot) /
+ squared_norm;
+ // heading = atan2(relative_y, relative_x) - robot_theta
+ // dheading / dt =
+ // (rel_x * rel_y' - rel_y * rel_x') / (rel_x^2 + rel_y^2) - dtheta / dt
+ const double dheading_dt = atan_diff - state.yaw_rate;
+
+ const double range =
+ config.turret_range.range() - config.anti_wrap_buffer * 2.0;
+ // Calculate a goal turret heading such that it is within +/- pi of the
+ // current position (i.e., a goal that would minimize the amount the turret
+ // would have to travel).
+ // We then check if this goal would bring us out of range of the valid angles,
+ // and if it would, we reset to be within +/- pi of zero.
+ double turret_heading =
+ state.last_turret_goal +
+ aos::math::NormalizeAngle(heading_to_goal - config.turret_zero_offset -
+ state.last_turret_goal);
+ if (std::abs(turret_heading - config.turret_range.middle()) > range / 2.0) {
+ turret_heading = aos::math::NormalizeAngle(turret_heading);
+ }
+ result.position = turret_heading;
+ result.velocity = dheading_dt;
+ return result;
+}
+
+} // namespace frc971::control_loops::aiming
diff --git a/frc971/control_loops/aiming/aiming.h b/frc971/control_loops/aiming/aiming.h
new file mode 100644
index 0000000..47fd06a
--- /dev/null
+++ b/frc971/control_loops/aiming/aiming.h
@@ -0,0 +1,62 @@
+#ifndef FRC971_CONTROL_LOOPS_AIMING_AIMING_H_
+#define FRC971_CONTROL_LOOPS_AIMING_AIMING_H_
+#include "frc971/constants.h"
+#include "frc971/control_loops/pose.h"
+
+// This library provides utilities associated with attempting to aim balls into
+// a goal.
+
+namespace frc971::control_loops::aiming {
+
+// Control modes for managing how we manage shooting on the fly.
+enum class ShotMode {
+ // Don't do any shooting-on-the-fly compensation--just point straight at the
+ // target. Primarily used in tests.
+ kStatic,
+ // Do do shooting-on-the-fly compensation.
+ kShootOnTheFly,
+};
+
+struct TurretGoal {
+ // Goal position (in radians) for the turret.
+ double position = 0.0;
+ // Goal velocity (in radians / sec) for the turret.
+ double velocity = 0.0;
+ // Physical distance from the robot's origin to the target we are shooting at,
+ // in meters.
+ double target_distance = 0.0;
+ // Shot distance to use when shooting on the fly (e.g., if driving towards the
+ // target, we will aim for a shorter shot than the actual physical distance),
+ // in meters.
+ double virtual_shot_distance = 0.0;
+};
+
+struct RobotState {
+ // Pose of the robot, in the field frame.
+ Pose pose;
+ // X/Y components of the robot velocity, in m/s.
+ Eigen::Vector2d velocity;
+ // Yaw rate of the robot, in rad / sec.
+ double yaw_rate;
+ // Last turret goal that we produced.
+ double last_turret_goal;
+};
+
+struct ShotConfig {
+ // Pose of the goal, in the field frame.
+ Pose goal;
+ ShotMode mode;
+ const constants::Range turret_range;
+ // We assume that the ball being shot has an ~constant speed over the ground,
+ // to allow us to estimate shooting-on-the fly values.
+ double ball_speed_over_ground;
+ // Amount of buffer to add on each side of the range to prevent wrapping/to
+ // prevent getting too close to the hard stops.
+ double anti_wrap_buffer;
+ // Offset from zero in the robot frame to zero for the turret.
+ double turret_zero_offset;
+};
+
+TurretGoal AimerGoal(const ShotConfig &config, const RobotState &state);
+}
+#endif // FRC971_CONTROL_LOOPS_AIMING_AIMING_H_
diff --git a/frc971/control_loops/aiming/aiming_test.cc b/frc971/control_loops/aiming/aiming_test.cc
new file mode 100644
index 0000000..c1f7367
--- /dev/null
+++ b/frc971/control_loops/aiming/aiming_test.cc
@@ -0,0 +1,160 @@
+#include "frc971/control_loops/aiming/aiming.h"
+
+#include "frc971/control_loops/pose.h"
+#include "gtest/gtest.h"
+#include "frc971/constants.h"
+
+namespace frc971::control_loops::aiming::testing {
+
+TEST(AimerTest, StandingStill) {
+ const Pose target({0.0, 0.0, 0.0}, 0.0);
+ Pose robot_pose({1.0, 0.0, 0.0}, 0.0);
+ const constants::Range range{-4.5, 4.5, -4.0, 4.0};
+ const double kBallSpeed = 10.0;
+ // Robot is ahead of target, should have to turret to 180 deg to shoot.
+ TurretGoal goal = AimerGoal(
+ ShotConfig{target, ShotMode::kShootOnTheFly, range, kBallSpeed, 0.0, 0.0},
+ RobotState{robot_pose, {0.0, 0.0}, 0.0, 0.0});
+ EXPECT_FLOAT_EQ(M_PI, goal.position);
+ EXPECT_FLOAT_EQ(0.0, goal.velocity);
+ EXPECT_FLOAT_EQ(1.0, goal.virtual_shot_distance);
+ EXPECT_FLOAT_EQ(1.0, goal.target_distance);
+
+ // If there is a turret offset, it should get compensated out.
+ goal = AimerGoal(ShotConfig{target, ShotMode::kShootOnTheFly, range,
+ kBallSpeed, 0.0, M_PI},
+ RobotState{robot_pose, {0.0, 0.0}, 0.0, 0.0});
+ EXPECT_FLOAT_EQ(0.0, goal.position);
+
+ robot_pose = Pose({-1.0, 0.0, 0.0}, 1.0);
+ goal = AimerGoal(
+ ShotConfig{target, ShotMode::kShootOnTheFly, range, kBallSpeed, 0.0, 0.0},
+ RobotState{robot_pose, {0.0, 0.0}, 0.0, 0.0});
+ EXPECT_FLOAT_EQ(-1.0, goal.position);
+ EXPECT_FLOAT_EQ(0.0, goal.velocity);
+ EXPECT_FLOAT_EQ(1.0, goal.virtual_shot_distance);
+ EXPECT_FLOAT_EQ(1.0, goal.target_distance);
+
+ // Test that we handle the case that where we are right on top of the target.
+ robot_pose = Pose({0.0, 0.0, 0.0}, 0.0);
+ goal = AimerGoal(
+ ShotConfig{target, ShotMode::kShootOnTheFly, range, kBallSpeed, 0.0, 0.0},
+ RobotState{robot_pose, {0.0, 0.0}, 0.0, 0.0});
+ EXPECT_FLOAT_EQ(0.0, goal.position);
+ EXPECT_FLOAT_EQ(0.0, goal.velocity);
+ EXPECT_FLOAT_EQ(0.0, goal.virtual_shot_distance);
+ EXPECT_FLOAT_EQ(0.0, goal.target_distance);
+}
+
+// Test that spinning in place results in correct velocity goals.
+TEST(AimerTest, SpinningRobot) {
+ const Pose target({0.0, 0.0, 0.0}, 0.0);
+ Pose robot_pose({-1.0, 0.0, 0.0}, 0.0);
+ const constants::Range range{-4.5, 4.5, -4.0, 4.0};
+ const double kBallSpeed = 10.0;
+ TurretGoal goal = AimerGoal(
+ ShotConfig{target, ShotMode::kShootOnTheFly, range, kBallSpeed, 0.0, 0.0},
+ RobotState{robot_pose, {0.0, 0.0}, 971.0, 0.0});
+ EXPECT_FLOAT_EQ(0.0, goal.position);
+ EXPECT_FLOAT_EQ(-971.0, goal.velocity);
+}
+
+// Tests that when we drive straight away from the target we don't have to spin
+// the turret.
+TEST(AimerTest, DrivingAwayFromTarget) {
+ const Pose target({0.0, 0.0, 0.0}, 0.0);
+ Pose robot_pose({-1.0, 0.0, 0.0}, 0.0);
+ const constants::Range range{-4.5, 4.5, -4.0, 4.0};
+ const double kBallSpeed = 10.0;
+ TurretGoal goal = AimerGoal(
+ ShotConfig{target, ShotMode::kStatic, range, kBallSpeed, 0.0, 0.0},
+ RobotState{robot_pose, {-1.0, 0.0}, 0.0, 0.0});
+ EXPECT_FLOAT_EQ(0.0, goal.position);
+ EXPECT_FLOAT_EQ(0.0, goal.velocity);
+ EXPECT_FLOAT_EQ(1.0, goal.virtual_shot_distance);
+ EXPECT_FLOAT_EQ(1.0, goal.target_distance);
+ // Next, try with shooting-on-the-fly enabled--because we are driving straight
+ // away from the target, only the goal distance should be impacted.
+ goal = AimerGoal(
+ ShotConfig{target, ShotMode::kShootOnTheFly, range, kBallSpeed, 0.0, 0.0},
+ RobotState{robot_pose, {-1.0, 0.0}, 0.0, 0.0});
+ EXPECT_FLOAT_EQ(0.0, goal.position);
+ EXPECT_FLOAT_EQ(0.0, goal.velocity);
+ EXPECT_FLOAT_EQ(1.111, goal.virtual_shot_distance);
+ EXPECT_FLOAT_EQ(1.0, goal.target_distance);
+}
+
+// Tests that when we drive perpendicular to the target, we do have to spin.
+TEST(AimerTest, DrivingLateralToTarget) {
+ const Pose target({0.0, 0.0, 0.0}, 0.0);
+ Pose robot_pose({0.0, -1.0, 0.0}, 0.0);
+ const constants::Range range{-4.5, 4.5, -4.0, 4.0};
+ const double kBallSpeed = 10.0;
+ TurretGoal goal = AimerGoal(
+ ShotConfig{target, ShotMode::kStatic, range, kBallSpeed, 0.0, 0.0},
+ RobotState{robot_pose, {1.0, 0.0}, 0.0, 0.0});
+ EXPECT_FLOAT_EQ(M_PI_2, goal.position);
+ EXPECT_FLOAT_EQ(1.0, goal.velocity);
+ EXPECT_FLOAT_EQ(1.0, goal.virtual_shot_distance);
+ EXPECT_FLOAT_EQ(1.0, goal.target_distance);
+ // Next, test with shooting-on-the-fly enabled, The goal numbers should all be
+ // slightly offset due to the robot velocity.
+ goal = AimerGoal(
+ ShotConfig{target, ShotMode::kShootOnTheFly, range, kBallSpeed, 0.0, 0.0},
+ RobotState{robot_pose, {1.0, 0.0}, 0.0, 0.0});
+ // Confirm that the turret heading goal is a bit more than pi / 2, but not by
+ // too much.
+ EXPECT_LT(M_PI_2 + 0.01, goal.position);
+ EXPECT_GT(M_PI_2 + 0.5, goal.position);
+ // Similarly, the turret velocity goal should be a bit less than 1.0,
+ // since the turret is no longer at exactly a right angle.
+ EXPECT_LT(0.9, goal.velocity);
+ EXPECT_GT(0.999, goal.velocity);
+ // And the distance to the goal should be a bit greater than 1.0.
+ EXPECT_LT(1.00001, goal.virtual_shot_distance);
+ EXPECT_GT(1.1, goal.virtual_shot_distance);
+ EXPECT_FLOAT_EQ(1.0, goal.target_distance);
+}
+
+// Confirms that when we move the turret heading so that it would be entirely
+// out of the normal range of motion that we send a valid (in-range) goal.
+// I.e., test that we have some hysteresis, but that it doesn't take us
+// out-of-range.
+TEST(AimerTest, WrapWhenOutOfRange) {
+ // Start ourselves needing a turret angle of 0.0.
+ const Pose target({0.0, 0.0, 0.0}, 0.0);
+ Pose robot_pose({-1.0, 0.0, 0.0}, 0.0);
+ const constants::Range range{-5.5, 5.5, -5.0, 5.0};
+ const double kBallSpeed = 10.0;
+ TurretGoal goal = AimerGoal(
+ ShotConfig{target, ShotMode::kShootOnTheFly, range, kBallSpeed, 0.0, 0.0},
+ RobotState{robot_pose, {0.0, 0.0}, 0.0, 0.0});
+ EXPECT_FLOAT_EQ(0.0, goal.position);
+ EXPECT_FLOAT_EQ(0.0, goal.velocity);
+
+ // Rotate a bit...
+ robot_pose = Pose({-1.0, 0.0, 0.0}, 2.0);
+ goal = AimerGoal(
+ ShotConfig{target, ShotMode::kShootOnTheFly, range, kBallSpeed, 0.0, 0.0},
+ RobotState{robot_pose, {0.0, 0.0}, 0.0, goal.position});
+ EXPECT_FLOAT_EQ(-2.0, goal.position);
+ EXPECT_FLOAT_EQ(0.0, goal.velocity);
+
+ // Rotate to the soft stop.
+ robot_pose = Pose({-1.0, 0.0, 0.0}, 4.0);
+ goal = AimerGoal(
+ ShotConfig{target, ShotMode::kShootOnTheFly, range, kBallSpeed, 0.0, 0.0},
+ RobotState{robot_pose, {0.0, 0.0}, 0.0, goal.position});
+ EXPECT_FLOAT_EQ(-4.0, goal.position);
+ EXPECT_FLOAT_EQ(0.0, goal.velocity);
+
+ // Rotate past the hard stop.
+ robot_pose = Pose({-1.0, 0.0, 0.0}, 0.0);
+ goal = AimerGoal(
+ ShotConfig{target, ShotMode::kShootOnTheFly, range, kBallSpeed, 0.0, 0.0},
+ RobotState{robot_pose, {0.0, 0.0}, 0.0, goal.position});
+ EXPECT_FLOAT_EQ(0.0, goal.position);
+ EXPECT_FLOAT_EQ(0.0, goal.velocity);
+}
+
+} // namespace frc971::control_loops::aiming::testing
diff --git a/frc971/control_loops/drivetrain/drivetrain.cc b/frc971/control_loops/drivetrain/drivetrain.cc
index 66a3dcd..4b36714 100644
--- a/frc971/control_loops/drivetrain/drivetrain.cc
+++ b/frc971/control_loops/drivetrain/drivetrain.cc
@@ -28,6 +28,11 @@
namespace control_loops {
namespace drivetrain {
+namespace {
+// Maximum variation to allow in the gyro when zeroing.
+constexpr double kMaxYawGyroZeroingRange = 0.05;
+}
+
DrivetrainFilters::DrivetrainFilters(const DrivetrainConfig<double> &dt_config,
::aos::EventLoop *event_loop,
LocalizerInterface *localizer)
@@ -204,9 +209,27 @@
break;
}
- ready_ = dt_config_.gyro_type == GyroType::SPARTAN_GYRO ||
- dt_config_.gyro_type == GyroType::FLIPPED_SPARTAN_GYRO ||
- imu_zeroer_.Zeroed();
+ switch (dt_config_.gyro_type) {
+ case GyroType::SPARTAN_GYRO:
+ case GyroType::FLIPPED_SPARTAN_GYRO:
+ if (!yaw_gyro_zero_.has_value()) {
+ yaw_gyro_zeroer_.AddData(last_gyro_rate_);
+ if (yaw_gyro_zeroer_.GetRange() < kMaxYawGyroZeroingRange) {
+ yaw_gyro_zero_ = yaw_gyro_zeroer_.GetAverage()(0);
+ }
+ }
+ ready_ = yaw_gyro_zero_.has_value();
+ if (ready_) {
+ last_gyro_rate_ = last_gyro_rate_ - yaw_gyro_zero_.value();
+ }
+ break;
+ case GyroType::IMU_X_GYRO:
+ case GyroType::IMU_Y_GYRO:
+ case GyroType::IMU_Z_GYRO:
+ case GyroType::FLIPPED_IMU_Z_GYRO:
+ ready_ = imu_zeroer_.Zeroed();
+ break;
+ }
// TODO(james): How aggressively can we fault here? If we fault to
// aggressively, we might have issues during startup if wpilib_interface takes
diff --git a/frc971/control_loops/drivetrain/drivetrain.h b/frc971/control_loops/drivetrain/drivetrain.h
index 52ae605..a06b965 100644
--- a/frc971/control_loops/drivetrain/drivetrain.h
+++ b/frc971/control_loops/drivetrain/drivetrain.h
@@ -138,6 +138,9 @@
// Last applied voltage.
Eigen::Matrix<double, 2, 1> last_voltage_;
Eigen::Matrix<double, 2, 1> last_last_voltage_;
+
+ std::optional<double> yaw_gyro_zero_;
+ zeroing::Averager<double, 200> yaw_gyro_zeroer_;
};
class DrivetrainLoop
diff --git a/frc971/control_loops/drivetrain/drivetrain_plotter.ts b/frc971/control_loops/drivetrain/drivetrain_plotter.ts
index deb300f..4b59dc0 100644
--- a/frc971/control_loops/drivetrain/drivetrain_plotter.ts
+++ b/frc971/control_loops/drivetrain/drivetrain_plotter.ts
@@ -20,6 +20,8 @@
'/drivetrain', 'frc971.control_loops.drivetrain.Status');
const output = aosPlotter.addMessageSource(
'/drivetrain', 'frc971.control_loops.drivetrain.Output');
+ const gyroReading = aosPlotter.addMessageSource(
+ '/drivetrain', 'frc971.sensors.GyroReading');
const imu = aosPlotter.addRawMessageSource(
'/drivetrain', 'frc971.IMUValuesBatch',
new ImuMessageHandler(conn.getSchema('frc971.IMUValuesBatch')));
@@ -323,6 +325,7 @@
gyroY.setColor(GREEN);
const gyroZ = gyroPlot.addMessageLine(imu, ['gyro_z']);
gyroZ.setColor(BLUE);
+ gyroPlot.addMessageLine(gyroReading, ['velocity']).setColor(BLUE);
// IMU States
const imuStatePlot =
diff --git a/frc971/control_loops/drivetrain/hybrid_ekf.h b/frc971/control_loops/drivetrain/hybrid_ekf.h
index 2a972b6..fcbed76 100644
--- a/frc971/control_loops/drivetrain/hybrid_ekf.h
+++ b/frc971/control_loops/drivetrain/hybrid_ekf.h
@@ -330,6 +330,12 @@
}
return X_hat();
}
+ std::optional<State> OldestState() {
+ if (observations_.empty()) {
+ return std::nullopt;
+ }
+ return observations_.begin()->X_hat;
+ }
// Returns the most recent input vector.
Input MostRecentInput() {
diff --git a/frc971/control_loops/profiled_subsystem.h b/frc971/control_loops/profiled_subsystem.h
index 5a450ec..1343770 100644
--- a/frc971/control_loops/profiled_subsystem.h
+++ b/frc971/control_loops/profiled_subsystem.h
@@ -36,6 +36,7 @@
: loop_(::std::move(loop)), estimators_(::std::move(estimators)) {
zeroed_.fill(false);
unprofiled_goal_.setZero();
+ X_hat_.setZero();
}
// Returns whether an error has occured
@@ -95,11 +96,14 @@
return unprofiled_goal_(row, col);
}
- // Returns the current state estimate.
+ // Returns the current state estimate after the most recent Correct. This
+ // does not change when Predict is run.
const Eigen::Matrix<double, number_of_states, 1> &X_hat() const {
- return loop_->X_hat();
+ return X_hat_;
}
- double X_hat(int row, int col) const { return loop_->X_hat(row, col); }
+ double X_hat(int row, int col) const { return X_hat()(row, col); }
+ // Returns a mutable reference to the current state of the actual kalman
+ // filter state. Note: changing this won't change X_hat() immediately.
double &mutable_X_hat(int row, int col) const {
return loop_->mutable_X_hat(row, col);
}
@@ -127,6 +131,8 @@
// The goal that the profile tries to reach.
Eigen::Matrix<double, number_of_states, 1> unprofiled_goal_;
+ Eigen::Matrix<double, number_of_states, 1> X_hat_;
+
bool initialized_ = false;
// If true, the subclass should reset in Update. It should then clear this
@@ -277,13 +283,13 @@
builder.add_zeroed(this->zeroed());
// We don't know, so default to the bad case.
- builder.add_position(this->X_hat(0, 0));
- builder.add_velocity(this->X_hat(1, 0));
+ builder.add_position(this->X_hat_(0, 0));
+ builder.add_velocity(this->X_hat_(1, 0));
builder.add_goal_position(this->goal(0, 0));
builder.add_goal_velocity(this->goal(1, 0));
builder.add_unprofiled_goal_position(this->unprofiled_goal(0, 0));
builder.add_unprofiled_goal_velocity(this->unprofiled_goal(1, 0));
- builder.add_voltage_error(this->X_hat(2, 0));
+ builder.add_voltage_error(this->X_hat_(2, 0));
builder.add_calculated_velocity(
(position() - last_position_) /
::aos::time::DurationInSeconds(this->loop_->plant().coefficients().dt));
@@ -305,6 +311,7 @@
if (this->estimators_[0].error()) {
AOS_LOG(ERROR, "zeroing error\n");
+ this->X_hat_ = this->loop_->X_hat();
return;
}
@@ -324,6 +331,7 @@
this->Y_ << new_position.encoder();
this->Y_ += this->offset_;
this->loop_->Correct(Y_);
+ this->X_hat_ = this->loop_->X_hat();
}
template <class ZeroingEstimator>
@@ -375,6 +383,7 @@
this->loop_->mutable_X_hat(0, 0) = Y_(0, 0);
this->loop_->mutable_X_hat(1, 0) = 0.0;
this->loop_->mutable_X_hat(2, 0) = 0.0;
+ this->X_hat_.setZero();
this->should_reset_ = false;
}
diff --git a/frc971/control_loops/python/constants.py b/frc971/control_loops/python/constants.py
index b515626..0a3ad18 100644
--- a/frc971/control_loops/python/constants.py
+++ b/frc971/control_loops/python/constants.py
@@ -33,6 +33,7 @@
Robot2019 = RobotType(width=0.65, length=0.8)
Robot2020 = RobotType(width=0.8128, length=0.8636) # 32 in x 34 in
Robot2021 = Robot2020
+Robot2022 = Robot2021
FIELDS = {
"2019 Field":
@@ -116,14 +117,25 @@
length=4.572,
robot=Robot2021,
field_id="autonav_bounce"),
+ "2022 Field":
+ FieldType(
+ "2022 Field",
+ tags=[],
+ year=2022,
+ width=16.4592,
+ length=8.2296,
+ robot=Robot2022,
+ field_id="2022"),
}
-FIELD = FIELDS["2020 Field"]
+FIELD = FIELDS["2022 Field"]
def get_json_folder(field):
if field.year == 2020 or field.year == 2021:
return "y2020/actors/splines"
+ elif field.year == 2022:
+ return "y2022/actors/splines"
else:
return "frc971/control_loops/python/spline_jsons"
diff --git a/frc971/control_loops/python/field_images/2022.png b/frc971/control_loops/python/field_images/2022.png
new file mode 100644
index 0000000..68087bd
--- /dev/null
+++ b/frc971/control_loops/python/field_images/2022.png
Binary files differ
diff --git a/frc971/control_loops/python/path_edit.py b/frc971/control_loops/python/path_edit.py
index df460d3..35a670c 100755
--- a/frc971/control_loops/python/path_edit.py
+++ b/frc971/control_loops/python/path_edit.py
@@ -7,7 +7,6 @@
import gi
import numpy as np
gi.require_version('Gtk', '3.0')
-gi.require_version('Gdk', '3.0')
from gi.repository import Gdk, Gtk, GLib
import cairo
from libspline import Spline
@@ -57,7 +56,7 @@
self.held_x = 0
self.spline_edit = -1
- self.transform = cairo.Matrix()
+ self.zoom_transform = cairo.Matrix()
self.set_events(Gdk.EventMask.BUTTON_PRESS_MASK
| Gdk.EventMask.BUTTON_PRESS_MASK
@@ -73,16 +72,28 @@
self.field.field_id + ".png")
except cairo.Error:
self.field_png = None
+
self.queue_draw()
+ def invert(self, transform):
+ xx, yx, xy, yy, x0, y0 = transform
+ matrix = cairo.Matrix(xx, yx, xy, yy, x0, y0)
+ matrix.invert()
+ return matrix
+
# returns the transform from widget space to field space
@property
def input_transform(self):
- xx, yx, xy, yy, x0, y0 = self.transform
- matrix = cairo.Matrix(xx, yx, xy, yy, x0, y0)
# the transform for input needs to be the opposite of the transform for drawing
- matrix.invert()
- return matrix
+ return self.invert(self.field_transform.multiply(self.zoom_transform))
+
+ @property
+ def field_transform(self):
+ field_transform = cairo.Matrix()
+ field_transform.scale(1, -1) # flipped y-axis
+ field_transform.scale(1 / self.pxToM_scale(), 1 / self.pxToM_scale())
+ field_transform.translate(self.field.width / 2, -1 * self.field.length / 2)
+ return field_transform
# returns the scale from pixels in field space to meters in field space
def pxToM_scale(self):
@@ -97,19 +108,19 @@
return m / self.pxToM_scale()
def draw_robot_at_point(self, cr, i, p, spline):
- p1 = [self.mToPx(spline.Point(i)[0]), self.mToPx(spline.Point(i)[1])]
+ p1 = [spline.Point(i)[0], spline.Point(i)[1]]
p2 = [
- self.mToPx(spline.Point(i + p)[0]),
- self.mToPx(spline.Point(i + p)[1])
+ spline.Point(i + p)[0],
+ spline.Point(i + p)[1]
]
#Calculate Robot
distance = np.sqrt((p2[1] - p1[1])**2 + (p2[0] - p1[0])**2)
x_difference_o = p2[0] - p1[0]
y_difference_o = p2[1] - p1[1]
- x_difference = x_difference_o * self.mToPx(
+ x_difference = x_difference_o * (
self.field.robot.length / 2) / distance
- y_difference = y_difference_o * self.mToPx(
+ y_difference = y_difference_o * (
self.field.robot.length / 2) / distance
front_middle = []
@@ -123,9 +134,9 @@
slope = [-(1 / x_difference_o) / (1 / y_difference_o)]
angle = np.arctan(slope)
- x_difference = np.sin(angle[0]) * self.mToPx(
+ x_difference = np.sin(angle[0]) * (
self.field.robot.width / 2)
- y_difference = np.cos(angle[0]) * self.mToPx(
+ y_difference = np.cos(angle[0]) * (
self.field.robot.width / 2)
front_1 = []
@@ -144,9 +155,9 @@
back_2.append(back_middle[0] + x_difference)
back_2.append(back_middle[1] + y_difference)
- x_difference = x_difference_o * self.mToPx(
+ x_difference = x_difference_o * (
self.field.robot.length / 2 + ROBOT_SIDE_TO_BALL_CENTER) / distance
- y_difference = y_difference_o * self.mToPx(
+ y_difference = y_difference_o * (
self.field.robot.length / 2 + ROBOT_SIDE_TO_BALL_CENTER) / distance
#Calculate Ball
@@ -154,9 +165,9 @@
ball_center.append(p1[0] + x_difference)
ball_center.append(p1[1] + y_difference)
- x_difference = x_difference_o * self.mToPx(
+ x_difference = x_difference_o * (
self.field.robot.length / 2 + ROBOT_SIDE_TO_HATCH_PANEL) / distance
- y_difference = y_difference_o * self.mToPx(
+ y_difference = y_difference_o * (
self.field.robot.length / 2 + ROBOT_SIDE_TO_HATCH_PANEL) / distance
#Calculate Panel
@@ -164,8 +175,8 @@
panel_center.append(p1[0] + x_difference)
panel_center.append(p1[1] + y_difference)
- x_difference = np.sin(angle[0]) * self.mToPx(HATCH_PANEL_WIDTH / 2)
- y_difference = np.cos(angle[0]) * self.mToPx(HATCH_PANEL_WIDTH / 2)
+ x_difference = np.sin(angle[0]) * (HATCH_PANEL_WIDTH / 2)
+ y_difference = np.cos(angle[0]) * (HATCH_PANEL_WIDTH / 2)
panel_1 = []
panel_1.append(panel_center[0] + x_difference)
@@ -188,7 +199,7 @@
set_color(cr, palette["ORANGE"], 0.5)
cr.move_to(back_middle[0], back_middle[1])
cr.line_to(ball_center[0], ball_center[1])
- cr.arc(ball_center[0], ball_center[1], self.mToPx(BALL_RADIUS), 0,
+ cr.arc(ball_center[0], ball_center[1], BALL_RADIUS, 0,
2 * np.pi)
cr.stroke()
@@ -201,23 +212,24 @@
cr.set_source_rgba(0, 0, 0, 1)
def do_draw(self, cr): # main
- cr.set_matrix(self.transform.multiply(cr.get_matrix()))
+ cr.set_matrix(self.field_transform.multiply(self.zoom_transform).multiply(cr.get_matrix()))
cr.save()
set_color(cr, palette["BLACK"])
- cr.set_line_width(1.0)
- cr.rectangle(0, 0, self.mToPx(self.field.width),
- self.mToPx(self.field.length))
+ cr.set_line_width(self.pxToM(2))
+ cr.rectangle(-0.5 * self.field.width, -0.5 * self.field.length, self.field.width,
+ self.field.length)
cr.set_line_join(cairo.LINE_JOIN_ROUND)
cr.stroke()
if self.field_png:
cr.save()
+ cr.translate(-0.5 * self.field.width, 0.5 * self.field.length)
cr.scale(
- self.mToPx(self.field.width) / self.field_png.get_width(),
- self.mToPx(self.field.length) / self.field_png.get_height(),
+ self.field.width / self.field_png.get_width(),
+ -self.field.length / self.field_png.get_height(),
)
cr.set_source_surface(self.field_png)
cr.paint()
@@ -225,11 +237,11 @@
# update everything
- cr.set_line_width(2.0)
+ cr.set_line_width(self.pxToM(2))
if self.mode == Mode.kPlacing or self.mode == Mode.kViewing:
set_color(cr, palette["BLACK"])
for i, point in enumerate(self.points.getPoints()):
- draw_px_x(cr, self.mToPx(point[0]), self.mToPx(point[1]), 10)
+ draw_px_x(cr, point[0], point[1], self.pxToM(5))
set_color(cr, palette["WHITE"])
elif self.mode == Mode.kEditing:
set_color(cr, palette["BLACK"])
@@ -237,17 +249,17 @@
self.draw_splines(cr)
for i, points in enumerate(self.points.getSplines()):
points = [
- np.array([self.mToPx(x), self.mToPx(y)])
+ np.array([x, y])
for (x, y) in points
]
- draw_control_points(cr, points)
+ draw_control_points(cr, points, width=self.pxToM(10), radius=self.pxToM(4))
p0, p1, p2, p3, p4, p5 = points
first_tangent = p0 + 2.0 * (p1 - p0)
second_tangent = p5 + 2.0 * (p4 - p5)
cr.set_source_rgb(0, 0.5, 0)
cr.move_to(p0[0], p0[1])
- cr.set_line_width(1.0)
+ cr.set_line_width(self.pxToM(1.0))
cr.line_to(first_tangent[0], first_tangent[1])
cr.move_to(first_tangent[0], first_tangent[1])
cr.line_to(p2[0], p2[1])
@@ -259,27 +271,27 @@
cr.line_to(p3[0], p3[1])
cr.stroke()
- cr.set_line_width(2.0)
+ cr.set_line_width(self.pxToM(2))
set_color(cr, palette["WHITE"])
cr.paint_with_alpha(0.2)
- draw_px_cross(cr, self.mousex, self.mousey, 10)
+ draw_px_cross(cr, self.mousex, self.mousey, self.pxToM(8))
cr.restore()
def draw_splines(self, cr):
for i, spline in enumerate(self.points.getLibsplines()):
- for k in np.linspace(0.01, 1, 100):
+ for k in np.linspace(0.02, 1, 200):
cr.move_to(
- self.mToPx(spline.Point(k - 0.01)[0]),
- self.mToPx(spline.Point(k - 0.01)[1]))
+ spline.Point(k - 0.008)[0],
+ spline.Point(k - 0.008)[1])
cr.line_to(
- self.mToPx(spline.Point(k)[0]),
- self.mToPx(spline.Point(k)[1]))
+ spline.Point(k)[0],
+ spline.Point(k)[1])
cr.stroke()
if i == 0:
- self.draw_robot_at_point(cr, 0.00, 0.01, spline)
- self.draw_robot_at_point(cr, 1, 0.01, spline)
+ self.draw_robot_at_point(cr, 0, 0.008, spline)
+ self.draw_robot_at_point(cr, 1, 0.008, spline)
def export_json(self, file_name):
self.path_to_export = os.path.join(
@@ -394,8 +406,8 @@
if self.mode == Mode.kEditing:
if self.index_of_edit > -1 and self.held_x != self.mousex:
self.points.setSplines(self.spline_edit, self.index_of_edit,
- self.pxToM(self.mousex),
- self.pxToM(self.mousey))
+ self.mousex,
+ self.mousey)
self.points.splineExtrapolate(self.spline_edit)
@@ -411,7 +423,7 @@
if self.mode == Mode.kPlacing:
if self.points.add_point(
- self.pxToM(self.mousex), self.pxToM(self.mousey)):
+ self.mousex, self.mousey):
self.mode = Mode.kEditing
self.graph.schedule_recalculate(self.points)
elif self.mode == Mode.kEditing:
@@ -421,7 +433,7 @@
# Get clicked point
# Find nearest
# Move nearest to clicked
- cur_p = [self.pxToM(self.mousex), self.pxToM(self.mousey)]
+ cur_p = [self.mousex, self.mousey]
# Get the distance between each for x and y
# Save the index of the point closest
nearest = 1 # Max distance away a the selected point can be in meters
@@ -448,23 +460,24 @@
event.x, event.y)
dif_x = self.mousex - old_x
dif_y = self.mousey - old_y
- difs = np.array([self.pxToM(dif_x), self.pxToM(dif_y)])
+ difs = np.array([dif_x, dif_y])
if self.mode == Mode.kEditing and self.spline_edit != -1:
self.points.updates_for_mouse_move(self.index_of_edit,
self.spline_edit,
- self.pxToM(self.mousex),
- self.pxToM(self.mousey), difs)
+ self.mousex,
+ self.mousey, difs)
self.points.update_lib_spline()
self.graph.schedule_recalculate(self.points)
self.queue_draw()
def do_scroll_event(self, event):
+
self.mousex, self.mousey = self.input_transform.transform_point(
event.x, event.y)
- step_size = 20 # px
+ step_size = self.pxToM(20) # px
if event.direction == Gdk.ScrollDirection.UP:
# zoom out
@@ -475,32 +488,27 @@
else:
return
- apparent_width, apparent_height = self.transform.transform_distance(
- self.mToPx(FIELD.width), self.mToPx(FIELD.length))
- scale = (apparent_width + scale_by) / apparent_width
-
- # scale from point in field coordinates
- point = self.mousex, self.mousey
+ scale = (self.field.width + scale_by) / self.field.width
# This restricts the amount it can be scaled.
- if self.transform.xx <= 0.75:
+ if self.zoom_transform.xx <= 0.5:
scale = max(scale, 1)
- elif self.transform.xx >= 16:
+ elif self.zoom_transform.xx >= 16:
scale = min(scale, 1)
# move the origin to point
- self.transform.translate(point[0], point[1])
+ self.zoom_transform.translate(event.x, event.y)
# scale from new origin
- self.transform.scale(scale, scale)
+ self.zoom_transform.scale(scale, scale)
# move back
- self.transform.translate(-point[0], -point[1])
+ self.zoom_transform.translate(-event.x, -event.y)
# snap to the edge when near 1x scaling
- if 0.99 < self.transform.xx < 1.01 and -50 < self.transform.x0 < 50:
- self.transform.x0 = 0
- self.transform.y0 = 0
+ if 0.99 < self.zoom_transform.xx < 1.01 and -50 < self.zoom_transform.x0 < 50:
+ self.zoom_transform.x0 = 0
+ self.zoom_transform.y0 = 0
print("snap")
self.queue_draw()
diff --git a/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h b/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h
index 04d93c4..65135d2 100644
--- a/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h
+++ b/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h
@@ -86,11 +86,12 @@
// Returns the current position
double position() const { return profiled_subsystem_.position(); }
+ // Returns the most recently corrected state.
Eigen::Vector3d estimated_state() const {
return profiled_subsystem_.X_hat();
}
- double estimated_position() const { return profiled_subsystem_.X_hat(0, 0); }
- double estimated_velocity() const { return profiled_subsystem_.X_hat(1, 0); }
+ double estimated_position() const { return estimated_state()(0, 0); }
+ double estimated_velocity() const { return estimated_state()(1, 0); }
// Corrects the internal state, adjusts limits, and sets nominal goals.
// Returns true if the controller should run.
@@ -126,6 +127,8 @@
void TriggerEstimatorError() { profiled_subsystem_.TriggerEstimatorError(); }
+ void Estop() { state_ = State::ESTOP; }
+
void set_controller_index(int index) {
profiled_subsystem_.set_controller_index(index);
}
diff --git a/frc971/input/joystick_state.fbs b/frc971/input/joystick_state.fbs
index 2f48bdf..49d2690 100644
--- a/frc971/input/joystick_state.fbs
+++ b/frc971/input/joystick_state.fbs
@@ -1,5 +1,7 @@
namespace aos;
+enum MatchType : byte { kNone, kPractice, kQualification, kElimination }
+
table Joystick {
// A bitmask of the butotn state.
buttons:ushort (id: 0);
@@ -44,6 +46,14 @@
// String corresponding to the game data string
game_data:string (id: 10);
+
+ // Driver station location.
+ location:ubyte (id: 11);
+
+ match_number:int (id: 12);
+ replay_number:int (id: 13);
+ match_type:MatchType (id: 14);
+ event_name:string (id: 15);
}
root_type JoystickState;
diff --git a/frc971/raspi/rootfs/README.md b/frc971/raspi/rootfs/README.md
index b972038..a349eb5 100644
--- a/frc971/raspi/rootfs/README.md
+++ b/frc971/raspi/rootfs/README.md
@@ -10,7 +10,7 @@
## Build the real-time kernel using `build_kernel.sh`
- Checkout the real-time kernel source code, e.g.,
- `cd CODE_DIR`
+ `cd CODE_DIR`, where CODE_DIR is the directory containing the FRC971 code
`git clone git@github.com:frc971/linux.git`
`git checkout frc971-5.10-pi4-rt branch`
@@ -18,6 +18,13 @@
`cd ROOTFS_DIR` (where ROOTFS_DIR -> //frc971/raspi/rootfs)
`./build_kernel.sh CODE_DIR/linux kernel_5.10.tar.gz`
+## Build the ADIS16505 overlay file (adis16505.ko)
+
+- Make sure the linux kernel source code is checked out at CODE_DIR/linux
+- cd //y2022/localizer/kernel
+- `make`
+- copy that file to this directory (//frc971/raspi/rootfs)
+
## Download the Raspberry Pi OS
Download the appropriate Raspberry Pi OS image, e.g.,
diff --git a/frc971/raspi/rootfs/modify_rootfs.sh b/frc971/raspi/rootfs/modify_rootfs.sh
index 15bdd80..c3582ea 100755
--- a/frc971/raspi/rootfs/modify_rootfs.sh
+++ b/frc971/raspi/rootfs/modify_rootfs.sh
@@ -4,6 +4,19 @@
# Full path to Raspberry Pi Bullseye disk image
IMAGE="2022-01-28-raspios-bullseye-arm64-lite.img"
+MOD_IMAGE_NAME=`echo ${IMAGE} | sed s/.img/-frc-mods.img/`
+
+if [ ! -f "$IMAGE" ]; then
+ echo "Attempting to use already modified image"
+ if [ ! -f "$MOD_IMAGE_NAME" ]; then
+ echo "Must provide image filename."
+ echo "Couldn't find $IMAGE or $MOD_IMAGE_NAME"
+ exit 1
+ fi
+ echo "Using already modified image: ${MOD_IMAGE_NAME}"
+ IMAGE=$MOD_IMAGE_NAME
+fi
+
# Kernel built with build_kernel.sh
KERNEL="kernel_5.10.tar.gz"
BOOT_PARTITION="${IMAGE}.boot_partition"
@@ -116,6 +129,7 @@
# Add a file to show when this image was last modified and by whom
TIMESTAMP_FILE="${PARTITION}/home/pi/.ImageModifiedDate.txt"
echo "Date modified:"`date` > "${TIMESTAMP_FILE}"
+echo "Image file: ${IMAGE}" >> "${TIMESTAMP_FILE}"
echo "Git tag: "`git rev-parse HEAD` >> "${TIMESTAMP_FILE}"
echo "User: "`whoami` >> "${TIMESTAMP_FILE}"
@@ -125,6 +139,7 @@
sudo umount -l "${PARTITION}"
rmdir "${PARTITION}"
-# Move the image to a different name, to indicated we've modified it
-MOD_IMAGE_NAME=`echo ${IMAGE} | sed s/.img/-frc-mods.img/`
-mv ${IMAGE} ${MOD_IMAGE_NAME}
+# Move the image to a different name, to indicate we've modified it
+if [ ${IMAGE} != ${MOD_IMAGE_NAME} ]; then
+ mv ${IMAGE} ${MOD_IMAGE_NAME}
+fi
diff --git a/frc971/vision/calibration_accumulator.cc b/frc971/vision/calibration_accumulator.cc
index 89945b0..ac1946c 100644
--- a/frc971/vision/calibration_accumulator.cc
+++ b/frc971/vision/calibration_accumulator.cc
@@ -38,6 +38,18 @@
imu_points_.emplace_back(distributed_now, std::make_pair(gyro, accel));
}
+void CalibrationData::AddTurret(
+ aos::distributed_clock::time_point distributed_now, Eigen::Vector2d state) {
+ // We want the turret to be known too when solving. But, we don't know if we
+ // are going to have a turret until we get the first reading. In that case,
+ // blow away any camera readings from before.
+ while (!rot_trans_points_.empty() &&
+ rot_trans_points_[0].first < distributed_now) {
+ rot_trans_points_.erase(rot_trans_points_.begin());
+ }
+ turret_points_.emplace_back(distributed_now, state);
+}
+
void CalibrationData::ReviewData(CalibrationDataObserver *observer) const {
size_t next_imu_point = 0;
size_t next_camera_point = 0;
diff --git a/frc971/vision/calibration_accumulator.h b/frc971/vision/calibration_accumulator.h
index 6d42708..e4f9c8a 100644
--- a/frc971/vision/calibration_accumulator.h
+++ b/frc971/vision/calibration_accumulator.h
@@ -26,6 +26,11 @@
// corresponding angular velocity and linear acceleration vectors wa.
virtual void UpdateIMU(aos::distributed_clock::time_point t,
std::pair<Eigen::Vector3d, Eigen::Vector3d> wa) = 0;
+
+ // Observes a turret sample at the corresponding time t, and with the
+ // corresponding state.
+ virtual void UpdateTurret(aos::distributed_clock::time_point t,
+ Eigen::Vector2d state) = 0;
};
// Class to both accumulate and replay camera and IMU data in time order.
@@ -40,12 +45,19 @@
void AddImu(aos::distributed_clock::time_point distributed_now,
Eigen::Vector3d gyro, Eigen::Vector3d accel);
+ // Adds a turret reading (position; velocity) to the list at the provided
+ // time.
+ void AddTurret(aos::distributed_clock::time_point distributed_now,
+ Eigen::Vector2d state);
+
// Processes the data points by calling UpdateCamera and UpdateIMU in time
// order.
void ReviewData(CalibrationDataObserver *observer) const;
size_t camera_samples_size() const { return rot_trans_points_.size(); }
+ size_t turret_samples() const { return turret_points_.size(); }
+
private:
std::vector<std::pair<aos::distributed_clock::time_point,
std::pair<Eigen::Vector3d, Eigen::Vector3d>>>
@@ -56,6 +68,10 @@
std::vector<std::pair<aos::distributed_clock::time_point,
std::pair<Eigen::Vector3d, Eigen::Vector3d>>>
rot_trans_points_;
+
+ // Turret state as a timestamp and [x, v].
+ std::vector<std::pair<aos::distributed_clock::time_point, Eigen::Vector2d>>
+ turret_points_;
};
// Class to register image and IMU callbacks in AOS and route them to the
diff --git a/frc971/vision/extrinsics_calibration.cc b/frc971/vision/extrinsics_calibration.cc
index df2c4b9..a71f14d 100644
--- a/frc971/vision/extrinsics_calibration.cc
+++ b/frc971/vision/extrinsics_calibration.cc
@@ -51,11 +51,13 @@
typedef Eigen::Transform<Scalar, 3, Eigen::Affine> Affine3s;
CeresPoseFilter(Eigen::Quaternion<Scalar> initial_orientation,
- Eigen::Quaternion<Scalar> imu_to_camera,
+ Eigen::Quaternion<Scalar> pivot_to_camera,
+ Eigen::Quaternion<Scalar> pivot_to_imu,
Eigen::Matrix<Scalar, 3, 1> gyro_bias,
Eigen::Matrix<Scalar, 6, 1> initial_state,
Eigen::Quaternion<Scalar> board_to_world,
- Eigen::Matrix<Scalar, 3, 1> imu_to_camera_translation,
+ Eigen::Matrix<Scalar, 3, 1> pivot_to_camera_translation,
+ Eigen::Matrix<Scalar, 3, 1> pivot_to_imu_translation,
Scalar gravity_scalar,
Eigen::Matrix<Scalar, 3, 1> accelerometer_bias)
: accel_(Eigen::Matrix<double, 3, 1>::Zero()),
@@ -64,8 +66,10 @@
orientation_(initial_orientation),
x_hat_(initial_state),
p_(Eigen::Matrix<Scalar, 6, 6>::Zero()),
- imu_to_camera_rotation_(imu_to_camera),
- imu_to_camera_translation_(imu_to_camera_translation),
+ pivot_to_camera_rotation_(pivot_to_camera),
+ pivot_to_camera_translation_(pivot_to_camera_translation),
+ pivot_to_imu_rotation_(pivot_to_imu),
+ pivot_to_imu_translation_(pivot_to_imu_translation),
board_to_world_(board_to_world),
gravity_scalar_(gravity_scalar),
accelerometer_bias_(accelerometer_bias) {}
@@ -78,12 +82,27 @@
Eigen::Quaternion<Scalar> /*imu_to_world_rotation*/,
Affine3s /*imu_to_world*/) {}
+ void UpdateTurret(distributed_clock::time_point t,
+ Eigen::Vector2d state) override {
+ state_ = state;
+ state_time_ = t;
+ }
+
+ Eigen::Vector2d state_ = Eigen::Vector2d::Zero();
+ distributed_clock::time_point state_time_ = distributed_clock::min_time;
+
// Observes a camera measurement by applying a kalman filter correction and
// accumulating up the error associated with the step.
void UpdateCamera(distributed_clock::time_point t,
std::pair<Eigen::Vector3d, Eigen::Vector3d> rt) override {
Integrate(t);
+ const double pivot_angle =
+ state_time_ == distributed_clock::min_time
+ ? 0.0
+ : state_(0) +
+ state_(1) * chrono::duration<double>(t - state_time_).count();
+
const Eigen::Quaternion<Scalar> board_to_camera_rotation(
frc971::controls::ToQuaternionFromRotationVector(rt.first)
.cast<Scalar>());
@@ -91,8 +110,10 @@
Eigen::Translation3d(rt.second).cast<Scalar>() *
board_to_camera_rotation;
- const Affine3s imu_to_camera =
- imu_to_camera_translation_ * imu_to_camera_rotation_;
+ const Affine3s pivot_to_camera =
+ pivot_to_camera_translation_ * pivot_to_camera_rotation_;
+ const Affine3s pivot_to_imu =
+ pivot_to_imu_translation_ * pivot_to_imu_rotation_;
// This converts us from (facing the board),
// x right, y up, z towards us -> x right, y away, z up.
@@ -102,10 +123,16 @@
// world <- board <- camera <- imu.
const Eigen::Quaternion<Scalar> imu_to_world_rotation =
board_to_world_ * board_to_camera_rotation.inverse() *
- imu_to_camera_rotation_;
+ pivot_to_camera_rotation_ *
+ Eigen::AngleAxis<Scalar>(static_cast<Scalar>(-pivot_angle),
+ Eigen::Vector3d::UnitZ().cast<Scalar>()) *
+ pivot_to_imu_rotation_.inverse();
const Affine3s imu_to_world =
- board_to_world_ * board_to_camera.inverse() * imu_to_camera;
+ board_to_world_ * board_to_camera.inverse() * pivot_to_camera *
+ Eigen::AngleAxis<Scalar>(static_cast<Scalar>(-pivot_angle),
+ Eigen::Vector3d::UnitZ().cast<Scalar>()) *
+ pivot_to_imu.inverse();
const Eigen::Matrix<Scalar, 3, 1> z =
imu_to_world * Eigen::Matrix<Scalar, 3, 1>::Zero();
@@ -261,8 +288,12 @@
Eigen::Matrix<Scalar, 6, 6> p_;
distributed_clock::time_point last_time_ = distributed_clock::min_time;
- Eigen::Quaternion<Scalar> imu_to_camera_rotation_;
- Eigen::Translation<Scalar, 3> imu_to_camera_translation_ =
+ Eigen::Quaternion<Scalar> pivot_to_camera_rotation_;
+ Eigen::Translation<Scalar, 3> pivot_to_camera_translation_ =
+ Eigen::Translation3d(0, 0, 0).cast<Scalar>();
+
+ Eigen::Quaternion<Scalar> pivot_to_imu_rotation_;
+ Eigen::Translation<Scalar, 3> pivot_to_imu_translation_ =
Eigen::Translation3d(0, 0, 0).cast<Scalar>();
Eigen::Quaternion<Scalar> board_to_world_;
@@ -286,22 +317,35 @@
std::vector<Eigen::Matrix<Scalar, 3, 1>> position_errors_;
};
+// Drives the Z coordinate of the quaternion to 0.
+struct PenalizeQuaternionZ {
+ template <typename S>
+ bool operator()(const S *const pivot_to_imu_ptr, S *residual) const {
+ Eigen::Quaternion<S> pivot_to_imu(pivot_to_imu_ptr[3], pivot_to_imu_ptr[0],
+ pivot_to_imu_ptr[1], pivot_to_imu_ptr[2]);
+ residual[0] = pivot_to_imu.z();
+ return true;
+ }
+};
+
// Subclass of the filter above which has plotting. This keeps debug code and
// actual code separate.
class PoseFilter : public CeresPoseFilter<double> {
public:
PoseFilter(Eigen::Quaternion<double> initial_orientation,
- Eigen::Quaternion<double> imu_to_camera,
+ Eigen::Quaternion<double> pivot_to_camera,
+ Eigen::Quaternion<double> pivot_to_imu,
Eigen::Matrix<double, 3, 1> gyro_bias,
Eigen::Matrix<double, 6, 1> initial_state,
Eigen::Quaternion<double> board_to_world,
- Eigen::Matrix<double, 3, 1> imu_to_camera_translation,
+ Eigen::Matrix<double, 3, 1> pivot_to_camera_translation,
+ Eigen::Matrix<double, 3, 1> pivot_to_imu_translation,
double gravity_scalar,
Eigen::Matrix<double, 3, 1> accelerometer_bias)
- : CeresPoseFilter<double>(initial_orientation, imu_to_camera, gyro_bias,
- initial_state, board_to_world,
- imu_to_camera_translation, gravity_scalar,
- accelerometer_bias) {}
+ : CeresPoseFilter<double>(
+ initial_orientation, pivot_to_camera, pivot_to_imu, gyro_bias,
+ initial_state, board_to_world, pivot_to_camera_translation,
+ pivot_to_imu_translation, gravity_scalar, accelerometer_bias) {}
void Plot() {
std::vector<double> rx;
@@ -496,30 +540,49 @@
const CalibrationData *data;
template <typename S>
- bool operator()(const S *const q1, const S *const q2, const S *const v,
- const S *const p, const S *const btw, const S *const itc,
+ bool operator()(const S *const initial_orientation_ptr,
+ const S *const pivot_to_camera_ptr,
+ const S *const pivot_to_imu_ptr, const S *const gyro_bias_ptr,
+ const S *const initial_state_ptr,
+ const S *const board_to_world_ptr,
+ const S *const pivot_to_camera_translation_ptr,
+ const S *const pivot_to_imu_translation_ptr,
const S *const gravity_scalar_ptr,
const S *const accelerometer_bias_ptr, S *residual) const {
- Eigen::Quaternion<S> initial_orientation(q1[3], q1[0], q1[1], q1[2]);
- Eigen::Quaternion<S> mounting_orientation(q2[3], q2[0], q2[1], q2[2]);
- Eigen::Quaternion<S> board_to_world(btw[3], btw[0], btw[1], btw[2]);
- Eigen::Matrix<S, 3, 1> gyro_bias(v[0], v[1], v[2]);
+ Eigen::Quaternion<S> initial_orientation(
+ initial_orientation_ptr[3], initial_orientation_ptr[0],
+ initial_orientation_ptr[1], initial_orientation_ptr[2]);
+ Eigen::Quaternion<S> pivot_to_camera(
+ pivot_to_camera_ptr[3], pivot_to_camera_ptr[0], pivot_to_camera_ptr[1],
+ pivot_to_camera_ptr[2]);
+ Eigen::Quaternion<S> pivot_to_imu(pivot_to_imu_ptr[3], pivot_to_imu_ptr[0],
+ pivot_to_imu_ptr[1], pivot_to_imu_ptr[2]);
+ Eigen::Quaternion<S> board_to_world(
+ board_to_world_ptr[3], board_to_world_ptr[0], board_to_world_ptr[1],
+ board_to_world_ptr[2]);
+ Eigen::Matrix<S, 3, 1> gyro_bias(gyro_bias_ptr[0], gyro_bias_ptr[1],
+ gyro_bias_ptr[2]);
Eigen::Matrix<S, 6, 1> initial_state;
- initial_state(0) = p[0];
- initial_state(1) = p[1];
- initial_state(2) = p[2];
- initial_state(3) = p[3];
- initial_state(4) = p[4];
- initial_state(5) = p[5];
- Eigen::Matrix<S, 3, 1> imu_to_camera_translation(itc[0], itc[1], itc[2]);
+ initial_state(0) = initial_state_ptr[0];
+ initial_state(1) = initial_state_ptr[1];
+ initial_state(2) = initial_state_ptr[2];
+ initial_state(3) = initial_state_ptr[3];
+ initial_state(4) = initial_state_ptr[4];
+ initial_state(5) = initial_state_ptr[5];
+ Eigen::Matrix<S, 3, 1> pivot_to_camera_translation(
+ pivot_to_camera_translation_ptr[0], pivot_to_camera_translation_ptr[1],
+ pivot_to_camera_translation_ptr[2]);
+ Eigen::Matrix<S, 3, 1> pivot_to_imu_translation(
+ pivot_to_imu_translation_ptr[0], pivot_to_imu_translation_ptr[1],
+ pivot_to_imu_translation_ptr[2]);
Eigen::Matrix<S, 3, 1> accelerometer_bias(accelerometer_bias_ptr[0],
accelerometer_bias_ptr[1],
accelerometer_bias_ptr[2]);
- CeresPoseFilter<S> filter(initial_orientation, mounting_orientation,
- gyro_bias, initial_state, board_to_world,
- imu_to_camera_translation, *gravity_scalar_ptr,
- accelerometer_bias);
+ CeresPoseFilter<S> filter(
+ initial_orientation, pivot_to_camera, pivot_to_imu, gyro_bias,
+ initial_state, board_to_world, pivot_to_camera_translation,
+ pivot_to_imu_translation, *gravity_scalar_ptr, accelerometer_bias);
data->ReviewData(&filter);
for (size_t i = 0; i < filter.num_errors(); ++i) {
@@ -547,25 +610,51 @@
// Set up the only cost function (also known as residual). This uses
// auto-differentiation to obtain the derivative (jacobian).
- ceres::CostFunction *cost_function =
- new ceres::AutoDiffCostFunction<CostFunctor, ceres::DYNAMIC, 4, 4, 3, 6,
- 4, 3, 1, 3>(
- new CostFunctor(&data), data.camera_samples_size() * 6);
- problem.AddResidualBlock(
- cost_function, new ceres::HuberLoss(1.0),
- calibration_parameters->initial_orientation.coeffs().data(),
- calibration_parameters->imu_to_camera.coeffs().data(),
- calibration_parameters->gyro_bias.data(),
- calibration_parameters->initial_state.data(),
- calibration_parameters->board_to_world.coeffs().data(),
- calibration_parameters->imu_to_camera_translation.data(),
- &calibration_parameters->gravity_scalar,
- calibration_parameters->accelerometer_bias.data());
+ {
+ ceres::CostFunction *cost_function =
+ new ceres::AutoDiffCostFunction<CostFunctor, ceres::DYNAMIC, 4, 4, 4, 3,
+ 6, 4, 3, 3, 1, 3>(
+ new CostFunctor(&data), data.camera_samples_size() * 6);
+ problem.AddResidualBlock(
+ cost_function, new ceres::HuberLoss(1.0),
+ calibration_parameters->initial_orientation.coeffs().data(),
+ calibration_parameters->pivot_to_camera.coeffs().data(),
+ calibration_parameters->pivot_to_imu.coeffs().data(),
+ calibration_parameters->gyro_bias.data(),
+ calibration_parameters->initial_state.data(),
+ calibration_parameters->board_to_world.coeffs().data(),
+ calibration_parameters->pivot_to_camera_translation.data(),
+ calibration_parameters->pivot_to_imu_translation.data(),
+ &calibration_parameters->gravity_scalar,
+ calibration_parameters->accelerometer_bias.data());
+ }
+
+ {
+ ceres::CostFunction *turret_z_cost_function =
+ new ceres::AutoDiffCostFunction<PenalizeQuaternionZ, 1, 4>(
+ new PenalizeQuaternionZ());
+ problem.AddResidualBlock(
+ turret_z_cost_function, nullptr,
+ calibration_parameters->pivot_to_imu.coeffs().data());
+ }
+
+ if (calibration_parameters->has_pivot) {
+ // Constrain Z.
+ problem.SetParameterization(
+ calibration_parameters->pivot_to_imu_translation.data(),
+ new ceres::SubsetParameterization(3, {2}));
+ } else {
+ problem.SetParameterBlockConstant(
+ calibration_parameters->pivot_to_imu.coeffs().data());
+ problem.SetParameterBlockConstant(
+ calibration_parameters->pivot_to_imu_translation.data());
+ }
+
problem.SetParameterization(
calibration_parameters->initial_orientation.coeffs().data(),
quaternion_local_parameterization);
problem.SetParameterization(
- calibration_parameters->imu_to_camera.coeffs().data(),
+ calibration_parameters->pivot_to_camera.coeffs().data(),
quaternion_local_parameterization);
problem.SetParameterization(
calibration_parameters->board_to_world.coeffs().data(),
@@ -597,11 +686,17 @@
LOG(INFO) << "initial_orientation "
<< calibration_parameters->initial_orientation.coeffs().transpose();
- LOG(INFO) << "imu_to_camera "
- << calibration_parameters->imu_to_camera.coeffs().transpose();
- LOG(INFO) << "imu_to_camera(rotation) "
+ LOG(INFO) << "pivot_to_imu "
+ << calibration_parameters->pivot_to_imu.coeffs().transpose();
+ LOG(INFO) << "pivot_to_imu(rotation) "
<< frc971::controls::ToRotationVectorFromQuaternion(
- calibration_parameters->imu_to_camera)
+ calibration_parameters->pivot_to_imu)
+ .transpose();
+ LOG(INFO) << "pivot_to_camera "
+ << calibration_parameters->pivot_to_camera.coeffs().transpose();
+ LOG(INFO) << "pivot_to_camera(rotation) "
+ << frc971::controls::ToRotationVectorFromQuaternion(
+ calibration_parameters->pivot_to_camera)
.transpose();
LOG(INFO) << "gyro_bias " << calibration_parameters->gyro_bias.transpose();
LOG(INFO) << "board_to_world "
@@ -610,8 +705,10 @@
<< frc971::controls::ToRotationVectorFromQuaternion(
calibration_parameters->board_to_world)
.transpose();
- LOG(INFO) << "imu_to_camera_translation "
- << calibration_parameters->imu_to_camera_translation.transpose();
+ LOG(INFO) << "pivot_to_imu_translation "
+ << calibration_parameters->pivot_to_imu_translation.transpose();
+ LOG(INFO) << "pivot_to_camera_translation "
+ << calibration_parameters->pivot_to_camera_translation.transpose();
LOG(INFO) << "gravity " << kGravity * calibration_parameters->gravity_scalar;
LOG(INFO) << "accelerometer bias "
<< calibration_parameters->accelerometer_bias.transpose();
@@ -620,11 +717,13 @@
void Plot(const CalibrationData &data,
const CalibrationParameters &calibration_parameters) {
PoseFilter filter(calibration_parameters.initial_orientation,
- calibration_parameters.imu_to_camera,
+ calibration_parameters.pivot_to_camera,
+ calibration_parameters.pivot_to_imu,
calibration_parameters.gyro_bias,
calibration_parameters.initial_state,
calibration_parameters.board_to_world,
- calibration_parameters.imu_to_camera_translation,
+ calibration_parameters.pivot_to_camera_translation,
+ calibration_parameters.pivot_to_imu_translation,
calibration_parameters.gravity_scalar,
calibration_parameters.accelerometer_bias);
data.ReviewData(&filter);
diff --git a/frc971/vision/extrinsics_calibration.h b/frc971/vision/extrinsics_calibration.h
index 9d6c704..b24f13f 100644
--- a/frc971/vision/extrinsics_calibration.h
+++ b/frc971/vision/extrinsics_calibration.h
@@ -11,7 +11,9 @@
struct CalibrationParameters {
Eigen::Quaternion<double> initial_orientation =
Eigen::Quaternion<double>::Identity();
- Eigen::Quaternion<double> imu_to_camera =
+ Eigen::Quaternion<double> pivot_to_camera =
+ Eigen::Quaternion<double>::Identity();
+ Eigen::Quaternion<double> pivot_to_imu =
Eigen::Quaternion<double>::Identity();
Eigen::Quaternion<double> board_to_world =
Eigen::Quaternion<double>::Identity();
@@ -19,17 +21,24 @@
Eigen::Vector3d gyro_bias = Eigen::Vector3d::Zero();
Eigen::Matrix<double, 6, 1> initial_state =
Eigen::Matrix<double, 6, 1>::Zero();
- Eigen::Matrix<double, 3, 1> imu_to_camera_translation =
+ Eigen::Matrix<double, 3, 1> pivot_to_camera_translation =
+ Eigen::Matrix<double, 3, 1>::Zero();
+ Eigen::Matrix<double, 3, 1> pivot_to_imu_translation =
Eigen::Matrix<double, 3, 1>::Zero();
double gravity_scalar = 1.0;
Eigen::Matrix<double, 3, 1> accelerometer_bias =
Eigen::Matrix<double, 3, 1>::Zero();
+
+ bool has_pivot = false;
};
+// Solves the mounting problem given the calibration data and parameters. The
+// parameters are used as the seed to the solver.
void Solve(const CalibrationData &data,
CalibrationParameters *calibration_parameters);
+// Plots the calibrated results to help visualize the fit.
void Plot(const CalibrationData &data,
const CalibrationParameters &calibration_parameters);
diff --git a/frc971/wpilib/ahal/DriverStation.cc b/frc971/wpilib/ahal/DriverStation.cc
index 2ed0a97..8b31af7 100644
--- a/frc971/wpilib/ahal/DriverStation.cc
+++ b/frc971/wpilib/ahal/DriverStation.cc
@@ -272,6 +272,54 @@
}
/**
+ * Returns the game specific message provided by the FMS.
+ *
+ * @return A string containing the game specific message.
+ */
+std::string_view DriverStation::GetGameSpecificMessage() const {
+ return std::string_view(
+ reinterpret_cast<const char *>(info_.gameSpecificMessage),
+ info_.gameSpecificMessageSize);
+}
+
+/**
+ * Returns the name of the competition event provided by the FMS.
+ *
+ * @return A string containing the event name
+ */
+std::string_view DriverStation::GetEventName() const {
+ return info_.eventName;
+}
+
+/**
+ * Returns the match number provided by the FMS.
+ *
+ * @return The number of the match
+ */
+DriverStation::MatchType DriverStation::GetMatchType() const {
+ return static_cast<DriverStation::MatchType>(info_.matchType);
+}
+
+/**
+ * Returns the match number provided by the FMS.
+ *
+ * @return The number of the match
+ */
+int DriverStation::GetMatchNumber() const {
+ return info_.matchNumber;
+}
+
+/**
+ * Returns the number of times the current match has been replayed from the
+ * FMS.
+ *
+ * @return The number of replays
+ */
+int DriverStation::GetReplayNumber() const {
+ return info_.replayNumber;
+}
+
+/**
* Return the alliance that the driver station says it is on.
*
* This could return kRed or kBlue.
@@ -374,10 +422,14 @@
HAL_ControlWord control_word;
HAL_GetControlWord(&control_word);
- is_enabled_ = control_word.enabled;
+ is_enabled_ = control_word.enabled && control_word.dsAttached;
is_autonomous_ = control_word.autonomous;
is_test_mode_ = control_word.test;
is_fms_attached_ = control_word.fmsAttached;
+ is_ds_attached_ = control_word.dsAttached;
+ is_teleop_ = !(control_word.autonomous || control_word.test);
+
+ HAL_GetMatchInfo(&info_);
}
/**
diff --git a/frc971/wpilib/ahal/DriverStation.h b/frc971/wpilib/ahal/DriverStation.h
index 5150360..8bcdcf1 100644
--- a/frc971/wpilib/ahal/DriverStation.h
+++ b/frc971/wpilib/ahal/DriverStation.h
@@ -27,6 +27,7 @@
class DriverStation {
public:
enum Alliance { kRed, kBlue, kInvalid };
+ enum MatchType { kNone, kPractice, kQualification, kElimination };
virtual ~DriverStation();
static DriverStation &GetInstance();
@@ -55,10 +56,18 @@
bool IsTestMode() const { return is_test_mode_; }
bool IsFmsAttached() const { return is_fms_attached_; }
bool IsAutonomous() const { return is_autonomous_; }
+ bool IsTeleop() const { return is_teleop_; }
+ bool IsDSAttached() const { return is_ds_attached_; }
bool IsSysActive() const;
bool IsBrownedOut() const;
+ std::string_view GetGameSpecificMessage() const;
+
+ std::string_view GetEventName() const;
+ MatchType GetMatchType() const;
+ int GetMatchNumber() const;
+ int GetReplayNumber() const;
Alliance GetAlliance() const;
int GetLocation() const;
double GetMatchTime() const;
@@ -88,6 +97,11 @@
bool is_test_mode_ = false;
bool is_autonomous_ = false;
bool is_fms_attached_ = false;
+ bool is_teleop_ = false;
+ bool is_ds_attached_ = false;
+
+ // statically allocated match info so we can return string_views into it.
+ HAL_MatchInfo info_;
};
} // namespace frc
diff --git a/frc971/wpilib/joystick_sender.cc b/frc971/wpilib/joystick_sender.cc
index fab3d05..9137a99 100644
--- a/frc971/wpilib/joystick_sender.cc
+++ b/frc971/wpilib/joystick_sender.cc
@@ -30,9 +30,6 @@
ds->RunIteration([&]() {
auto builder = joystick_state_sender_.MakeBuilder();
- HAL_MatchInfo match_info;
- auto status = HAL_GetMatchInfo(&match_info);
-
std::array<flatbuffers::Offset<Joystick>,
frc971::input::driver_station::JoystickFeature::kJoysticks>
joysticks;
@@ -67,32 +64,26 @@
joysticks_offset = builder.fbb()->CreateVector(joysticks.begin(),
joysticks.size());
- flatbuffers::Offset<flatbuffers::String> game_data_offset;
- if (status == 0) {
- static_assert(sizeof(match_info.gameSpecificMessage) == 64,
- "Check that the match info game specific message size "
- "hasn't changed and is still sane.");
- CHECK_LE(match_info.gameSpecificMessageSize,
- sizeof(match_info.gameSpecificMessage));
- game_data_offset = builder.fbb()->CreateString(
- reinterpret_cast<const char *>(match_info.gameSpecificMessage),
- match_info.gameSpecificMessageSize);
- }
+ flatbuffers::Offset<flatbuffers::String> game_data_offset =
+ builder.fbb()->CreateString(ds->GetGameSpecificMessage());
+
+ flatbuffers::Offset<flatbuffers::String> event_name_offset =
+ builder.fbb()->CreateString(ds->GetEventName());
aos::JoystickState::Builder joystick_state_builder =
builder.MakeBuilder<aos::JoystickState>();
joystick_state_builder.add_joysticks(joysticks_offset);
- if (status == 0) {
+ if (ds->GetGameSpecificMessage().size() >= 2u) {
joystick_state_builder.add_switch_left(
- match_info.gameSpecificMessage[0] == 'L' ||
- match_info.gameSpecificMessage[0] == 'l');
+ ds->GetGameSpecificMessage()[0] == 'L' ||
+ ds->GetGameSpecificMessage()[0] == 'l');
joystick_state_builder.add_scale_left(
- match_info.gameSpecificMessage[1] == 'L' ||
- match_info.gameSpecificMessage[1] == 'l');
- joystick_state_builder.add_game_data(game_data_offset);
+ ds->GetGameSpecificMessage()[1] == 'L' ||
+ ds->GetGameSpecificMessage()[1] == 'l');
}
+ joystick_state_builder.add_game_data(game_data_offset);
joystick_state_builder.add_test_mode(ds->IsTestMode());
joystick_state_builder.add_fms_attached(ds->IsFmsAttached());
@@ -109,7 +100,28 @@
joystick_state_builder.add_alliance(aos::Alliance::kInvalid);
break;
}
+ joystick_state_builder.add_location(ds->GetLocation());
+
joystick_state_builder.add_team_id(team_id_);
+ joystick_state_builder.add_match_number(ds->GetMatchNumber());
+ joystick_state_builder.add_replay_number(ds->GetReplayNumber());
+
+ switch (ds->GetMatchType()) {
+ case frc::DriverStation::kNone:
+ joystick_state_builder.add_match_type(aos::MatchType::kNone);
+ break;
+ case frc::DriverStation::kPractice:
+ joystick_state_builder.add_match_type(aos::MatchType::kPractice);
+ break;
+ case frc::DriverStation::kQualification:
+ joystick_state_builder.add_match_type(
+ aos::MatchType::kQualification);
+ break;
+ case frc::DriverStation::kElimination:
+ joystick_state_builder.add_match_type(aos::MatchType::kElimination);
+ break;
+ }
+ joystick_state_builder.add_event_name(event_name_offset);
if (builder.Send(joystick_state_builder.Finish()) !=
aos::RawSender::Error::kOk) {
diff --git a/package.json b/package.json
index 125a090..d16aed7 100644
--- a/package.json
+++ b/package.json
@@ -2,36 +2,37 @@
"name": "971-Robot-Code",
"license": "MIT",
"devDependencies": {
- "@types/jasmine": "latest",
- "@types/node": "latest",
- "jasmine": "latest",
- "karma-requirejs": "latest",
- "karma-sourcemap-loader": "latest",
- "karma-chrome-launcher": "latest",
- "karma-firefox-launcher": "latest",
- "karma": "latest",
- "karma-jasmine": "latest",
- "requirejs": "latest",
- "@bazel/concatjs": "latest",
- "@angular/animations": "latest",
- "@angular/core": "latest",
- "@angular/common": "latest",
- "@angular/platform-browser": "latest",
- "@angular/compiler": "latest",
- "@angular/compiler-cli": "latest",
- "@angular/cli": "latest",
- "@types/flatbuffers": "latest",
- "@bazel/protractor": "4.4.6",
- "@bazel/typescript": "4.4.6",
- "@bazel/rollup": "latest",
- "@bazel/terser": "latest",
- "@rollup/plugin-node-resolve": "latest",
- "protractor": "latest",
- "typescript": "latest",
- "rollup": "latest",
- "terser": "latest",
+ "@angular/animations": "13.2.0",
+ "@angular/common": "13.2.0",
+ "@angular/compiler": "13.2.0",
+ "@angular/compiler-cli": "13.2.0",
+ "@angular/core": "13.2.0",
+ "@angular/forms": "13.2.0",
+ "@angular/platform-browser": "13.2.0",
+ "@angular/cli": "13.2.0",
"@babel/cli": "^7.6.0",
"@babel/core": "^7.6.0",
+ "@bazel/concatjs": "4.4.6",
+ "@bazel/protractor": "4.4.6",
+ "@bazel/rollup": "4.4.6",
+ "@bazel/typescript": "4.4.6",
+ "@bazel/terser": "4.4.6",
+ "@types/jasmine": "3.10.3",
+ "jasmine": "3.10.0",
+ "karma": "6.3.12",
+ "karma-chrome-launcher": "3.1.0",
+ "karma-firefox-launcher": "2.1.2",
+ "karma-jasmine": "4.0.1",
+ "karma-requirejs": "1.1.0",
+ "karma-sourcemap-loader": "0.3.8",
+ "protractor": "7.0.0",
+ "requirejs": "2.3.6",
+ "rollup": "2.66.1",
+ "@rollup/plugin-node-resolve": "13.1.3",
+ "@types/flatbuffers": "1.10.0",
+ "@types/node": "17.0.21",
+ "typescript": "4.5.5",
+ "terser": "5.10.0",
"zone.js": "^0.11.4"
}
}
diff --git a/scouting/BUILD b/scouting/BUILD
index 0ed540b..0c2c641 100644
--- a/scouting/BUILD
+++ b/scouting/BUILD
@@ -33,6 +33,7 @@
"//scouting/www:index.html",
"//scouting/www:zonejs_copy",
],
+ visibility = ["//visibility:public"],
)
protractor_ts_test(
@@ -41,5 +42,5 @@
":scouting_test.ts",
],
on_prepare = ":scouting_test.protractor.on-prepare.js",
- server = ":scouting",
+ server = "//scouting/testing:scouting_test_servers",
)
diff --git a/scouting/db/db.go b/scouting/db/db.go
index 5d68e0f..94e9056 100644
--- a/scouting/db/db.go
+++ b/scouting/db/db.go
@@ -2,6 +2,7 @@
import (
"database/sql"
+ "errors"
"fmt"
_ "github.com/mattn/go-sqlite3"
@@ -26,101 +27,217 @@
Climbing int32
}
+type NotesData struct {
+ TeamNumber int32
+ Notes []string
+}
+
// Opens a database at the specified path. If the path refers to a non-existent
// file, the database will be created and initialized with empty tables.
func NewDatabase(path string) (*Database, error) {
+ var err error
database := new(Database)
- database.DB, _ = sql.Open("sqlite3", path)
- statement, error_ := database.Prepare("CREATE TABLE IF NOT EXISTS matches " +
- "(id INTEGER PRIMARY KEY, MatchNumber INTEGER, Round INTEGER, CompLevel INTEGER, R1 INTEGER, R2 INTEGER, R3 INTEGER, B1 INTEGER, B2 INTEGER, B3 INTEGER, r1ID INTEGER, r2ID INTEGER, r3ID INTEGER, b1ID INTEGER, b2ID INTEGER, b3ID INTEGER)")
- defer statement.Close()
- if error_ != nil {
- fmt.Println(error_)
- return nil, error_
+ database.DB, err = sql.Open("sqlite3", path)
+ if err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to create postgres db: ", err))
}
- _, error_ = statement.Exec()
- statement, error_ = database.Prepare("CREATE TABLE IF NOT EXISTS team_match_stats (id INTEGER PRIMARY KEY, TeamNumber INTEGER, MatchNumber DOUBLE, ShotsMissed INTEGER, UpperGoalShots INTEGER, LowerGoalShots INTEGER, ShotsMissedAuto INTEGER, UpperGoalAuto INTEGER, LowerGoalAuto INTEGER, PlayedDefense INTEGER, Climbing INTEGER)")
- defer statement.Close()
- if error_ != nil {
- fmt.Println(error_)
- return nil, error_
+
+ statement, err := database.Prepare("CREATE TABLE IF NOT EXISTS matches (" +
+ "id INTEGER PRIMARY KEY, " +
+ "MatchNumber INTEGER, " +
+ "Round INTEGER, " +
+ "CompLevel INTEGER, " +
+ "R1 INTEGER, " +
+ "R2 INTEGER, " +
+ "R3 INTEGER, " +
+ "B1 INTEGER, " +
+ "B2 INTEGER, " +
+ "B3 INTEGER, " +
+ "r1ID INTEGER, " +
+ "r2ID INTEGER, " +
+ "r3ID INTEGER, " +
+ "b1ID INTEGER, " +
+ "b2ID INTEGER, " +
+ "b3ID INTEGER)")
+ if err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to prepare matches table creation: ", err))
}
- _, error_ = statement.Exec()
+ defer statement.Close()
+
+ _, err = statement.Exec()
+ if err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to create matches table: ", err))
+ }
+
+ statement, err = database.Prepare("CREATE TABLE IF NOT EXISTS team_match_stats (" +
+ "id INTEGER PRIMARY KEY, " +
+ "TeamNumber INTEGER, " +
+ "MatchNumber INTEGER, " +
+ "ShotsMissed INTEGER, " +
+ "UpperGoalShots INTEGER, " +
+ "LowerGoalShots INTEGER, " +
+ "ShotsMissedAuto INTEGER, " +
+ "UpperGoalAuto INTEGER, " +
+ "LowerGoalAuto INTEGER, " +
+ "PlayedDefense INTEGER, " +
+ "Climbing INTEGER)")
+ if err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to prepare stats table creation: ", err))
+ }
+ defer statement.Close()
+
+ _, err = statement.Exec()
+ if err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to create team_match_stats table: ", err))
+ }
+
+ statement, err = database.Prepare("CREATE TABLE IF NOT EXISTS team_notes (" +
+ "id INTEGER PRIMARY KEY, " +
+ "TeamNumber INTEGER, " +
+ "Notes TEXT)")
+ if err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to prepare notes table creation: ", err))
+ }
+ defer statement.Close()
+
+ _, err = statement.Exec()
+ if err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to create notes table: ", err))
+ }
+
return database, nil
}
func (database *Database) Delete() error {
- statement, error_ := database.Prepare("DROP TABLE IF EXISTS matches")
- if error_ != nil {
- fmt.Println(error_)
- return (error_)
+ statement, err := database.Prepare("DROP TABLE IF EXISTS matches")
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to prepare dropping matches table: ", err))
}
- _, error_ = statement.Exec()
- statement, error_ = database.Prepare("DROP TABLE IF EXISTS team_match_stats")
- if error_ != nil {
- fmt.Println(error_)
- return (error_)
+ _, err = statement.Exec()
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to drop matches table: ", err))
}
- _, error_ = statement.Exec()
+
+ statement, err = database.Prepare("DROP TABLE IF EXISTS team_match_stats")
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to prepare dropping stats table: ", err))
+ }
+ _, err = statement.Exec()
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to drop stats table: ", err))
+ }
+
+ statement, err = database.Prepare("DROP TABLE IF EXISTS team_notes")
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to prepare dropping notes table: ", err))
+ }
+ _, err = statement.Exec()
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to drop notes table: ", err))
+ }
return nil
}
// This function will also populate the Stats table with six empty rows every time a match is added
func (database *Database) AddToMatch(m Match) error {
- statement, error_ := database.Prepare("INSERT INTO team_match_stats(TeamNumber, MatchNumber, ShotsMissed, UpperGoalShots, LowerGoalShots, ShotsMissedAuto, UpperGoalAuto, LowerGoalAuto, PlayedDefense, Climbing) VALUES (?, ?, ?, ?, ?, ?, ?, ?, ?, ?)")
- defer statement.Close()
- if error_ != nil {
- fmt.Println("failed to prepare stats database:", error_)
- return (error_)
+ statement, err := database.Prepare("INSERT INTO team_match_stats(" +
+ "TeamNumber, MatchNumber, " +
+ "ShotsMissed, UpperGoalShots, LowerGoalShots, " +
+ "ShotsMissedAuto, UpperGoalAuto, LowerGoalAuto, " +
+ "PlayedDefense, Climbing) " +
+ "VALUES (" +
+ "?, ?, " +
+ "?, ?, ?, " +
+ "?, ?, ?, " +
+ "?, ?)")
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to prepare insertion into stats database: ", err))
}
+ defer statement.Close()
+
var rowIds [6]int64
for i, TeamNumber := range []int32{m.R1, m.R2, m.R3, m.B1, m.B2, m.B3} {
- result, error_ := statement.Exec(TeamNumber, m.MatchNumber, 0, 0, 0, 0, 0, 0, 0, 0)
- if error_ != nil {
- fmt.Println("failed to execute statement 2:", error_)
- return (error_)
+ result, err := statement.Exec(TeamNumber, m.MatchNumber, 0, 0, 0, 0, 0, 0, 0, 0)
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to insert stats: ", err))
}
- rowIds[i], error_ = result.LastInsertId()
+ rowIds[i], err = result.LastInsertId()
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to get last insert ID: ", err))
+ }
}
- statement, error_ = database.Prepare("INSERT INTO matches(MatchNumber, Round, CompLevel, R1, R2, R3, B1, B2, B3, r1ID, r2ID, r3ID, b1ID, b2ID, b3ID) VALUES (?, ?, ?, ?, ?, ?, ?, ?, ?, ?, ?, ?, ?, ?, ?)")
+
+ statement, err = database.Prepare("INSERT INTO matches(" +
+ "MatchNumber, Round, CompLevel, " +
+ "R1, R2, R3, B1, B2, B3, " +
+ "r1ID, r2ID, r3ID, b1ID, b2ID, b3ID) " +
+ "VALUES (" +
+ "?, ?, ?, " +
+ "?, ?, ?, ?, ?, ?, " +
+ "?, ?, ?, ?, ?, ?)")
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to prepare insertion into match database: ", err))
+ }
defer statement.Close()
- if error_ != nil {
- fmt.Println("failed to prepare match database:", error_)
- return (error_)
- }
- _, error_ = statement.Exec(m.MatchNumber, m.Round, m.CompLevel, m.R1, m.R2, m.R3, m.B1, m.B2, m.B3, rowIds[0], rowIds[1], rowIds[2], rowIds[3], rowIds[4], rowIds[5])
- if error_ != nil {
- fmt.Println(error_)
- return (error_)
+
+ _, err = statement.Exec(m.MatchNumber, m.Round, m.CompLevel,
+ m.R1, m.R2, m.R3, m.B1, m.B2, m.B3,
+ rowIds[0], rowIds[1], rowIds[2], rowIds[3], rowIds[4], rowIds[5])
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to insert into match database: ", err))
}
return nil
}
func (database *Database) AddToStats(s Stats) error {
- statement, error_ := database.Prepare("UPDATE team_match_stats SET TeamNumber = ?, MatchNumber = ?, ShotsMissed = ?, UpperGoalShots = ?, LowerGoalShots = ?, ShotsMissedAuto = ?, UpperGoalAuto = ?, LowerGoalAuto = ?, PlayedDefense = ?, Climbing = ? WHERE MatchNumber = ? AND TeamNumber = ?")
- if error_ != nil {
- fmt.Println(error_)
- return (error_)
+ statement, err := database.Prepare("UPDATE team_match_stats SET " +
+ "TeamNumber = ?, MatchNumber = ?, " +
+ "ShotsMissed = ?, UpperGoalShots = ?, LowerGoalShots = ?, " +
+ "ShotsMissedAuto = ?, UpperGoalAuto = ?, LowerGoalAuto = ?, " +
+ "PlayedDefense = ?, Climbing = ? " +
+ "WHERE MatchNumber = ? AND TeamNumber = ?")
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to prepare stats update statement: ", err))
}
- _, error_ = statement.Exec(s.TeamNumber, s.MatchNumber, s.ShotsMissed, s.UpperGoalShots, s.LowerGoalShots, s.ShotsMissedAuto, s.UpperGoalAuto, s.LowerGoalAuto, s.PlayedDefense, s.Climbing, s.MatchNumber, s.TeamNumber)
- if error_ != nil {
- fmt.Println(error_)
- return (error_)
+ defer statement.Close()
+
+ result, err := statement.Exec(s.TeamNumber, s.MatchNumber,
+ s.ShotsMissed, s.UpperGoalShots, s.LowerGoalShots,
+ s.ShotsMissedAuto, s.UpperGoalAuto, s.LowerGoalAuto,
+ s.PlayedDefense, s.Climbing,
+ s.MatchNumber, s.TeamNumber)
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to update stats database: ", err))
+ }
+
+ numRowsAffected, err := result.RowsAffected()
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to query rows affected: ", err))
+ }
+ if numRowsAffected == 0 {
+ return errors.New(fmt.Sprint(
+ "Failed to find team ", s.TeamNumber,
+ " in match ", s.MatchNumber, " in the schedule."))
}
return nil
}
func (database *Database) ReturnMatches() ([]Match, error) {
- matches := make([]Match, 0)
- rows, _ := database.Query("SELECT * FROM matches")
+ rows, err := database.Query("SELECT * FROM matches")
+ if err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to select from matches: ", err))
+ }
defer rows.Close()
+
+ matches := make([]Match, 0)
for rows.Next() {
var match Match
var id int
- error_ := rows.Scan(&id, &match.MatchNumber, &match.Round, &match.CompLevel, &match.R1, &match.R2, &match.R3, &match.B1, &match.B2, &match.B3, &match.r1ID, &match.r2ID, &match.r3ID, &match.b1ID, &match.b2ID, &match.b3ID)
- if error_ != nil {
- fmt.Println(nil, error_)
- return nil, error_
+ err := rows.Scan(&id, &match.MatchNumber, &match.Round, &match.CompLevel,
+ &match.R1, &match.R2, &match.R3, &match.B1, &match.B2, &match.B3,
+ &match.r1ID, &match.r2ID, &match.r3ID, &match.b1ID, &match.b2ID, &match.b3ID)
+ if err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to scan from matches: ", err))
}
matches = append(matches, match)
}
@@ -128,16 +245,22 @@
}
func (database *Database) ReturnStats() ([]Stats, error) {
- rows, _ := database.Query("SELECT * FROM team_match_stats")
+ rows, err := database.Query("SELECT * FROM team_match_stats")
+ if err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to SELECT * FROM team_match_stats: ", err))
+ }
defer rows.Close()
+
teams := make([]Stats, 0)
- var id int
for rows.Next() {
var team Stats
- error_ := rows.Scan(&id, &team.TeamNumber, &team.MatchNumber, &team.ShotsMissed, &team.UpperGoalShots, &team.LowerGoalShots, &team.ShotsMissedAuto, &team.UpperGoalAuto, &team.LowerGoalAuto, &team.PlayedDefense, &team.Climbing)
- if error_ != nil {
- fmt.Println(error_)
- return nil, error_
+ var id int
+ err = rows.Scan(&id, &team.TeamNumber, &team.MatchNumber,
+ &team.ShotsMissed, &team.UpperGoalShots, &team.LowerGoalShots,
+ &team.ShotsMissedAuto, &team.UpperGoalAuto, &team.LowerGoalAuto,
+ &team.PlayedDefense, &team.Climbing)
+ if err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to scan from stats: ", err))
}
teams = append(teams, team)
}
@@ -145,41 +268,87 @@
}
func (database *Database) QueryMatches(teamNumber_ int32) ([]Match, error) {
- rows, error_ := database.Query("SELECT * FROM matches WHERE R1 = ? OR R2 = ? OR R3 = ? OR B1 = ? OR B2 = ? OR B3 = ?", teamNumber_, teamNumber_, teamNumber_, teamNumber_, teamNumber_, teamNumber_)
- if error_ != nil {
- fmt.Println("failed to execute statement 1:", error_)
- return nil, error_
+ rows, err := database.Query("SELECT * FROM matches WHERE "+
+ "R1 = ? OR R2 = ? OR R3 = ? OR B1 = ? OR B2 = ? OR B3 = ?",
+ teamNumber_, teamNumber_, teamNumber_, teamNumber_, teamNumber_, teamNumber_)
+ if err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to select from matches for team: ", err))
}
defer rows.Close()
+
var matches []Match
- var id int
for rows.Next() {
var match Match
- rows.Scan(&id, &match.MatchNumber, &match.Round, &match.CompLevel, &match.R1, &match.R2, &match.R3, &match.B1, &match.B2, &match.B3, &match.r1ID, &match.r2ID, &match.r3ID, &match.b1ID, &match.b2ID, &match.b3ID)
+ var id int
+ err = rows.Scan(&id, &match.MatchNumber, &match.Round, &match.CompLevel,
+ &match.R1, &match.R2, &match.R3, &match.B1, &match.B2, &match.B3,
+ &match.r1ID, &match.r2ID, &match.r3ID, &match.b1ID, &match.b2ID, &match.b3ID)
+ if err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to scan from matches: ", err))
+ }
matches = append(matches, match)
}
return matches, nil
}
func (database *Database) QueryStats(teamNumber_ int) ([]Stats, error) {
- rows, error_ := database.Query("SELECT * FROM team_match_stats WHERE TeamNumber = ?", teamNumber_)
- if error_ != nil {
- fmt.Println("failed to execute statement 3:", error_)
- return nil, error_
+ rows, err := database.Query("SELECT * FROM team_match_stats WHERE TeamNumber = ?", teamNumber_)
+ if err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to select from stats: ", err))
}
defer rows.Close()
+
var teams []Stats
for rows.Next() {
var team Stats
var id int
- error_ = rows.Scan(&id, &team.TeamNumber, &team.MatchNumber, &team.ShotsMissed,
- &team.UpperGoalShots, &team.LowerGoalShots, &team.ShotsMissedAuto, &team.UpperGoalAuto,
- &team.LowerGoalAuto, &team.PlayedDefense, &team.Climbing)
+ err = rows.Scan(&id, &team.TeamNumber, &team.MatchNumber,
+ &team.ShotsMissed, &team.UpperGoalShots, &team.LowerGoalShots,
+ &team.ShotsMissedAuto, &team.UpperGoalAuto, &team.LowerGoalAuto,
+ &team.PlayedDefense, &team.Climbing)
+ if err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to scan from stats: ", err))
+ }
teams = append(teams, team)
}
- if error_ != nil {
- fmt.Println("failed to execute statement 3:", error_)
- return nil, error_
- }
return teams, nil
}
+
+func (database *Database) QueryNotes(TeamNumber int32) (NotesData, error) {
+ rows, err := database.Query("SELECT * FROM team_notes WHERE TeamNumber = ?", TeamNumber)
+ if err != nil {
+ return NotesData{}, errors.New(fmt.Sprint("Failed to select from notes: ", err))
+ }
+ defer rows.Close()
+
+ var notes []string
+ for rows.Next() {
+ var id int32
+ var data string
+ err = rows.Scan(&id, &TeamNumber, &data)
+ if err != nil {
+ return NotesData{}, errors.New(fmt.Sprint("Failed to scan from notes: ", err))
+ }
+ notes = append(notes, data)
+ }
+ return NotesData{TeamNumber, notes}, nil
+}
+
+func (database *Database) AddNotes(data NotesData) error {
+ if len(data.Notes) > 1 {
+ return errors.New("Can only insert one row of notes at a time")
+ }
+ statement, err := database.Prepare("INSERT INTO " +
+ "team_notes(TeamNumber, Notes)" +
+ "VALUES (?, ?)")
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to prepare insertion into notes table: ", err))
+ }
+ defer statement.Close()
+
+ _, err = statement.Exec(data.TeamNumber, data.Notes[0])
+ if err != nil {
+ return errors.New(fmt.Sprint("Failed to insert into Notes database: ", err))
+ }
+ return nil
+}
diff --git a/scouting/db/db_test.go b/scouting/db/db_test.go
index 85ad339..13a43f8 100644
--- a/scouting/db/db_test.go
+++ b/scouting/db/db_test.go
@@ -1,21 +1,28 @@
package db
import (
+ "fmt"
"os"
"path/filepath"
"reflect"
"testing"
)
+// Shortcut for error checking. If the specified error is non-nil, print the
+// error message and exit the test.
+func check(t *testing.T, err error, message string) {
+ if err != nil {
+ t.Fatal(message, ":", err)
+ }
+}
+
// Creates a database in TEST_TMPDIR so that we don't accidentally write it
// into the runfiles directory.
func createDatabase(t *testing.T) *Database {
// Get the path to our temporary writable directory.
testTmpdir := os.Getenv("TEST_TMPDIR")
db, err := NewDatabase(filepath.Join(testTmpdir, "scouting.db"))
- if err != nil {
- t.Fatal("Failed to create a new database: ", err)
- }
+ check(t, err, "Failed to create new database")
return db
}
@@ -23,12 +30,22 @@
db := createDatabase(t)
defer db.Delete()
- correct := []Match{Match{MatchNumber: 7, Round: 1, CompLevel: "quals", R1: 9999, R2: 1000, R3: 777, B1: 0000, B2: 4321, B3: 1234, r1ID: 1, r2ID: 2, r3ID: 3, b1ID: 4, b2ID: 5, b3ID: 6}}
- db.AddToMatch(correct[0])
- got, error_ := db.ReturnMatches()
- if error_ != nil {
- t.Fatalf(error_.Error())
+ correct := []Match{
+ Match{
+ MatchNumber: 7,
+ Round: 1,
+ CompLevel: "quals",
+ R1: 9999, R2: 1000, R3: 777, B1: 0000, B2: 4321, B3: 1234,
+ r1ID: 1, r2ID: 2, r3ID: 3, b1ID: 4, b2ID: 5, b3ID: 6,
+ },
}
+
+ err := db.AddToMatch(correct[0])
+ check(t, err, "Failed to add match data")
+
+ got, err := db.ReturnMatches()
+ check(t, err, "Failed ReturnMatches()")
+
if !reflect.DeepEqual(correct, got) {
t.Fatalf("Got %#v,\nbut expected %#v.", got, correct)
}
@@ -39,21 +56,58 @@
defer db.Delete()
correct := []Stats{
- Stats{TeamNumber: 1236, MatchNumber: 7, ShotsMissed: 9, UpperGoalShots: 5, LowerGoalShots: 4, ShotsMissedAuto: 3, UpperGoalAuto: 2, LowerGoalAuto: 1, PlayedDefense: 2, Climbing: 3},
- Stats{TeamNumber: 1001, MatchNumber: 7, ShotsMissed: 6, UpperGoalShots: 9, LowerGoalShots: 9, ShotsMissedAuto: 0, UpperGoalAuto: 0, LowerGoalAuto: 0, PlayedDefense: 0, Climbing: 0},
- Stats{TeamNumber: 777, MatchNumber: 7, ShotsMissed: 5, UpperGoalShots: 7, LowerGoalShots: 12, ShotsMissedAuto: 0, UpperGoalAuto: 4, LowerGoalAuto: 0, PlayedDefense: 0, Climbing: 0},
- Stats{TeamNumber: 1000, MatchNumber: 7, ShotsMissed: 12, UpperGoalShots: 6, LowerGoalShots: 10, ShotsMissedAuto: 0, UpperGoalAuto: 7, LowerGoalAuto: 0, PlayedDefense: 0, Climbing: 0},
- Stats{TeamNumber: 4321, MatchNumber: 7, ShotsMissed: 14, UpperGoalShots: 12, LowerGoalShots: 3, ShotsMissedAuto: 0, UpperGoalAuto: 7, LowerGoalAuto: 0, PlayedDefense: 0, Climbing: 0},
- Stats{TeamNumber: 1234, MatchNumber: 7, ShotsMissed: 3, UpperGoalShots: 4, LowerGoalShots: 0, ShotsMissedAuto: 0, UpperGoalAuto: 9, LowerGoalAuto: 0, PlayedDefense: 0, Climbing: 0},
+ Stats{
+ TeamNumber: 1236, MatchNumber: 7,
+ ShotsMissed: 9, UpperGoalShots: 5, LowerGoalShots: 4,
+ ShotsMissedAuto: 3, UpperGoalAuto: 2, LowerGoalAuto: 1,
+ PlayedDefense: 2, Climbing: 3,
+ },
+ Stats{
+ TeamNumber: 1001, MatchNumber: 7,
+ ShotsMissed: 6, UpperGoalShots: 9, LowerGoalShots: 9,
+ ShotsMissedAuto: 0, UpperGoalAuto: 0, LowerGoalAuto: 0,
+ PlayedDefense: 0, Climbing: 0,
+ },
+ Stats{
+ TeamNumber: 777, MatchNumber: 7,
+ ShotsMissed: 5, UpperGoalShots: 7, LowerGoalShots: 12,
+ ShotsMissedAuto: 0, UpperGoalAuto: 4, LowerGoalAuto: 0,
+ PlayedDefense: 0, Climbing: 0,
+ },
+ Stats{
+ TeamNumber: 1000, MatchNumber: 7,
+ ShotsMissed: 12, UpperGoalShots: 6, LowerGoalShots: 10,
+ ShotsMissedAuto: 0, UpperGoalAuto: 7, LowerGoalAuto: 0,
+ PlayedDefense: 0, Climbing: 0,
+ },
+ Stats{
+ TeamNumber: 4321, MatchNumber: 7,
+ ShotsMissed: 14, UpperGoalShots: 12, LowerGoalShots: 3,
+ ShotsMissedAuto: 0, UpperGoalAuto: 7, LowerGoalAuto: 0,
+ PlayedDefense: 0, Climbing: 0,
+ },
+ Stats{
+ TeamNumber: 1234, MatchNumber: 7,
+ ShotsMissed: 3, UpperGoalShots: 4, LowerGoalShots: 0,
+ ShotsMissedAuto: 0, UpperGoalAuto: 9, LowerGoalAuto: 0,
+ PlayedDefense: 0, Climbing: 0,
+ },
}
- db.AddToMatch(Match{MatchNumber: 7, Round: 1, CompLevel: "quals", R1: 1236, R2: 1001, R3: 777, B1: 1000, B2: 4321, B3: 1234, r1ID: 1, r2ID: 2, r3ID: 3, b1ID: 4, b2ID: 5, b3ID: 6})
+
+ err := db.AddToMatch(Match{
+ MatchNumber: 7, Round: 1, CompLevel: "quals",
+ R1: 1236, R2: 1001, R3: 777, B1: 1000, B2: 4321, B3: 1234,
+ r1ID: 1, r2ID: 2, r3ID: 3, b1ID: 4, b2ID: 5, b3ID: 6})
+ check(t, err, "Failed to add match")
+
for i := 0; i < len(correct); i++ {
- db.AddToStats(correct[i])
+ err = db.AddToStats(correct[i])
+ check(t, err, "Failed to add stats to DB")
}
- got, error_ := db.ReturnStats()
- if error_ != nil {
- t.Fatalf(error_.Error())
- }
+
+ got, err := db.ReturnStats()
+ check(t, err, "Failed ReturnStats()")
+
if !reflect.DeepEqual(correct, got) {
t.Errorf("Got %#v,\nbut expected %#v.", got, correct)
}
@@ -71,18 +125,26 @@
}
for i := 0; i < len(testDatabase); i++ {
- db.AddToMatch(testDatabase[i])
+ err := db.AddToMatch(testDatabase[i])
+ check(t, err, fmt.Sprint("Failed to add match", i))
}
correct := []Match{
- Match{MatchNumber: 2, Round: 1, CompLevel: "quals", R1: 251, R2: 169, R3: 286, B1: 253, B2: 538, B3: 149, r1ID: 1, r2ID: 2, r3ID: 3, b1ID: 4, b2ID: 5, b3ID: 6},
- Match{MatchNumber: 3, Round: 1, CompLevel: "quals", R1: 147, R2: 421, R3: 538, B1: 126, B2: 448, B3: 262, r1ID: 13, r2ID: 14, r3ID: 15, b1ID: 16, b2ID: 17, b3ID: 18},
+ Match{
+ MatchNumber: 2, Round: 1, CompLevel: "quals",
+ R1: 251, R2: 169, R3: 286, B1: 253, B2: 538, B3: 149,
+ r1ID: 1, r2ID: 2, r3ID: 3, b1ID: 4, b2ID: 5, b3ID: 6,
+ },
+ Match{
+ MatchNumber: 3, Round: 1, CompLevel: "quals",
+ R1: 147, R2: 421, R3: 538, B1: 126, B2: 448, B3: 262,
+ r1ID: 13, r2ID: 14, r3ID: 15, b1ID: 16, b2ID: 17, b3ID: 18,
+ },
}
- got, error_ := db.QueryMatches(538)
- if error_ != nil {
- t.Fatal("Failed to query matches for 538: ", error_)
- }
+ got, err := db.QueryMatches(538)
+ check(t, err, "Failed to query matches for 538")
+
if !reflect.DeepEqual(correct, got) {
t.Fatalf("Got %#v,\nbut expected %#v.", got, correct)
}
@@ -93,24 +155,65 @@
defer db.Delete()
testDatabase := []Stats{
- Stats{TeamNumber: 1235, MatchNumber: 94, ShotsMissed: 2, UpperGoalShots: 2, LowerGoalShots: 2, ShotsMissedAuto: 2, UpperGoalAuto: 2, LowerGoalAuto: 2, PlayedDefense: 2, Climbing: 2},
- Stats{TeamNumber: 1234, MatchNumber: 94, ShotsMissed: 4, UpperGoalShots: 4, LowerGoalShots: 4, ShotsMissedAuto: 4, UpperGoalAuto: 4, LowerGoalAuto: 4, PlayedDefense: 7, Climbing: 2},
- Stats{TeamNumber: 1233, MatchNumber: 94, ShotsMissed: 3, UpperGoalShots: 3, LowerGoalShots: 3, ShotsMissedAuto: 3, UpperGoalAuto: 3, LowerGoalAuto: 3, PlayedDefense: 3, Climbing: 3},
- Stats{TeamNumber: 1232, MatchNumber: 94, ShotsMissed: 5, UpperGoalShots: 5, LowerGoalShots: 5, ShotsMissedAuto: 5, UpperGoalAuto: 5, LowerGoalAuto: 5, PlayedDefense: 7, Climbing: 1},
- Stats{TeamNumber: 1231, MatchNumber: 94, ShotsMissed: 6, UpperGoalShots: 6, LowerGoalShots: 6, ShotsMissedAuto: 6, UpperGoalAuto: 6, LowerGoalAuto: 6, PlayedDefense: 7, Climbing: 1},
- Stats{TeamNumber: 1239, MatchNumber: 94, ShotsMissed: 7, UpperGoalShots: 7, LowerGoalShots: 7, ShotsMissedAuto: 7, UpperGoalAuto: 7, LowerGoalAuto: 3, PlayedDefense: 7, Climbing: 1},
+ Stats{
+ TeamNumber: 1235, MatchNumber: 94,
+ ShotsMissed: 2, UpperGoalShots: 2, LowerGoalShots: 2,
+ ShotsMissedAuto: 2, UpperGoalAuto: 2, LowerGoalAuto: 2,
+ PlayedDefense: 2, Climbing: 2},
+ Stats{
+ TeamNumber: 1234, MatchNumber: 94,
+ ShotsMissed: 4, UpperGoalShots: 4, LowerGoalShots: 4,
+ ShotsMissedAuto: 4, UpperGoalAuto: 4, LowerGoalAuto: 4,
+ PlayedDefense: 7, Climbing: 2,
+ },
+ Stats{
+ TeamNumber: 1233, MatchNumber: 94,
+ ShotsMissed: 3, UpperGoalShots: 3, LowerGoalShots: 3,
+ ShotsMissedAuto: 3, UpperGoalAuto: 3, LowerGoalAuto: 3,
+ PlayedDefense: 3, Climbing: 3,
+ },
+ Stats{
+ TeamNumber: 1232, MatchNumber: 94,
+ ShotsMissed: 5, UpperGoalShots: 5, LowerGoalShots: 5,
+ ShotsMissedAuto: 5, UpperGoalAuto: 5, LowerGoalAuto: 5,
+ PlayedDefense: 7, Climbing: 1,
+ },
+ Stats{
+ TeamNumber: 1231, MatchNumber: 94,
+ ShotsMissed: 6, UpperGoalShots: 6, LowerGoalShots: 6,
+ ShotsMissedAuto: 6, UpperGoalAuto: 6, LowerGoalAuto: 6,
+ PlayedDefense: 7, Climbing: 1,
+ },
+ Stats{
+ TeamNumber: 1239, MatchNumber: 94,
+ ShotsMissed: 7, UpperGoalShots: 7, LowerGoalShots: 7,
+ ShotsMissedAuto: 7, UpperGoalAuto: 7, LowerGoalAuto: 3,
+ PlayedDefense: 7, Climbing: 1,
+ },
}
- db.AddToMatch(Match{MatchNumber: 94, Round: 1, CompLevel: "quals", R1: 1235, R2: 1234, R3: 1233, B1: 1232, B2: 1231, B3: 1239})
+
+ err := db.AddToMatch(Match{
+ MatchNumber: 94, Round: 1, CompLevel: "quals",
+ R1: 1235, R2: 1234, R3: 1233, B1: 1232, B2: 1231, B3: 1239})
+ check(t, err, "Failed to add match")
+
for i := 0; i < len(testDatabase); i++ {
- db.AddToStats(testDatabase[i])
+ err = db.AddToStats(testDatabase[i])
+ check(t, err, fmt.Sprint("Failed to add stats", i))
}
+
correct := []Stats{
- Stats{TeamNumber: 1235, MatchNumber: 94, ShotsMissed: 2, UpperGoalShots: 2, LowerGoalShots: 2, ShotsMissedAuto: 2, UpperGoalAuto: 2, LowerGoalAuto: 2, PlayedDefense: 2, Climbing: 2},
+ Stats{
+ TeamNumber: 1235, MatchNumber: 94,
+ ShotsMissed: 2, UpperGoalShots: 2, LowerGoalShots: 2,
+ ShotsMissedAuto: 2, UpperGoalAuto: 2, LowerGoalAuto: 2,
+ PlayedDefense: 2, Climbing: 2,
+ },
}
- got, error_ := db.QueryStats(1235)
- if error_ != nil {
- t.Fatalf(error_.Error())
- }
+
+ got, err := db.QueryStats(1235)
+ check(t, err, "Failed QueryStats()")
+
if !reflect.DeepEqual(correct, got) {
t.Errorf("Got %#v,\nbut expected %#v.", got, correct)
}
@@ -121,19 +224,41 @@
defer db.Delete()
correct := []Match{
- Match{MatchNumber: 2, Round: 1, CompLevel: "quals", R1: 251, R2: 169, R3: 286, B1: 253, B2: 538, B3: 149, r1ID: 1, r2ID: 2, r3ID: 3, b1ID: 4, b2ID: 5, b3ID: 6},
- Match{MatchNumber: 3, Round: 1, CompLevel: "quals", R1: 147, R2: 421, R3: 538, B1: 126, B2: 448, B3: 262, r1ID: 7, r2ID: 8, r3ID: 9, b1ID: 10, b2ID: 11, b3ID: 12},
- Match{MatchNumber: 4, Round: 1, CompLevel: "quals", R1: 251, R2: 169, R3: 286, B1: 653, B2: 538, B3: 149, r1ID: 13, r2ID: 14, r3ID: 15, b1ID: 16, b2ID: 17, b3ID: 18},
- Match{MatchNumber: 5, Round: 1, CompLevel: "quals", R1: 198, R2: 1421, R3: 538, B1: 26, B2: 448, B3: 262, r1ID: 19, r2ID: 20, r3ID: 21, b1ID: 22, b2ID: 23, b3ID: 24},
- Match{MatchNumber: 6, Round: 1, CompLevel: "quals", R1: 251, R2: 188, R3: 286, B1: 555, B2: 538, B3: 149, r1ID: 25, r2ID: 26, r3ID: 27, b1ID: 28, b2ID: 29, b3ID: 30},
+ Match{
+ MatchNumber: 2, Round: 1, CompLevel: "quals",
+ R1: 251, R2: 169, R3: 286, B1: 253, B2: 538, B3: 149,
+ r1ID: 1, r2ID: 2, r3ID: 3, b1ID: 4, b2ID: 5, b3ID: 6,
+ },
+ Match{
+ MatchNumber: 3, Round: 1, CompLevel: "quals",
+ R1: 147, R2: 421, R3: 538, B1: 126, B2: 448, B3: 262,
+ r1ID: 7, r2ID: 8, r3ID: 9, b1ID: 10, b2ID: 11, b3ID: 12,
+ },
+ Match{
+ MatchNumber: 4, Round: 1, CompLevel: "quals",
+ R1: 251, R2: 169, R3: 286, B1: 653, B2: 538, B3: 149,
+ r1ID: 13, r2ID: 14, r3ID: 15, b1ID: 16, b2ID: 17, b3ID: 18,
+ },
+ Match{
+ MatchNumber: 5, Round: 1, CompLevel: "quals",
+ R1: 198, R2: 1421, R3: 538, B1: 26, B2: 448, B3: 262,
+ r1ID: 19, r2ID: 20, r3ID: 21, b1ID: 22, b2ID: 23, b3ID: 24,
+ },
+ Match{
+ MatchNumber: 6, Round: 1, CompLevel: "quals",
+ R1: 251, R2: 188, R3: 286, B1: 555, B2: 538, B3: 149,
+ r1ID: 25, r2ID: 26, r3ID: 27, b1ID: 28, b2ID: 29, b3ID: 30,
+ },
}
+
for i := 0; i < len(correct); i++ {
- db.AddToMatch(correct[i])
+ err := db.AddToMatch(correct[i])
+ check(t, err, fmt.Sprint("Failed to add match", i))
}
- got, error_ := db.ReturnMatches()
- if error_ != nil {
- t.Fatalf(error_.Error())
- }
+
+ got, err := db.ReturnMatches()
+ check(t, err, "Failed ReturnMatches()")
+
if !reflect.DeepEqual(correct, got) {
t.Errorf("Got %#v,\nbut expected %#v.", got, correct)
}
@@ -144,22 +269,82 @@
defer db.Delete()
correct := []Stats{
- Stats{TeamNumber: 1235, MatchNumber: 94, ShotsMissed: 2, UpperGoalShots: 2, LowerGoalShots: 2, ShotsMissedAuto: 2, UpperGoalAuto: 2, LowerGoalAuto: 2, PlayedDefense: 2, Climbing: 2},
- Stats{TeamNumber: 1236, MatchNumber: 94, ShotsMissed: 4, UpperGoalShots: 4, LowerGoalShots: 4, ShotsMissedAuto: 4, UpperGoalAuto: 4, LowerGoalAuto: 4, PlayedDefense: 7, Climbing: 2},
- Stats{TeamNumber: 1237, MatchNumber: 94, ShotsMissed: 3, UpperGoalShots: 3, LowerGoalShots: 3, ShotsMissedAuto: 3, UpperGoalAuto: 3, LowerGoalAuto: 3, PlayedDefense: 3, Climbing: 3},
- Stats{TeamNumber: 1238, MatchNumber: 94, ShotsMissed: 5, UpperGoalShots: 5, LowerGoalShots: 5, ShotsMissedAuto: 5, UpperGoalAuto: 5, LowerGoalAuto: 5, PlayedDefense: 7, Climbing: 1},
- Stats{TeamNumber: 1239, MatchNumber: 94, ShotsMissed: 6, UpperGoalShots: 6, LowerGoalShots: 6, ShotsMissedAuto: 6, UpperGoalAuto: 6, LowerGoalAuto: 6, PlayedDefense: 7, Climbing: 1},
- Stats{TeamNumber: 1233, MatchNumber: 94, ShotsMissed: 7, UpperGoalShots: 7, LowerGoalShots: 7, ShotsMissedAuto: 7, UpperGoalAuto: 7, LowerGoalAuto: 3, PlayedDefense: 7, Climbing: 1},
+ Stats{
+ TeamNumber: 1235, MatchNumber: 94,
+ ShotsMissed: 2, UpperGoalShots: 2, LowerGoalShots: 2,
+ ShotsMissedAuto: 2, UpperGoalAuto: 2, LowerGoalAuto: 2,
+ PlayedDefense: 2, Climbing: 2,
+ },
+ Stats{
+ TeamNumber: 1236, MatchNumber: 94,
+ ShotsMissed: 4, UpperGoalShots: 4, LowerGoalShots: 4,
+ ShotsMissedAuto: 4, UpperGoalAuto: 4, LowerGoalAuto: 4,
+ PlayedDefense: 7, Climbing: 2,
+ },
+ Stats{
+ TeamNumber: 1237, MatchNumber: 94,
+ ShotsMissed: 3, UpperGoalShots: 3, LowerGoalShots: 3,
+ ShotsMissedAuto: 3, UpperGoalAuto: 3, LowerGoalAuto: 3,
+ PlayedDefense: 3, Climbing: 3,
+ },
+ Stats{
+ TeamNumber: 1238, MatchNumber: 94,
+ ShotsMissed: 5, UpperGoalShots: 5, LowerGoalShots: 5,
+ ShotsMissedAuto: 5, UpperGoalAuto: 5, LowerGoalAuto: 5,
+ PlayedDefense: 7, Climbing: 1,
+ },
+ Stats{
+ TeamNumber: 1239, MatchNumber: 94,
+ ShotsMissed: 6, UpperGoalShots: 6, LowerGoalShots: 6,
+ ShotsMissedAuto: 6, UpperGoalAuto: 6, LowerGoalAuto: 6,
+ PlayedDefense: 7, Climbing: 1,
+ },
+ Stats{
+ TeamNumber: 1233, MatchNumber: 94,
+ ShotsMissed: 7, UpperGoalShots: 7, LowerGoalShots: 7,
+ ShotsMissedAuto: 7, UpperGoalAuto: 7, LowerGoalAuto: 3,
+ PlayedDefense: 7, Climbing: 1,
+ },
}
- db.AddToMatch(Match{MatchNumber: 94, Round: 1, CompLevel: "quals", R1: 1235, R2: 1236, R3: 1237, B1: 1238, B2: 1239, B3: 1233})
+
+ err := db.AddToMatch(Match{
+ MatchNumber: 94, Round: 1, CompLevel: "quals",
+ R1: 1235, R2: 1236, R3: 1237, B1: 1238, B2: 1239, B3: 1233})
+ check(t, err, "Failed to add match")
+
for i := 0; i < len(correct); i++ {
- db.AddToStats(correct[i])
+ err = db.AddToStats(correct[i])
+ check(t, err, fmt.Sprint("Failed to add stats", i))
}
- got, error_ := db.ReturnStats()
- if error_ != nil {
- t.Fatalf(error_.Error())
- }
+
+ got, err := db.ReturnStats()
+ check(t, err, "Failed ReturnStats()")
+
if !reflect.DeepEqual(correct, got) {
t.Errorf("Got %#v,\nbut expected %#v.", got, correct)
}
}
+
+func TestNotes(t *testing.T) {
+ db := createDatabase(t)
+ defer db.Delete()
+
+ expected := NotesData{
+ TeamNumber: 1234,
+ Notes: []string{"Note 1", "Note 3"},
+ }
+
+ err := db.AddNotes(NotesData{1234, []string{"Note 1"}})
+ check(t, err, "Failed to add Note")
+ err = db.AddNotes(NotesData{1235, []string{"Note 2"}})
+ check(t, err, "Failed to add Note")
+ err = db.AddNotes(NotesData{1234, []string{"Note 3"}})
+ check(t, err, "Failed to add Note")
+
+ actual, err := db.QueryNotes(1234)
+ check(t, err, "Failed to get Notes")
+
+ if !reflect.DeepEqual(expected, actual) {
+ t.Errorf("Got %#v,\nbut expected %#v.", actual, expected)
+ }
+}
diff --git a/scouting/deploy/BUILD b/scouting/deploy/BUILD
new file mode 100644
index 0000000..ed4b9cd
--- /dev/null
+++ b/scouting/deploy/BUILD
@@ -0,0 +1,60 @@
+load("@rules_pkg//pkg:pkg.bzl", "pkg_deb", "pkg_tar")
+load("@rules_pkg//pkg:mappings.bzl", "pkg_files")
+
+pkg_files(
+ name = "systemd_files",
+ srcs = [
+ "scouting.service",
+ ],
+ prefix = "etc/systemd/system",
+)
+
+pkg_tar(
+ name = "server_files",
+ srcs = [
+ "//scouting",
+ ],
+ include_runfiles = True,
+ package_dir = "opt/frc971/scouting_server",
+ strip_prefix = ".",
+)
+
+pkg_tar(
+ name = "deploy_tar",
+ srcs = [
+ ":systemd_files",
+ ],
+ deps = [
+ ":server_files",
+ ],
+)
+
+pkg_deb(
+ name = "frc971-scouting-server",
+ architecture = "amd64",
+ data = ":deploy_tar",
+ description = "The FRC971 scouting web server.",
+ # TODO(phil): What's a good email address for this?
+ maintainer = "frc971@frc971.org",
+ package = "frc971-scouting-server",
+ postinst = "postinst",
+ predepends = [
+ "systemd",
+ ],
+ prerm = "prerm",
+ version = "1",
+)
+
+py_binary(
+ name = "deploy",
+ srcs = [
+ "deploy.py",
+ ],
+ args = [
+ "--deb",
+ "$(location :frc971-scouting-server)",
+ ],
+ data = [
+ ":frc971-scouting-server",
+ ],
+)
diff --git a/scouting/deploy/README.md b/scouting/deploy/README.md
new file mode 100644
index 0000000..6d223da
--- /dev/null
+++ b/scouting/deploy/README.md
@@ -0,0 +1,37 @@
+Deploying the scouting application
+================================================================================
+The scouting application is deployed to `scouting.frc971.org` via `bazel`:
+```console
+$ bazel run //scouting/deploy
+(Reading database ... 119978 files and directories currently installed.)
+Preparing to unpack .../frc971-scouting-server_1_amd64.deb ...
+Removed /etc/systemd/system/multi-user.target.wants/scouting.service.
+Unpacking frc971-scouting-server (1) over (1) ...
+Setting up frc971-scouting-server (1) ...
+Created symlink /etc/systemd/system/multi-user.target.wants/scouting.service → /etc/systemd/system/scouting.service.
+Connection to scouting.frc971.org closed.
+```
+
+You will need SSH access to the scouting server. You can customize the SSH host
+with the `--host` argument.
+
+The Blue Alliance API key
+--------------------------------------------------------------------------------
+You need to set up an API key on the scouting server so that the scraping logic
+can use it. It needs to live in `/var/frc971/scouting/tba_config.json` and look
+as follows:
+```json
+{
+ "api_key": "..."
+}
+```
+
+Starting and stopping the application
+--------------------------------------------------------------------------------
+When you SSH into the scouting server, use `systemctl` to manage
+`scouting.service` like any other service.
+```console
+$ sudo systemctl stop scouting.service
+$ sudo systemctl start scouting.service
+$ sudo systemctl restart scouting.service
+```
diff --git a/scouting/deploy/deploy.py b/scouting/deploy/deploy.py
new file mode 100644
index 0000000..c9886fb
--- /dev/null
+++ b/scouting/deploy/deploy.py
@@ -0,0 +1,34 @@
+import argparse
+from pathlib import Path
+import subprocess
+import sys
+
+def main(argv):
+ """Installs the scouting application on the scouting server."""
+ parser = argparse.ArgumentParser()
+ parser.add_argument(
+ "--deb",
+ type=str,
+ required=True,
+ help="The .deb file to deploy.",
+ )
+ parser.add_argument(
+ "--host",
+ type=str,
+ default="scouting.frc971.org",
+ help="The SSH host to install the scouting web server to.",
+ )
+ args = parser.parse_args(argv[1:])
+ deb = Path(args.deb)
+
+ # Copy the .deb to the scouting server, install it, and delete it again.
+ subprocess.run(["rsync", "-L", args.deb, f"{args.host}:/tmp/{deb.name}"],
+ check=True, stdin=sys.stdin)
+ subprocess.run(f"ssh -tt {args.host} sudo dpkg -i /tmp/{deb.name}",
+ shell=True, check=True, stdin=sys.stdin)
+ subprocess.run(f"ssh {args.host} rm -f /tmp/{deb.name}",
+ shell=True, check=True, stdin=sys.stdin)
+
+
+if __name__ == "__main__":
+ sys.exit(main(sys.argv))
diff --git a/scouting/deploy/postinst b/scouting/deploy/postinst
new file mode 100644
index 0000000..a7a8b16
--- /dev/null
+++ b/scouting/deploy/postinst
@@ -0,0 +1,24 @@
+#!/bin/bash
+
+# This script runs after the frc971-scouting-server package is installed. This
+# script is responsible for making sure the webserver has everything it needs,
+# then starts the webserver.
+
+set -o errexit
+set -o nounset
+set -o pipefail
+
+# Create a directory for the database to live in.
+mkdir -p /var/frc971/scouting/
+
+# Create an empty The Blue Alliance configuration file.
+if [[ ! -e /var/frc971/scouting/tba_config.json ]]; then
+ echo '{}' > /var/frc971/scouting/tba_config.json
+fi
+
+# Make sure it's all usable by the user.
+chown -R www-data:www-data /var/frc971/scouting/
+
+systemctl daemon-reload
+systemctl enable scouting.service
+systemctl start scouting.service || :
diff --git a/scouting/deploy/prerm b/scouting/deploy/prerm
new file mode 100644
index 0000000..31e3fbc
--- /dev/null
+++ b/scouting/deploy/prerm
@@ -0,0 +1,13 @@
+#!/bin/bash
+
+# This script gets run before the frc971-scouting-server package gets removed
+# or upgraded. This script is responsible for stopping the webserver before the
+# underlying files are removed by dpkg.
+
+set -o errexit
+set -o nounset
+set -o pipefail
+
+systemctl stop scouting.service
+systemctl disable scouting.service
+systemctl daemon-reload
diff --git a/scouting/deploy/scouting.service b/scouting/deploy/scouting.service
new file mode 100644
index 0000000..2990f42
--- /dev/null
+++ b/scouting/deploy/scouting.service
@@ -0,0 +1,17 @@
+[Unit]
+Description=FRC971 Scouting Server
+After=systemd-networkd-wait-online.service
+
+[Service]
+User=www-data
+Group=www-data
+Type=simple
+WorkingDirectory=/opt/frc971/scouting_server
+ExecStart=/opt/frc971/scouting_server/scouting/scouting \
+ -port 8080 \
+ -database /var/frc971/scouting/scouting.db \
+ -tba_config /var/frc971/scouting/tba_config.json
+Restart=always
+
+[Install]
+WantedBy=multi-user.target
diff --git a/scouting/scouting_test.ts b/scouting/scouting_test.ts
index bb1c075..f400430 100644
--- a/scouting/scouting_test.ts
+++ b/scouting/scouting_test.ts
@@ -1,32 +1,81 @@
-import {browser, by, element} from 'protractor';
+import {browser, by, element, protractor} from 'protractor';
-class AppPage {
- async navigateTo() {
- await browser.get(browser.baseUrl);
- }
+// Returns the contents of the header that displays the "Auto", "TeleOp", and
+// "Climb" labels etc.
+function getHeadingText() {
+ return element(by.css('.header')).getText();
+}
- // Wait for basically forever for these elements to appear.
- // Bazel will manage the timeouts.
- async waitForElement(el, timeout = 1000000) {
- await browser.wait(() => el.isPresent(), timeout);
- await browser.wait(() => el.isDisplayed(), timeout);
- return el;
- }
+// Returns the currently displayed error message on the screen. This only
+// exists on screens where the web page interacts with the web server.
+function getErrorMessage() {
+ return element(by.css('.error_message')).getText();
+}
- async getParagraphText() {
- return (await this.waitForElement(element(by.css('h1')))).getText();
- }
+// Asserts that the field on the "Submit and Review" screen has a specific
+// value.
+function expectReviewFieldToBe(fieldName: string, expectedValue: string) {
+ return expectNthReviewFieldToBe(fieldName, 0, expectedValue);
+}
+
+// Asserts that the n'th instance of a field on the "Submit and Review"
+// screen has a specific value.
+async function expectNthReviewFieldToBe(fieldName: string, n: number, expectedValue: string) {
+ expect(await element.all(by.cssContainingText('li', `${fieldName}:`)).get(n).getText())
+ .toEqual(`${fieldName}: ${expectedValue}`);
}
describe('The scouting web page', () => {
- let page: AppPage;
+ it('should: review and submit correct data.', async () => {
+ await browser.get(browser.baseUrl);
- beforeEach(() => {
- page = new AppPage();
- });
+ expect(await getHeadingText()).toEqual('Team Selection');
+ // Just sending "971" to the input fields is insufficient. We need to
+ // overwrite the text that is there. If we didn't hit CTRL-A to select all
+ // the text, we'd be appending to whatever is there already.
+ await element(by.id('team_number')).sendKeys(
+ protractor.Key.CONTROL, 'a', protractor.Key.NULL,
+ '971');
+ await element(by.buttonText('Next')).click();
- it('should display: This is an app.', async () => {
- await page.navigateTo();
- expect(await page.getParagraphText()).toEqual('This is an app.');
+ expect(await getHeadingText()).toEqual('Auto');
+ await element(by.buttonText('Next')).click();
+
+ expect(await getHeadingText()).toEqual('TeleOp');
+ await element(by.buttonText('Next')).click();
+
+ expect(await getHeadingText()).toEqual('Climb');
+ await element(by.buttonText('Next')).click();
+
+ expect(await getHeadingText()).toEqual('Defense');
+ await element(by.buttonText('Next')).click();
+
+ expect(await getHeadingText()).toEqual('Review and Submit');
+ expect(await getErrorMessage()).toEqual('');
+
+ // Validate Team Selection.
+ await expectReviewFieldToBe('Match number', '1');
+ await expectReviewFieldToBe('Team number', '971');
+
+ // Validate Auto.
+ await expectNthReviewFieldToBe('Upper Shots Made', 0, '0');
+ await expectNthReviewFieldToBe('Lower Shots Made', 0, '0');
+ await expectNthReviewFieldToBe('Missed Shots', 0, '0');
+
+ // Validate TeleOp.
+ await expectNthReviewFieldToBe('Upper Shots Made', 1, '0');
+ await expectNthReviewFieldToBe('Lower Shots Made', 1, '0');
+ await expectNthReviewFieldToBe('Missed Shots', 1, '0');
+
+ // Validate Climb.
+ await expectReviewFieldToBe('Attempted to Climb', 'No');
+
+ // Validate Defense.
+ await expectReviewFieldToBe('Defense Played On Rating', '0');
+ await expectReviewFieldToBe('Defense Played Rating', '0');
+
+ // TODO(phil): Submit data and make sure it made its way to the database
+ // correctly. Right now the /requests/submit/data_scouting endpoint is not
+ // implemented.
});
});
diff --git a/scouting/scraping/BUILD b/scouting/scraping/BUILD
index d9248f8..c643192 100644
--- a/scouting/scraping/BUILD
+++ b/scouting/scraping/BUILD
@@ -1,5 +1,15 @@
load("@io_bazel_rules_go//go:def.bzl", "go_binary", "go_library")
+filegroup(
+ name = "test_data",
+ srcs = [
+ # Generated with: bazel run //scouting/scraping:scraping_demo -- --json
+ "test_data/2016_nytr.json",
+ "test_data/2020_fake.json",
+ ],
+ visibility = ["//visibility:public"],
+)
+
go_library(
name = "scraping",
srcs = [
diff --git a/scouting/scraping/scrape.go b/scouting/scraping/scrape.go
index fa20f7b..170fe50 100644
--- a/scouting/scraping/scrape.go
+++ b/scouting/scraping/scrape.go
@@ -4,15 +4,17 @@
import (
"encoding/json"
"errors"
+ "fmt"
"io/ioutil"
- "log"
"net/http"
"os"
+ "strconv"
)
// Stores the TBA API key to access the API.
-type params struct {
- ApiKey string `json:"api_key"`
+type scrapingConfig struct {
+ ApiKey string `json:"api_key"`
+ BaseUrl string `json:"base_url"`
}
// Takes in year and FIRST event code and returns all matches in that event according to TBA.
@@ -22,64 +24,64 @@
//{
// api_key:"myTBAapiKey"
//}
-func AllMatches(year, eventCode, filePath string) ([]Match, error) {
- if filePath == "" {
- filePath = os.Getenv("BUILD_WORKSPACE_DIRECTORY") + "/scouting_config.json"
+func AllMatches(year int32, eventCode, configPath string) ([]Match, error) {
+ if configPath == "" {
+ configPath = os.Getenv("BUILD_WORKSPACE_DIRECTORY") + "/scouting_config.json"
}
+
// Takes the filepath and grabs the api key from the json.
- content, err := ioutil.ReadFile(filePath)
+ content, err := ioutil.ReadFile(configPath)
if err != nil {
- log.Fatal(err)
+ return nil, errors.New(fmt.Sprint("Failed to open config at ", configPath, ": ", err))
}
// Parses the JSON parameters into a struct.
- var passed_params params
- error := json.Unmarshal([]byte(content), &passed_params)
- if error != nil {
- log.Fatalf("You forgot to add the api_key parameter in the json file")
- log.Fatalf("%s", err)
+ var config scrapingConfig
+ if err := json.Unmarshal([]byte(content), &config); err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to parse config file as JSON: ", err))
+ }
+
+ // Perform some basic validation on the data.
+ if config.ApiKey == "" {
+ return nil, errors.New("Missing 'api_key' in config JSON.")
+ }
+ if config.BaseUrl == "" {
+ config.BaseUrl = "https://www.thebluealliance.com"
}
// Create the TBA event key for the year and event code.
- eventKey := year + eventCode
-
- // Create the client for HTTP requests.
- client := &http.Client{}
+ eventKey := strconv.Itoa(int(year)) + eventCode
// Create a get request for the match info.
- req, err := http.NewRequest("GET", "https://www.thebluealliance.com/api/v3/event/"+eventKey+"/matches", nil)
-
+ req, err := http.NewRequest("GET", config.BaseUrl+"/api/v3/event/"+eventKey+"/matches", nil)
if err != nil {
- return nil, errors.New("failed to build http request")
+ return nil, errors.New(fmt.Sprint("Failed to build http request: ", err))
}
// Add the auth key header to the request.
- req.Header.Add("X-TBA-Auth-Key", passed_params.ApiKey)
+ req.Header.Add("X-TBA-Auth-Key", config.ApiKey)
- // Make the API request
+ // Make the API request.
+ client := &http.Client{}
resp, err := client.Do(req)
-
if err != nil {
- return nil, err
+ return nil, errors.New(fmt.Sprint("Failed to make TBA API request: ", err))
}
- if resp.Status != "200 OK" {
- return nil, errors.New("Recieved a status of " + resp.Status + " expected : 200 OK")
- }
-
- // Wait until the response is done.
defer resp.Body.Close()
+ if resp.StatusCode != 200 {
+ return nil, errors.New(fmt.Sprint("Got unexpected status code from TBA API request: ", resp.Status))
+ }
// Get all bytes from response body.
bodyBytes, err := ioutil.ReadAll(resp.Body)
if err != nil {
- return nil, errors.New("failed to read response body with error :" + err.Error())
+ return nil, errors.New(fmt.Sprint("Failed to read TBA API response: ", err))
}
var matches []Match
// Unmarshal json into go usable format.
- jsonError := json.Unmarshal([]byte(bodyBytes), &matches)
- if jsonError != nil {
- return nil, errors.New("failed to unmarshal json recieved from TBA")
+ if err := json.Unmarshal([]byte(bodyBytes), &matches); err != nil {
+ return nil, errors.New(fmt.Sprint("Failed to parse JSON received from TBA: ", err))
}
return matches, nil
diff --git a/scouting/scraping/scraping_demo.go b/scouting/scraping/scraping_demo.go
index 1d727f3..0ea3e53 100644
--- a/scouting/scraping/scraping_demo.go
+++ b/scouting/scraping/scraping_demo.go
@@ -2,6 +2,9 @@
// To run the demo, ensure that you have a file named scouting_config.json at the workspace root with your TBA api key in it.
import (
+ "encoding/json"
+ "flag"
+ "fmt"
"log"
"github.com/davecgh/go-spew/spew"
@@ -9,12 +12,23 @@
)
func main() {
+ jsonPtr := flag.Bool("json", false, "If set, dump as JSON, rather than Go debug output.")
+ flag.Parse()
+
// Get all the matches.
- matches, err := scraping.AllMatches("2016", "nytr", "")
- // Fail on error.
+ matches, err := scraping.AllMatches(2016, "nytr", "")
if err != nil {
- log.Fatal("Error:", err.Error)
+ log.Fatal("Failed to scrape match list: ", err)
}
+
// Dump the matches.
- spew.Dump(matches)
+ if *jsonPtr {
+ jsonData, err := json.MarshalIndent(matches, "", " ")
+ if err != nil {
+ log.Fatal("Failed to turn match list into JSON: ", err)
+ }
+ fmt.Println(string(jsonData))
+ } else {
+ spew.Dump(matches)
+ }
}
diff --git a/scouting/scraping/test_data/2016_nytr.json b/scouting/scraping/test_data/2016_nytr.json
new file mode 100644
index 0000000..120d6d3
--- /dev/null
+++ b/scouting/scraping/test_data/2016_nytr.json
@@ -0,0 +1,10812 @@
+[
+ {
+ "Key": "2016nytr_f1m1",
+ "comp_level": "f",
+ "set_number": 1,
+ "match_number": 1,
+ "alliances": {
+ "red": {
+ "score": 168,
+ "team_keys": [
+ "frc3990",
+ "frc359",
+ "frc4508"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 115,
+ "team_keys": [
+ "frc20",
+ "frc5254",
+ "frc1665"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458418140,
+ "predicted_time": 0,
+ "actual_time": 1458417643,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_f1m2",
+ "comp_level": "f",
+ "set_number": 1,
+ "match_number": 2,
+ "alliances": {
+ "red": {
+ "score": 134,
+ "team_keys": [
+ "frc3990",
+ "frc359",
+ "frc4508"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 136,
+ "team_keys": [
+ "frc20",
+ "frc5254",
+ "frc1665"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458418920,
+ "predicted_time": 0,
+ "actual_time": 1458418685,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_f1m3",
+ "comp_level": "f",
+ "set_number": 1,
+ "match_number": 3,
+ "alliances": {
+ "red": {
+ "score": 164,
+ "team_keys": [
+ "frc3990",
+ "frc359",
+ "frc4508"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 147,
+ "team_keys": [
+ "frc20",
+ "frc5254",
+ "frc1665"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458419700,
+ "predicted_time": 0,
+ "actual_time": 1458419924,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qf1m1",
+ "comp_level": "qf",
+ "set_number": 1,
+ "match_number": 1,
+ "alliances": {
+ "red": {
+ "score": 121,
+ "team_keys": [
+ "frc3990",
+ "frc359",
+ "frc4508"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 107,
+ "team_keys": [
+ "frc3044",
+ "frc4930",
+ "frc4481"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458408600,
+ "predicted_time": 0,
+ "actual_time": 1458408170,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qf1m2",
+ "comp_level": "qf",
+ "set_number": 1,
+ "match_number": 2,
+ "alliances": {
+ "red": {
+ "score": 170,
+ "team_keys": [
+ "frc3990",
+ "frc359",
+ "frc4508"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 80,
+ "team_keys": [
+ "frc3044",
+ "frc4930",
+ "frc4481"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458410460,
+ "predicted_time": 0,
+ "actual_time": 1458410300,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qf2m1",
+ "comp_level": "qf",
+ "set_number": 2,
+ "match_number": 1,
+ "alliances": {
+ "red": {
+ "score": 107,
+ "team_keys": [
+ "frc5240",
+ "frc3419",
+ "frc663"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 110,
+ "team_keys": [
+ "frc1493",
+ "frc48",
+ "frc1551"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458409020,
+ "predicted_time": 0,
+ "actual_time": 1458408692,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qf2m2",
+ "comp_level": "qf",
+ "set_number": 2,
+ "match_number": 2,
+ "alliances": {
+ "red": {
+ "score": 116,
+ "team_keys": [
+ "frc5240",
+ "frc3419",
+ "frc663"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 78,
+ "team_keys": [
+ "frc1493",
+ "frc48",
+ "frc1551"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458410880,
+ "predicted_time": 0,
+ "actual_time": 1458410748,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qf2m3",
+ "comp_level": "qf",
+ "set_number": 2,
+ "match_number": 3,
+ "alliances": {
+ "red": {
+ "score": 104,
+ "team_keys": [
+ "frc5240",
+ "frc3419",
+ "frc663"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 94,
+ "team_keys": [
+ "frc1493",
+ "frc48",
+ "frc1551"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458412920,
+ "predicted_time": 0,
+ "actual_time": 1458412900,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qf3m1",
+ "comp_level": "qf",
+ "set_number": 3,
+ "match_number": 1,
+ "alliances": {
+ "red": {
+ "score": 132,
+ "team_keys": [
+ "frc20",
+ "frc5254",
+ "frc229"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 84,
+ "team_keys": [
+ "frc3003",
+ "frc358",
+ "frc527"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458409440,
+ "predicted_time": 0,
+ "actual_time": 1458409186,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qf3m2",
+ "comp_level": "qf",
+ "set_number": 3,
+ "match_number": 2,
+ "alliances": {
+ "red": {
+ "score": 144,
+ "team_keys": [
+ "frc20",
+ "frc5254",
+ "frc229"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 103,
+ "team_keys": [
+ "frc3003",
+ "frc358",
+ "frc527"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458411300,
+ "predicted_time": 0,
+ "actual_time": 1458411317,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qf4m1",
+ "comp_level": "qf",
+ "set_number": 4,
+ "match_number": 1,
+ "alliances": {
+ "red": {
+ "score": 147,
+ "team_keys": [
+ "frc2791",
+ "frc5236",
+ "frc3624"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 121,
+ "team_keys": [
+ "frc333",
+ "frc250",
+ "frc145"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458409860,
+ "predicted_time": 0,
+ "actual_time": 1458409739,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qf4m2",
+ "comp_level": "qf",
+ "set_number": 4,
+ "match_number": 2,
+ "alliances": {
+ "red": {
+ "score": 106,
+ "team_keys": [
+ "frc2791",
+ "frc5236",
+ "frc3624"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 151,
+ "team_keys": [
+ "frc333",
+ "frc250",
+ "frc145"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458411720,
+ "predicted_time": 0,
+ "actual_time": 1458411761,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qf4m3",
+ "comp_level": "qf",
+ "set_number": 4,
+ "match_number": 3,
+ "alliances": {
+ "red": {
+ "score": 165,
+ "team_keys": [
+ "frc2791",
+ "frc5236",
+ "frc3624"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 89,
+ "team_keys": [
+ "frc333",
+ "frc250",
+ "frc145"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458413760,
+ "predicted_time": 0,
+ "actual_time": 1458413371,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm1",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 1,
+ "alliances": {
+ "red": {
+ "score": 62,
+ "team_keys": [
+ "frc5240",
+ "frc3003",
+ "frc3419"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 85,
+ "team_keys": [
+ "frc3990",
+ "frc371",
+ "frc2791"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458306000,
+ "predicted_time": 0,
+ "actual_time": 1458306152,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm10",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 10,
+ "alliances": {
+ "red": {
+ "score": 79,
+ "team_keys": [
+ "frc250",
+ "frc5879",
+ "frc2791"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 85,
+ "team_keys": [
+ "frc371",
+ "frc4856",
+ "frc359"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458310680,
+ "predicted_time": 0,
+ "actual_time": 1458310963,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm11",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 11,
+ "alliances": {
+ "red": {
+ "score": 40,
+ "team_keys": [
+ "frc1551",
+ "frc1665",
+ "frc3624"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": [
+ "frc3624"
+ ]
+ },
+ "blue": {
+ "score": 82,
+ "team_keys": [
+ "frc20",
+ "frc3044",
+ "frc4093"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458311160,
+ "predicted_time": 0,
+ "actual_time": 1458311501,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm12",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 12,
+ "alliances": {
+ "red": {
+ "score": 76,
+ "team_keys": [
+ "frc3990",
+ "frc4481",
+ "frc5881"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 45,
+ "team_keys": [
+ "frc4203",
+ "frc663",
+ "frc527"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458311640,
+ "predicted_time": 0,
+ "actual_time": 1458311984,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm13",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 13,
+ "alliances": {
+ "red": {
+ "score": 24,
+ "team_keys": [
+ "frc1450",
+ "frc4856",
+ "frc5879"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": [
+ "frc5879"
+ ]
+ },
+ "blue": {
+ "score": 60,
+ "team_keys": [
+ "frc5254",
+ "frc5585",
+ "frc371"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458312120,
+ "predicted_time": 0,
+ "actual_time": 1458312573,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm14",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 14,
+ "alliances": {
+ "red": {
+ "score": 34,
+ "team_keys": [
+ "frc4508",
+ "frc5149",
+ "frc250"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 44,
+ "team_keys": [
+ "frc5964",
+ "frc5240",
+ "frc1665"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458312600,
+ "predicted_time": 0,
+ "actual_time": 1458313136,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm15",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 15,
+ "alliances": {
+ "red": {
+ "score": 91,
+ "team_keys": [
+ "frc2791",
+ "frc5881",
+ "frc527"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 85,
+ "team_keys": [
+ "frc48",
+ "frc3624",
+ "frc333"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": [
+ "frc3624"
+ ]
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458313080,
+ "predicted_time": 0,
+ "actual_time": 1458313525,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm16",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 16,
+ "alliances": {
+ "red": {
+ "score": 95,
+ "team_keys": [
+ "frc229",
+ "frc1493",
+ "frc359"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 77,
+ "team_keys": [
+ "frc3419",
+ "frc3044",
+ "frc663"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458313740,
+ "predicted_time": 0,
+ "actual_time": 1458314003,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm17",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 17,
+ "alliances": {
+ "red": {
+ "score": 45,
+ "team_keys": [
+ "frc3990",
+ "frc4203",
+ "frc5943"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 86,
+ "team_keys": [
+ "frc1551",
+ "frc358",
+ "frc145"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458314220,
+ "predicted_time": 0,
+ "actual_time": 1458314433,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm18",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 18,
+ "alliances": {
+ "red": {
+ "score": 75,
+ "team_keys": [
+ "frc4481",
+ "frc4930",
+ "frc4093"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 88,
+ "team_keys": [
+ "frc5236",
+ "frc3003",
+ "frc20"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458314700,
+ "predicted_time": 0,
+ "actual_time": 1458314859,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm19",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 19,
+ "alliances": {
+ "red": {
+ "score": 88,
+ "team_keys": [
+ "frc48",
+ "frc5149",
+ "frc5254"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 62,
+ "team_keys": [
+ "frc229",
+ "frc663",
+ "frc4856"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458315180,
+ "predicted_time": 0,
+ "actual_time": 1458315401,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm2",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 2,
+ "alliances": {
+ "red": {
+ "score": 85,
+ "team_keys": [
+ "frc48",
+ "frc3044",
+ "frc4856"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": [
+ "frc4856"
+ ]
+ },
+ "blue": {
+ "score": 15,
+ "team_keys": [
+ "frc4481",
+ "frc358",
+ "frc3624"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": [
+ "frc3624"
+ ]
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458306480,
+ "predicted_time": 0,
+ "actual_time": 1458306689,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm20",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 20,
+ "alliances": {
+ "red": {
+ "score": 10,
+ "team_keys": [
+ "frc1665",
+ "frc371",
+ "frc5943"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 65,
+ "team_keys": [
+ "frc5585",
+ "frc3624",
+ "frc3044"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458315660,
+ "predicted_time": 0,
+ "actual_time": 1458315911,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm21",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 21,
+ "alliances": {
+ "red": {
+ "score": 30,
+ "team_keys": [
+ "frc1551",
+ "frc4203",
+ "frc250"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 81,
+ "team_keys": [
+ "frc333",
+ "frc20",
+ "frc1493"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458316140,
+ "predicted_time": 0,
+ "actual_time": 1458316579,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm22",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 22,
+ "alliances": {
+ "red": {
+ "score": 124,
+ "team_keys": [
+ "frc359",
+ "frc3419",
+ "frc145"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 66,
+ "team_keys": [
+ "frc2791",
+ "frc4481",
+ "frc3003"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458316800,
+ "predicted_time": 0,
+ "actual_time": 1458316995,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm23",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 23,
+ "alliances": {
+ "red": {
+ "score": 63,
+ "team_keys": [
+ "frc5964",
+ "frc4508",
+ "frc5881"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 81,
+ "team_keys": [
+ "frc4093",
+ "frc1450",
+ "frc3990"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458317280,
+ "predicted_time": 0,
+ "actual_time": 1458317393,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm24",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 24,
+ "alliances": {
+ "red": {
+ "score": 26,
+ "team_keys": [
+ "frc358",
+ "frc5236",
+ "frc527"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 47,
+ "team_keys": [
+ "frc5240",
+ "frc4930",
+ "frc5879"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458321360,
+ "predicted_time": 0,
+ "actual_time": 1458321119,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm25",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 25,
+ "alliances": {
+ "red": {
+ "score": 69,
+ "team_keys": [
+ "frc250",
+ "frc371",
+ "frc3003"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 62,
+ "team_keys": [
+ "frc5585",
+ "frc4481",
+ "frc4203"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458321840,
+ "predicted_time": 0,
+ "actual_time": 1458321835,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm26",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 26,
+ "alliances": {
+ "red": {
+ "score": 99,
+ "team_keys": [
+ "frc229",
+ "frc333",
+ "frc5881"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 115,
+ "team_keys": [
+ "frc1665",
+ "frc359",
+ "frc3990"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458322320,
+ "predicted_time": 0,
+ "actual_time": 1458322308,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm27",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 27,
+ "alliances": {
+ "red": {
+ "score": 73,
+ "team_keys": [
+ "frc5240",
+ "frc527",
+ "frc20"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 47,
+ "team_keys": [
+ "frc4856",
+ "frc4930",
+ "frc5943"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458322800,
+ "predicted_time": 0,
+ "actual_time": 1458322685,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm28",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 28,
+ "alliances": {
+ "red": {
+ "score": 29,
+ "team_keys": [
+ "frc5149",
+ "frc3624",
+ "frc145"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 84,
+ "team_keys": [
+ "frc5254",
+ "frc358",
+ "frc1450"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458323460,
+ "predicted_time": 0,
+ "actual_time": 1458323094,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm29",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 29,
+ "alliances": {
+ "red": {
+ "score": 51,
+ "team_keys": [
+ "frc1493",
+ "frc4093",
+ "frc5879"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 82,
+ "team_keys": [
+ "frc5964",
+ "frc48",
+ "frc3419"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458323940,
+ "predicted_time": 0,
+ "actual_time": 1458324109,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm3",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 3,
+ "alliances": {
+ "red": {
+ "score": 60,
+ "team_keys": [
+ "frc663",
+ "frc4093",
+ "frc333"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 64,
+ "team_keys": [
+ "frc5585",
+ "frc145",
+ "frc1450"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458306960,
+ "predicted_time": 0,
+ "actual_time": 1458307302,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm30",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 30,
+ "alliances": {
+ "red": {
+ "score": 54,
+ "team_keys": [
+ "frc3044",
+ "frc1551",
+ "frc4508"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 93,
+ "team_keys": [
+ "frc5236",
+ "frc663",
+ "frc2791"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458324420,
+ "predicted_time": 0,
+ "actual_time": 1458324499,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm31",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 31,
+ "alliances": {
+ "red": {
+ "score": 66,
+ "team_keys": [
+ "frc5585",
+ "frc20",
+ "frc4856"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 112,
+ "team_keys": [
+ "frc333",
+ "frc4930",
+ "frc3990"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458324900,
+ "predicted_time": 0,
+ "actual_time": 1458325029,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm32",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 32,
+ "alliances": {
+ "red": {
+ "score": 49,
+ "team_keys": [
+ "frc145",
+ "frc371",
+ "frc4093"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 92,
+ "team_keys": [
+ "frc5879",
+ "frc5964",
+ "frc359"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458325380,
+ "predicted_time": 0,
+ "actual_time": 1458325592,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm33",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 33,
+ "alliances": {
+ "red": {
+ "score": 74,
+ "team_keys": [
+ "frc3624",
+ "frc527",
+ "frc229"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 67,
+ "team_keys": [
+ "frc5236",
+ "frc4203",
+ "frc4508"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458325860,
+ "predicted_time": 0,
+ "actual_time": 1458325971,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm34",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 34,
+ "alliances": {
+ "red": {
+ "score": 70,
+ "team_keys": [
+ "frc4481",
+ "frc5149",
+ "frc1450"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 86,
+ "team_keys": [
+ "frc1551",
+ "frc2791",
+ "frc1493"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458326520,
+ "predicted_time": 0,
+ "actual_time": 1458326383,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm35",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 35,
+ "alliances": {
+ "red": {
+ "score": 72,
+ "team_keys": [
+ "frc663",
+ "frc48",
+ "frc5943"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 83,
+ "team_keys": [
+ "frc1665",
+ "frc5254",
+ "frc3003"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458327000,
+ "predicted_time": 0,
+ "actual_time": 1458326796,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm36",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 36,
+ "alliances": {
+ "red": {
+ "score": 107,
+ "team_keys": [
+ "frc3044",
+ "frc5240",
+ "frc250"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 74,
+ "team_keys": [
+ "frc3419",
+ "frc358",
+ "frc5881"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458327480,
+ "predicted_time": 0,
+ "actual_time": 1458327181,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm37",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 37,
+ "alliances": {
+ "red": {
+ "score": 66,
+ "team_keys": [
+ "frc4481",
+ "frc145",
+ "frc1493"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 90,
+ "team_keys": [
+ "frc527",
+ "frc371",
+ "frc333"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458327960,
+ "predicted_time": 0,
+ "actual_time": 1458327852,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm38",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 38,
+ "alliances": {
+ "red": {
+ "score": 44,
+ "team_keys": [
+ "frc5236",
+ "frc4856",
+ "frc5149"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 111,
+ "team_keys": [
+ "frc20",
+ "frc48",
+ "frc3990"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458328440,
+ "predicted_time": 0,
+ "actual_time": 1458328284,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm39",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 39,
+ "alliances": {
+ "red": {
+ "score": 99,
+ "team_keys": [
+ "frc3419",
+ "frc2791",
+ "frc4930"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 67,
+ "team_keys": [
+ "frc5964",
+ "frc1551",
+ "frc663"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458328920,
+ "predicted_time": 0,
+ "actual_time": 1458328709,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm4",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 4,
+ "alliances": {
+ "red": {
+ "score": 73,
+ "team_keys": [
+ "frc4508",
+ "frc4930",
+ "frc1493"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 78,
+ "team_keys": [
+ "frc5254",
+ "frc250",
+ "frc5943"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458307620,
+ "predicted_time": 0,
+ "actual_time": 1458307725,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm40",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 40,
+ "alliances": {
+ "red": {
+ "score": 82,
+ "team_keys": [
+ "frc5254",
+ "frc5879",
+ "frc4203"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 77,
+ "team_keys": [
+ "frc5881",
+ "frc5943",
+ "frc3044"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458329580,
+ "predicted_time": 0,
+ "actual_time": 1458329683,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm41",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 41,
+ "alliances": {
+ "red": {
+ "score": 70,
+ "team_keys": [
+ "frc3624",
+ "frc1450",
+ "frc5240"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 77,
+ "team_keys": [
+ "frc4093",
+ "frc250",
+ "frc229"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458330060,
+ "predicted_time": 0,
+ "actual_time": 1458330063,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm42",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 42,
+ "alliances": {
+ "red": {
+ "score": 109,
+ "team_keys": [
+ "frc3003",
+ "frc359",
+ "frc358"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 39,
+ "team_keys": [
+ "frc5585",
+ "frc1665",
+ "frc4508"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458330540,
+ "predicted_time": 0,
+ "actual_time": 1458330433,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm43",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 43,
+ "alliances": {
+ "red": {
+ "score": 61,
+ "team_keys": [
+ "frc5881",
+ "frc4203",
+ "frc145"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 64,
+ "team_keys": [
+ "frc3044",
+ "frc4930",
+ "frc527"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458331020,
+ "predicted_time": 0,
+ "actual_time": 1458330818,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm44",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 44,
+ "alliances": {
+ "red": {
+ "score": 101,
+ "team_keys": [
+ "frc5254",
+ "frc333",
+ "frc4481"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 77,
+ "team_keys": [
+ "frc5149",
+ "frc5240",
+ "frc2791"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458331500,
+ "predicted_time": 0,
+ "actual_time": 1458331224,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm45",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 45,
+ "alliances": {
+ "red": {
+ "score": 60,
+ "team_keys": [
+ "frc5964",
+ "frc4093",
+ "frc3003"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 62,
+ "team_keys": [
+ "frc250",
+ "frc4856",
+ "frc1493"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458331980,
+ "predicted_time": 0,
+ "actual_time": 1458331735,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm46",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 46,
+ "alliances": {
+ "red": {
+ "score": 56,
+ "team_keys": [
+ "frc371",
+ "frc20",
+ "frc3624"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 107,
+ "team_keys": [
+ "frc663",
+ "frc4508",
+ "frc359"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458332640,
+ "predicted_time": 0,
+ "actual_time": 1458332313,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm47",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 47,
+ "alliances": {
+ "red": {
+ "score": 72,
+ "team_keys": [
+ "frc1450",
+ "frc1665",
+ "frc48"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 86,
+ "team_keys": [
+ "frc358",
+ "frc5879",
+ "frc3990"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458333120,
+ "predicted_time": 0,
+ "actual_time": 1458333025,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm48",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 48,
+ "alliances": {
+ "red": {
+ "score": 49,
+ "team_keys": [
+ "frc5943",
+ "frc5585",
+ "frc229"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 102,
+ "team_keys": [
+ "frc1551",
+ "frc3419",
+ "frc5236"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458333600,
+ "predicted_time": 0,
+ "actual_time": 1458333472,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm49",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 49,
+ "alliances": {
+ "red": {
+ "score": 143,
+ "team_keys": [
+ "frc359",
+ "frc3624",
+ "frc5254"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 86,
+ "team_keys": [
+ "frc5964",
+ "frc4481",
+ "frc20"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458334080,
+ "predicted_time": 0,
+ "actual_time": 1458333898,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm5",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 5,
+ "alliances": {
+ "red": {
+ "score": 102,
+ "team_keys": [
+ "frc5236",
+ "frc359",
+ "frc5881"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 19,
+ "team_keys": [
+ "frc5149",
+ "frc4203",
+ "frc5964"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458308100,
+ "predicted_time": 0,
+ "actual_time": 1458308171,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm50",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 50,
+ "alliances": {
+ "red": {
+ "score": 82,
+ "team_keys": [
+ "frc5240",
+ "frc1493",
+ "frc663"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 54,
+ "team_keys": [
+ "frc5879",
+ "frc3003",
+ "frc145"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458334560,
+ "predicted_time": 0,
+ "actual_time": 1458334725,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm51",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 51,
+ "alliances": {
+ "red": {
+ "score": 69,
+ "team_keys": [
+ "frc2791",
+ "frc5943",
+ "frc358"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 52,
+ "team_keys": [
+ "frc5585",
+ "frc5881",
+ "frc4093"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458335040,
+ "predicted_time": 0,
+ "actual_time": 1458335144,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm52",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 52,
+ "alliances": {
+ "red": {
+ "score": 101,
+ "team_keys": [
+ "frc5236",
+ "frc3990",
+ "frc229"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 82,
+ "team_keys": [
+ "frc333",
+ "frc1450",
+ "frc250"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458335700,
+ "predicted_time": 0,
+ "actual_time": 1458335606,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm53",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 53,
+ "alliances": {
+ "red": {
+ "score": 55,
+ "team_keys": [
+ "frc371",
+ "frc3044",
+ "frc5149"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 102,
+ "team_keys": [
+ "frc48",
+ "frc4930",
+ "frc1551"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458336180,
+ "predicted_time": 0,
+ "actual_time": 1458336076,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm54",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 54,
+ "alliances": {
+ "red": {
+ "score": 89,
+ "team_keys": [
+ "frc1665",
+ "frc3419",
+ "frc4203"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 83,
+ "team_keys": [
+ "frc4508",
+ "frc527",
+ "frc4856"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458392400,
+ "predicted_time": 0,
+ "actual_time": 1458391888,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm55",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 55,
+ "alliances": {
+ "red": {
+ "score": 108,
+ "team_keys": [
+ "frc3990",
+ "frc3003",
+ "frc663"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 83,
+ "team_keys": [
+ "frc1493",
+ "frc3624",
+ "frc5943"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458392880,
+ "predicted_time": 0,
+ "actual_time": 1458392321,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm56",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 56,
+ "alliances": {
+ "red": {
+ "score": 94,
+ "team_keys": [
+ "frc5240",
+ "frc5585",
+ "frc333"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 68,
+ "team_keys": [
+ "frc5881",
+ "frc5879",
+ "frc48"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458393360,
+ "predicted_time": 0,
+ "actual_time": 1458393079,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm57",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 57,
+ "alliances": {
+ "red": {
+ "score": 86,
+ "team_keys": [
+ "frc3419",
+ "frc20",
+ "frc5149"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 71,
+ "team_keys": [
+ "frc358",
+ "frc3044",
+ "frc4203"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458393840,
+ "predicted_time": 0,
+ "actual_time": 1458393573,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm58",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 58,
+ "alliances": {
+ "red": {
+ "score": 97,
+ "team_keys": [
+ "frc5254",
+ "frc1551",
+ "frc4093"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 110,
+ "team_keys": [
+ "frc527",
+ "frc359",
+ "frc250"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458394500,
+ "predicted_time": 0,
+ "actual_time": 1458394319,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm59",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 59,
+ "alliances": {
+ "red": {
+ "score": 89,
+ "team_keys": [
+ "frc5964",
+ "frc4856",
+ "frc2791"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 101,
+ "team_keys": [
+ "frc1665",
+ "frc145",
+ "frc5236"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458394980,
+ "predicted_time": 0,
+ "actual_time": 1458394775,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm6",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 6,
+ "alliances": {
+ "red": {
+ "score": 50,
+ "team_keys": [
+ "frc5879",
+ "frc1665",
+ "frc527"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 86,
+ "team_keys": [
+ "frc229",
+ "frc20",
+ "frc1551"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458308580,
+ "predicted_time": 0,
+ "actual_time": 1458309050,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm60",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 60,
+ "alliances": {
+ "red": {
+ "score": 62,
+ "team_keys": [
+ "frc4481",
+ "frc4508",
+ "frc371"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 46,
+ "team_keys": [
+ "frc229",
+ "frc4930",
+ "frc1450"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458395460,
+ "predicted_time": 0,
+ "actual_time": 1458395186,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm61",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 61,
+ "alliances": {
+ "red": {
+ "score": 105,
+ "team_keys": [
+ "frc4093",
+ "frc48",
+ "frc527"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 70,
+ "team_keys": [
+ "frc359",
+ "frc5943",
+ "frc5149"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458395940,
+ "predicted_time": 0,
+ "actual_time": 1458395574,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm62",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 62,
+ "alliances": {
+ "red": {
+ "score": 61,
+ "team_keys": [
+ "frc663",
+ "frc358",
+ "frc20"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 84,
+ "team_keys": [
+ "frc5964",
+ "frc145",
+ "frc5254"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458396420,
+ "predicted_time": 0,
+ "actual_time": 1458395960,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm63",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 63,
+ "alliances": {
+ "red": {
+ "score": 57,
+ "team_keys": [
+ "frc1551",
+ "frc333",
+ "frc5879"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 80,
+ "team_keys": [
+ "frc4508",
+ "frc3624",
+ "frc3003"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458396900,
+ "predicted_time": 0,
+ "actual_time": 1458396366,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm64",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 64,
+ "alliances": {
+ "red": {
+ "score": 85,
+ "team_keys": [
+ "frc1665",
+ "frc3044",
+ "frc1493"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 101,
+ "team_keys": [
+ "frc5236",
+ "frc4481",
+ "frc5240"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458397560,
+ "predicted_time": 0,
+ "actual_time": 1458396974,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm65",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 65,
+ "alliances": {
+ "red": {
+ "score": 110,
+ "team_keys": [
+ "frc3990",
+ "frc4856",
+ "frc3419"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 50,
+ "team_keys": [
+ "frc1450",
+ "frc5881",
+ "frc371"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458398040,
+ "predicted_time": 0,
+ "actual_time": 1458397555,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm66",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 66,
+ "alliances": {
+ "red": {
+ "score": 59,
+ "team_keys": [
+ "frc250",
+ "frc5585",
+ "frc4930"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 57,
+ "team_keys": [
+ "frc4203",
+ "frc2791",
+ "frc229"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458398520,
+ "predicted_time": 0,
+ "actual_time": 1458398075,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm67",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 67,
+ "alliances": {
+ "red": {
+ "score": 97,
+ "team_keys": [
+ "frc333",
+ "frc3044",
+ "frc5964"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 92,
+ "team_keys": [
+ "frc4481",
+ "frc5943",
+ "frc527"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458399000,
+ "predicted_time": 0,
+ "actual_time": 1458398523,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm68",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 68,
+ "alliances": {
+ "red": {
+ "score": 76,
+ "team_keys": [
+ "frc5236",
+ "frc1493",
+ "frc1450"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 80,
+ "team_keys": [
+ "frc4856",
+ "frc358",
+ "frc1665"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458399480,
+ "predicted_time": 0,
+ "actual_time": 1458398992,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm69",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 69,
+ "alliances": {
+ "red": {
+ "score": 101,
+ "team_keys": [
+ "frc2791",
+ "frc20",
+ "frc359"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 40,
+ "team_keys": [
+ "frc5879",
+ "frc5149",
+ "frc229"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458399960,
+ "predicted_time": 0,
+ "actual_time": 1458399575,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm7",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 7,
+ "alliances": {
+ "red": {
+ "score": 64,
+ "team_keys": [
+ "frc4508",
+ "frc5943",
+ "frc1450"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 103,
+ "team_keys": [
+ "frc5240",
+ "frc48",
+ "frc145"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458309060,
+ "predicted_time": 0,
+ "actual_time": 1458309624,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm70",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 70,
+ "alliances": {
+ "red": {
+ "score": 83,
+ "team_keys": [
+ "frc1551",
+ "frc5585",
+ "frc3003"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 96,
+ "team_keys": [
+ "frc5881",
+ "frc5254",
+ "frc5240"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458400620,
+ "predicted_time": 0,
+ "actual_time": 1458400008,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm71",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 71,
+ "alliances": {
+ "red": {
+ "score": 30,
+ "team_keys": [
+ "frc4203",
+ "frc371",
+ "frc48"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 94,
+ "team_keys": [
+ "frc4508",
+ "frc4093",
+ "frc3419"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458401100,
+ "predicted_time": 0,
+ "actual_time": 1458400865,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm72",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 72,
+ "alliances": {
+ "red": {
+ "score": 74,
+ "team_keys": [
+ "frc4930",
+ "frc663",
+ "frc145"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 103,
+ "team_keys": [
+ "frc250",
+ "frc3624",
+ "frc3990"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458401580,
+ "predicted_time": 0,
+ "actual_time": 1458401706,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm8",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 8,
+ "alliances": {
+ "red": {
+ "score": 90,
+ "team_keys": [
+ "frc5254",
+ "frc5236",
+ "frc4930"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 74,
+ "team_keys": [
+ "frc1493",
+ "frc5585",
+ "frc3419"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458309540,
+ "predicted_time": 0,
+ "actual_time": 1458310026,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_qm9",
+ "comp_level": "qm",
+ "set_number": 1,
+ "match_number": 9,
+ "alliances": {
+ "red": {
+ "score": 64,
+ "team_keys": [
+ "frc5964",
+ "frc229",
+ "frc358"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 52,
+ "team_keys": [
+ "frc3003",
+ "frc333",
+ "frc5149"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458310020,
+ "predicted_time": 0,
+ "actual_time": 1458310411,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_sf1m1",
+ "comp_level": "sf",
+ "set_number": 1,
+ "match_number": 1,
+ "alliances": {
+ "red": {
+ "score": 164,
+ "team_keys": [
+ "frc3990",
+ "frc359",
+ "frc4508"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 147,
+ "team_keys": [
+ "frc5240",
+ "frc3419",
+ "frc663"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458414720,
+ "predicted_time": 0,
+ "actual_time": 1458414299,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_sf1m2",
+ "comp_level": "sf",
+ "set_number": 1,
+ "match_number": 2,
+ "alliances": {
+ "red": {
+ "score": 179,
+ "team_keys": [
+ "frc3990",
+ "frc359",
+ "frc4508"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 153,
+ "team_keys": [
+ "frc5240",
+ "frc3419",
+ "frc663"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458415560,
+ "predicted_time": 0,
+ "actual_time": 1458415297,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_sf2m1",
+ "comp_level": "sf",
+ "set_number": 2,
+ "match_number": 1,
+ "alliances": {
+ "red": {
+ "score": 107,
+ "team_keys": [
+ "frc20",
+ "frc5254",
+ "frc229"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 111,
+ "team_keys": [
+ "frc2791",
+ "frc5236",
+ "frc3624"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "blue",
+ "event_key": "2016nytr",
+ "time": 1458415140,
+ "predicted_time": 0,
+ "actual_time": 1458414793,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_sf2m2",
+ "comp_level": "sf",
+ "set_number": 2,
+ "match_number": 2,
+ "alliances": {
+ "red": {
+ "score": 149,
+ "team_keys": [
+ "frc20",
+ "frc5254",
+ "frc1665"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 106,
+ "team_keys": [
+ "frc2791",
+ "frc5236",
+ "frc3624"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458415980,
+ "predicted_time": 0,
+ "actual_time": 1458415857,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ },
+ {
+ "Key": "2016nytr_sf2m3",
+ "comp_level": "sf",
+ "set_number": 2,
+ "match_number": 3,
+ "alliances": {
+ "red": {
+ "score": 149,
+ "team_keys": [
+ "frc20",
+ "frc5254",
+ "frc1665"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ },
+ "blue": {
+ "score": 90,
+ "team_keys": [
+ "frc2791",
+ "frc5236",
+ "frc3624"
+ ],
+ "surrogate_team_keys": [],
+ "dq_team_keys": []
+ }
+ },
+ "winning_alliance": "red",
+ "event_key": "2016nytr",
+ "time": 1458417180,
+ "predicted_time": 0,
+ "actual_time": 1458416630,
+ "post_result_time": 0,
+ "score_breakdowns": {
+ "blue": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ },
+ "red": {
+ "taxiRobot1": "",
+ "endgameRobot1": "",
+ "taxiRobot2": "",
+ "endgameRobot2": "",
+ "taxiRobot3": "",
+ "endgameRobot3": "",
+ "autoCargoLowerNear": 0,
+ "autoCargoLowerFar": 0,
+ "autoCargoLowerBlue": 0,
+ "autoCargoLowerRed": 0,
+ "autoCargoUpperNear": 0,
+ "autoCargoUpperFar": 0,
+ "autoCargoUpperBlue": 0,
+ "autoCargoUpperRed": 0,
+ "autoCargoTotal": 0,
+ "teleopCargoLowerNear": 0,
+ "teleopCargoLowerFar": 0,
+ "teleopCargoLowerBlue": 0,
+ "teleopCargoLowerRed": 0,
+ "teleopCargoUpperNear": 0,
+ "teleopCargoUpperFar": 0,
+ "teleopCargoUpperBlue": 0,
+ "teleopCargoUpperRed": 0,
+ "teleopCargoTotal": 0,
+ "matchCargoTotal": 0,
+ "autoTaxiPoints": 0,
+ "autoCargoPoints": 0,
+ "autoPoints": 0,
+ "quintetAchieved": false,
+ "teleopCargoPoints": 0,
+ "endgamePoints": 0,
+ "teleopPoints": 0,
+ "cargoBonusRankingPoint": false,
+ "hangarBonusRankingPoint": false,
+ "foulCount": false,
+ "techFoulCount": 0,
+ "adjustPoints": 0,
+ "foulPoints": 0,
+ "rp": 0,
+ "totalPoints": 0
+ }
+ }
+ }
+]
diff --git a/scouting/scraping/test_data/2020_fake.json b/scouting/scraping/test_data/2020_fake.json
new file mode 100644
index 0000000..6aa01fa
--- /dev/null
+++ b/scouting/scraping/test_data/2020_fake.json
@@ -0,0 +1,22 @@
+[
+ {
+ "match_number": 1,
+ "comp_level": "qm",
+ "alliances": {
+ "red": {
+ "team_keys": [
+ "frc100",
+ "frc101",
+ "frc102"
+ ]
+ },
+ "blue": {
+ "team_keys": [
+ "frc103",
+ "frc104",
+ "frc105"
+ ]
+ }
+ }
+ }
+]
diff --git a/scouting/testing/BUILD b/scouting/testing/BUILD
new file mode 100644
index 0000000..43bbe06
--- /dev/null
+++ b/scouting/testing/BUILD
@@ -0,0 +1,12 @@
+py_binary(
+ name = "scouting_test_servers",
+ testonly = True,
+ srcs = [
+ "scouting_test_servers.py",
+ ],
+ data = [
+ "//scouting",
+ "//scouting/scraping:test_data",
+ ],
+ visibility = ["//visibility:public"],
+)
diff --git a/scouting/testing/scouting_test_servers.py b/scouting/testing/scouting_test_servers.py
new file mode 100644
index 0000000..3447815
--- /dev/null
+++ b/scouting/testing/scouting_test_servers.py
@@ -0,0 +1,108 @@
+"""This library is here to run the various servers involved in the scouting app.
+
+The servers are:
+ - The fake TBA server
+ - The actual web server
+"""
+
+import argparse
+import json
+import os
+from pathlib import Path
+import shutil
+import signal
+import socket
+import subprocess
+import sys
+import time
+from typing import List
+
+def wait_for_server(port: int):
+ """Waits for the server at the specified port to respond to TCP connections."""
+ while True:
+ try:
+ connection = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
+ connection.connect(("localhost", port))
+ connection.close()
+ break
+ except ConnectionRefusedError:
+ connection.close()
+ time.sleep(0.01)
+
+def create_tba_config(tmpdir: Path) -> Path:
+ # Configure the scouting webserver to scrape data from our fake TBA
+ # server.
+ config = tmpdir / "scouting_config.json"
+ config.write_text(json.dumps({
+ "api_key": "dummy_key_that_is_not_actually_used_in_this_test",
+ "base_url": "http://localhost:7000",
+ }))
+ return config
+
+def set_up_tba_api_dir(tmpdir: Path, year: int, event_code: str):
+ tba_api_dir = tmpdir / "api" / "v3" / "event" / f"{year}{event_code}"
+ tba_api_dir.mkdir(parents=True, exist_ok=True)
+ (tba_api_dir / "matches").write_text(
+ Path(f"scouting/scraping/test_data/{year}_{event_code}.json").read_text()
+ )
+
+class Runner:
+ """Helps manage the services we need for testing the scouting app."""
+
+ def start(self, port: int):
+ """Starts the services needed for testing the scouting app."""
+ self.tmpdir = Path(os.environ["TEST_TMPDIR"]) / "servers"
+ self.tmpdir.mkdir(exist_ok=True)
+
+ db_path = self.tmpdir / "scouting.db"
+ tba_config = create_tba_config(self.tmpdir)
+
+ self.webserver = subprocess.Popen([
+ "scouting/scouting",
+ f"--port={port}",
+ f"--database={db_path}",
+ f"--tba_config={tba_config}",
+ ])
+
+ # Create a fake TBA server to serve the static match list.
+ set_up_tba_api_dir(self.tmpdir, year=2016, event_code="nytr")
+ set_up_tba_api_dir(self.tmpdir, year=2020, event_code="fake")
+ self.fake_tba_api = subprocess.Popen(
+ ["python3", "-m", "http.server", "7000"],
+ cwd=self.tmpdir,
+ )
+
+ # Wait for the TBA server and the scouting webserver to start up.
+ wait_for_server(7000)
+ wait_for_server(port)
+
+ def stop(self):
+ """Stops the services needed for testing the scouting app."""
+ servers = (self.webserver, self.fake_tba_api)
+ for server in servers:
+ server.terminate()
+ for server in servers:
+ server.wait()
+
+ try:
+ shutil.rmtree(self.tmpdir)
+ except FileNotFoundError:
+ pass
+
+
+def main(argv: List[str]):
+ parser = argparse.ArgumentParser()
+ parser.add_argument("--port", type=int, help="The port for the actual web server.")
+ args = parser.parse_args(argv[1:])
+
+ runner = Runner()
+ runner.start(args.port)
+
+ # Wait until we're asked to shut down via CTRL-C or SIGTERM.
+ signal.pause()
+
+ runner.stop()
+
+
+if __name__ == "__main__":
+ sys.exit(main(sys.argv))
diff --git a/scouting/webserver/BUILD b/scouting/webserver/BUILD
index 66db8e8..745852a 100644
--- a/scouting/webserver/BUILD
+++ b/scouting/webserver/BUILD
@@ -8,6 +8,7 @@
visibility = ["//visibility:private"],
deps = [
"//scouting/db",
+ "//scouting/scraping",
"//scouting/webserver/requests",
"//scouting/webserver/server",
"//scouting/webserver/static",
diff --git a/scouting/webserver/main.go b/scouting/webserver/main.go
index 3c699fd..282e248 100644
--- a/scouting/webserver/main.go
+++ b/scouting/webserver/main.go
@@ -1,6 +1,7 @@
package main
import (
+ "errors"
"flag"
"fmt"
"io/ioutil"
@@ -11,6 +12,7 @@
"syscall"
"github.com/frc971/971-Robot-Code/scouting/db"
+ "github.com/frc971/971-Robot-Code/scouting/scraping"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests"
"github.com/frc971/971-Robot-Code/scouting/webserver/server"
"github.com/frc971/971-Robot-Code/scouting/webserver/static"
@@ -40,6 +42,10 @@
portPtr := flag.Int("port", 8080, "The port number to bind to.")
dirPtr := flag.String("directory", ".", "The directory to serve at /.")
dbPathPtr := flag.String("database", getDefaultDatabasePath(), "The path to the database.")
+ blueAllianceConfigPtr := flag.String("tba_config", "",
+ "The path to your The Blue Alliance JSON config. "+
+ "It needs an \"api_key\" field with your TBA API key. "+
+ "Optionally, it can have a \"base_url\" field with the TBA API base URL.")
flag.Parse()
database, err := db.NewDatabase(*dbPathPtr)
@@ -47,9 +53,16 @@
log.Fatal("Failed to connect to database: ", err)
}
+ scrapeMatchList := func(year int32, eventCode string) ([]scraping.Match, error) {
+ if *blueAllianceConfigPtr == "" {
+ return nil, errors.New("Cannot scrape TBA's match list without a config file.")
+ }
+ return scraping.AllMatches(year, eventCode, *blueAllianceConfigPtr)
+ }
+
scoutingServer := server.NewScoutingServer()
static.ServePages(scoutingServer, *dirPtr)
- requests.HandleRequests(database, scoutingServer)
+ requests.HandleRequests(database, scrapeMatchList, scoutingServer)
scoutingServer.Start(*portPtr)
fmt.Println("Serving", *dirPtr, "on port", *portPtr)
diff --git a/scouting/webserver/requests/BUILD b/scouting/webserver/requests/BUILD
index 196c522..df487f2 100644
--- a/scouting/webserver/requests/BUILD
+++ b/scouting/webserver/requests/BUILD
@@ -8,7 +8,10 @@
visibility = ["//visibility:public"],
deps = [
"//scouting/db",
+ "//scouting/scraping",
"//scouting/webserver/requests/messages:error_response_go_fbs",
+ "//scouting/webserver/requests/messages:refresh_match_list_go_fbs",
+ "//scouting/webserver/requests/messages:refresh_match_list_response_go_fbs",
"//scouting/webserver/requests/messages:request_all_matches_go_fbs",
"//scouting/webserver/requests/messages:request_all_matches_response_go_fbs",
"//scouting/webserver/requests/messages:request_data_scouting_go_fbs",
@@ -29,8 +32,11 @@
target_compatible_with = ["@platforms//cpu:x86_64"],
deps = [
"//scouting/db",
+ "//scouting/scraping",
"//scouting/webserver/requests/debug",
"//scouting/webserver/requests/messages:error_response_go_fbs",
+ "//scouting/webserver/requests/messages:refresh_match_list_go_fbs",
+ "//scouting/webserver/requests/messages:refresh_match_list_response_go_fbs",
"//scouting/webserver/requests/messages:request_all_matches_go_fbs",
"//scouting/webserver/requests/messages:request_all_matches_response_go_fbs",
"//scouting/webserver/requests/messages:request_data_scouting_go_fbs",
diff --git a/scouting/webserver/requests/debug/BUILD b/scouting/webserver/requests/debug/BUILD
index e3028dc..402503f 100644
--- a/scouting/webserver/requests/debug/BUILD
+++ b/scouting/webserver/requests/debug/BUILD
@@ -8,6 +8,7 @@
visibility = ["//visibility:public"],
deps = [
"//scouting/webserver/requests/messages:error_response_go_fbs",
+ "//scouting/webserver/requests/messages:refresh_match_list_response_go_fbs",
"//scouting/webserver/requests/messages:request_all_matches_response_go_fbs",
"//scouting/webserver/requests/messages:request_data_scouting_response_go_fbs",
"//scouting/webserver/requests/messages:request_matches_for_team_response_go_fbs",
diff --git a/scouting/webserver/requests/debug/cli/BUILD b/scouting/webserver/requests/debug/cli/BUILD
index aba9177..371f66e 100644
--- a/scouting/webserver/requests/debug/cli/BUILD
+++ b/scouting/webserver/requests/debug/cli/BUILD
@@ -10,7 +10,10 @@
importpath = "github.com/frc971/971-Robot-Code/scouting/webserver/requests/debug/cli",
target_compatible_with = ["@platforms//cpu:x86_64"],
visibility = ["//visibility:private"],
- deps = ["//scouting/webserver/requests/debug"],
+ deps = [
+ "//scouting/webserver/requests/debug",
+ "@com_github_davecgh_go_spew//spew",
+ ],
)
go_binary(
@@ -27,6 +30,8 @@
],
data = [
":cli",
- "//scouting/webserver",
+ ],
+ deps = [
+ "//scouting/testing:scouting_test_servers",
],
)
diff --git a/scouting/webserver/requests/debug/cli/cli_test.py b/scouting/webserver/requests/debug/cli/cli_test.py
index 347c828..f4b82b4 100644
--- a/scouting/webserver/requests/debug/cli/cli_test.py
+++ b/scouting/webserver/requests/debug/cli/cli_test.py
@@ -2,19 +2,24 @@
import json
import os
+import re
from pathlib import Path
import shutil
import socket
import subprocess
+import sys
+import textwrap
import time
from typing import Any, Dict, List
import unittest
-def write_json(content: Dict[str, Any]):
+import scouting.testing.scouting_test_servers
+
+
+def write_json_request(content: Dict[str, Any]):
"""Writes a JSON file with the specified dict content."""
json_path = Path(os.environ["TEST_TMPDIR"]) / "test.json"
- with open(json_path, "w") as file:
- file.write(json.dumps(content))
+ json_path.write_text(json.dumps(content))
return json_path
def run_debug_cli(args: List[str]):
@@ -30,71 +35,89 @@
run_result.stderr.decode("utf-8"),
)
+
class TestDebugCli(unittest.TestCase):
def setUp(self):
- self.webserver = subprocess.Popen(["scouting/webserver/webserver_/webserver"])
-
- # Wait for the server to respond to requests.
- while True:
- try:
- connection = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
- connection.connect(("localhost", 8080))
- connection.close()
- break
- except ConnectionRefusedError:
- connection.close()
- time.sleep(0.01)
+ self.servers = scouting.testing.scouting_test_servers.Runner()
+ self.servers.start(8080)
def tearDown(self):
- self.webserver.terminate()
- self.webserver.wait()
+ self.servers.stop()
- def test_submit_data_scouting(self):
- json_path = write_json({
- "team": 971,
- "match": 42,
- "missed_shots_auto": 9971,
- "upper_goal_auto": 9971,
- "lower_goal_auto": 9971,
- "missed_shots_tele": 9971,
- "upper_goal_tele": 9971,
- "lower_goal_tele": 9971,
- "defense_rating": 9971,
- "climbing": 9971,
+ def refresh_match_list(self, year=2016, event_code="nytr"):
+ """Triggers the webserver to fetch the match list."""
+ json_path = write_json_request({
+ "year": year,
+ "event_code": event_code,
})
- exit_code, _stdout, stderr = run_debug_cli(["-submitDataScouting", json_path])
+ exit_code, stdout, stderr = run_debug_cli(["-refreshMatchList", json_path])
+ self.assertEqual(exit_code, 0, stderr)
+ self.assertIn("(refresh_match_list_response.RefreshMatchListResponseT)", stdout)
- # The SubmitDataScouting message isn't handled yet.
- self.assertEqual(exit_code, 1)
- self.assertIn("/requests/submit/data_scouting returned 501 Not Implemented", stderr)
+ def test_submit_and_request_data_scouting(self):
+ self.refresh_match_list(year=2020, event_code="fake")
+
+ # First submit some data to be added to the database.
+ json_path = write_json_request({
+ "team": 100,
+ "match": 1,
+ "missed_shots_auto": 10,
+ "upper_goal_auto": 11,
+ "lower_goal_auto": 12,
+ "missed_shots_tele": 13,
+ "upper_goal_tele": 14,
+ "lower_goal_tele": 15,
+ "defense_rating": 3,
+ "climbing": 1,
+ })
+ exit_code, _, stderr = run_debug_cli(["-submitDataScouting", json_path])
+ self.assertEqual(exit_code, 0, stderr)
+
+ # Now request the data back with zero indentation. That let's us
+ # validate the data easily.
+ json_path = write_json_request({})
+ exit_code, stdout, stderr = run_debug_cli(["-requestDataScouting", json_path, "-indent="])
+
+ self.assertEqual(exit_code, 0, stderr)
+ self.assertIn(textwrap.dedent("""\
+ {
+ Team: (int32) 100,
+ Match: (int32) 1,
+ MissedShotsAuto: (int32) 10,
+ UpperGoalAuto: (int32) 11,
+ LowerGoalAuto: (int32) 12,
+ MissedShotsTele: (int32) 13,
+ UpperGoalTele: (int32) 14,
+ LowerGoalTele: (int32) 15,
+ DefenseRating: (int32) 3,
+ Climbing: (int32) 1
+ }"""), stdout)
def test_request_all_matches(self):
- # RequestAllMatches has no fields.
- json_path = write_json({})
- exit_code, _stdout, stderr = run_debug_cli(["-requestAllMatches", json_path])
+ self.refresh_match_list()
- # TODO(phil): Actually add some matches here.
- self.assertEqual(exit_code, 0)
- self.assertIn("{MatchList:[]}", stderr)
+ # RequestAllMatches has no fields.
+ json_path = write_json_request({})
+ exit_code, stdout, stderr = run_debug_cli(["-requestAllMatches", json_path])
+
+ self.assertEqual(exit_code, 0, stderr)
+ self.assertIn("MatchList: ([]*request_all_matches_response.MatchT) (len=90 cap=90) {", stdout)
+ self.assertEqual(stdout.count("MatchNumber:"), 90)
def test_request_matches_for_team(self):
- json_path = write_json({
- "team": 971,
+ self.refresh_match_list()
+
+ json_path = write_json_request({
+ "team": 4856,
})
- exit_code, _stdout, stderr = run_debug_cli(["-requestMatchesForTeam", json_path])
+ exit_code, stdout, stderr = run_debug_cli(["-requestMatchesForTeam", json_path])
- # TODO(phil): Actually add some matches here.
- self.assertEqual(exit_code, 0)
- self.assertIn("{MatchList:[]}", stderr)
-
- def test_request_data_scouting(self):
- json_path = write_json({})
- exit_code, _stdout, stderr = run_debug_cli(["-requestDataScouting", json_path])
-
- # TODO(phil): Actually add data here before querying it.
- self.assertEqual(exit_code, 0)
- self.assertIn("{StatsList:[]}", stderr)
+ # Team 4856 has 12 matches.
+ self.assertEqual(exit_code, 0, stderr)
+ self.assertIn("MatchList: ([]*request_matches_for_team_response.MatchT) (len=12 cap=12) {", stdout)
+ self.assertEqual(stdout.count("MatchNumber:"), 12)
+ self.assertEqual(len(re.findall(r": \(int32\) 4856[,\n]", stdout)), 12)
if __name__ == "__main__":
unittest.main()
diff --git a/scouting/webserver/requests/debug/cli/main.go b/scouting/webserver/requests/debug/cli/main.go
index 0782d82..6f2de1d 100644
--- a/scouting/webserver/requests/debug/cli/main.go
+++ b/scouting/webserver/requests/debug/cli/main.go
@@ -11,6 +11,7 @@
"os/exec"
"path/filepath"
+ "github.com/davecgh/go-spew/spew"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/debug"
)
@@ -66,6 +67,8 @@
func main() {
// Parse command line arguments.
+ indentPtr := flag.String("indent", " ",
+ "The indentation to use for the result dumping. Default is a space.")
addressPtr := flag.String("address", "http://localhost:8080",
"The end point where the server is listening.")
submitDataScoutingPtr := flag.String("submitDataScouting", "",
@@ -76,8 +79,12 @@
"If specified, parse the file as a RequestMatchesForTeam JSON request.")
requestDataScoutingPtr := flag.String("requestDataScouting", "",
"If specified, parse the file as a RequestDataScouting JSON request.")
+ refreshMatchListPtr := flag.String("refreshMatchList", "",
+ "If specified, parse the file as a RefreshMatchList JSON request.")
flag.Parse()
+ spew.Config.Indent = *indentPtr
+
// Handle the actual arguments.
if *submitDataScoutingPtr != "" {
log.Printf("Sending SubmitDataScouting to %s", *addressPtr)
@@ -88,7 +95,7 @@
if err != nil {
log.Fatal("Failed SubmitDataScouting: ", err)
}
- log.Printf("%+v", *response)
+ spew.Dump(*response)
}
if *requestAllMatchesPtr != "" {
log.Printf("Sending RequestAllMatches to %s", *addressPtr)
@@ -99,7 +106,7 @@
if err != nil {
log.Fatal("Failed RequestAllMatches: ", err)
}
- log.Printf("%+v", *response)
+ spew.Dump(*response)
}
if *requestMatchesForTeamPtr != "" {
log.Printf("Sending RequestMatchesForTeam to %s", *addressPtr)
@@ -110,7 +117,7 @@
if err != nil {
log.Fatal("Failed RequestMatchesForTeam: ", err)
}
- log.Printf("%+v", *response)
+ spew.Dump(*response)
}
if *requestDataScoutingPtr != "" {
log.Printf("Sending RequestDataScouting to %s", *addressPtr)
@@ -121,6 +128,17 @@
if err != nil {
log.Fatal("Failed RequestDataScouting: ", err)
}
- log.Printf("%+v", *response)
+ spew.Dump(*response)
+ }
+ if *refreshMatchListPtr != "" {
+ log.Printf("Sending RefreshMatchList to %s", *addressPtr)
+ binaryRequest := parseJson(
+ "scouting/webserver/requests/messages/refresh_match_list.fbs",
+ *refreshMatchListPtr)
+ response, err := debug.RefreshMatchList(*addressPtr, binaryRequest)
+ if err != nil {
+ log.Fatal("Failed RefreshMatchList: ", err)
+ }
+ spew.Dump(*response)
}
}
diff --git a/scouting/webserver/requests/debug/debug.go b/scouting/webserver/requests/debug/debug.go
index 6515e81..81be3d1 100644
--- a/scouting/webserver/requests/debug/debug.go
+++ b/scouting/webserver/requests/debug/debug.go
@@ -9,6 +9,7 @@
"net/http"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/error_response"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/refresh_match_list_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_all_matches_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_data_scouting_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_matches_for_team_response"
@@ -20,6 +21,7 @@
type RequestAllMatchesResponseT = request_all_matches_response.RequestAllMatchesResponseT
type RequestMatchesForTeamResponseT = request_matches_for_team_response.RequestMatchesForTeamResponseT
type RequestDataScoutingResponseT = request_data_scouting_response.RequestDataScoutingResponseT
+type RefreshMatchListResponseT = refresh_match_list_response.RefreshMatchListResponseT
// A struct that can be used as an `error`. It contains information about the
// why the server was unhappy and what the corresponding request was.
@@ -127,3 +129,15 @@
response := request_data_scouting_response.GetRootAsRequestDataScoutingResponse(responseBytes, 0)
return response.UnPack(), nil
}
+
+// Sends a `RefreshMatchList` message to the server and returns the
+// deserialized response.
+func RefreshMatchList(server string, requestBytes []byte) (*RefreshMatchListResponseT, error) {
+ responseBytes, err := performPost(server+"/requests/refresh_match_list", requestBytes)
+ if err != nil {
+ return nil, err
+ }
+ log.Printf("Parsing RefreshMatchListResponse")
+ response := refresh_match_list_response.GetRootAsRefreshMatchListResponse(responseBytes, 0)
+ return response.UnPack(), nil
+}
diff --git a/scouting/webserver/requests/messages/BUILD b/scouting/webserver/requests/messages/BUILD
index 53ceab2..c27f730 100644
--- a/scouting/webserver/requests/messages/BUILD
+++ b/scouting/webserver/requests/messages/BUILD
@@ -10,6 +10,8 @@
"request_matches_for_team_response",
"request_data_scouting",
"request_data_scouting_response",
+ "refresh_match_list",
+ "refresh_match_list_response",
)
filegroup(
diff --git a/scouting/webserver/requests/messages/refresh_match_list.fbs b/scouting/webserver/requests/messages/refresh_match_list.fbs
new file mode 100644
index 0000000..c4384c7
--- /dev/null
+++ b/scouting/webserver/requests/messages/refresh_match_list.fbs
@@ -0,0 +1,8 @@
+namespace scouting.webserver.requests;
+
+table RefreshMatchList {
+ year: int (id: 0);
+ event_code: string (id: 1);
+}
+
+root_type RefreshMatchList;
diff --git a/scouting/webserver/requests/messages/refresh_match_list_response.fbs b/scouting/webserver/requests/messages/refresh_match_list_response.fbs
new file mode 100644
index 0000000..ba80272
--- /dev/null
+++ b/scouting/webserver/requests/messages/refresh_match_list_response.fbs
@@ -0,0 +1,6 @@
+namespace scouting.webserver.requests;
+
+table RefreshMatchListResponse {
+}
+
+root_type RefreshMatchListResponse;
diff --git a/scouting/webserver/requests/messages/submit_data_scouting.fbs b/scouting/webserver/requests/messages/submit_data_scouting.fbs
index 6213dd5..755e70b 100644
--- a/scouting/webserver/requests/messages/submit_data_scouting.fbs
+++ b/scouting/webserver/requests/messages/submit_data_scouting.fbs
@@ -9,7 +9,17 @@
missed_shots_tele:int (id: 5);
upper_goal_tele:int (id:6);
lower_goal_tele:int (id:7);
+ // The rating that is used to rate the defense that this robot played on
+ // other robots.
+ // TODO: Document what the different values mean. E.g. 0 means no defense
+ // played?
defense_rating:int (id:8);
+ // The amount of defense that other robots played on this robot.
+ // TODO: Document what the different values mean. E.g. 0 means no defense
+ // played against this robot?
+ defense_received_rating:int (id:10);
+ // The rating that this robot gets for its climbing.
+ // TODO: Change into an enum to make the different values self-documenting.
climbing:int (id:9);
}
diff --git a/scouting/webserver/requests/requests.go b/scouting/webserver/requests/requests.go
index 3c21402..6c4bdd1 100644
--- a/scouting/webserver/requests/requests.go
+++ b/scouting/webserver/requests/requests.go
@@ -1,12 +1,18 @@
package requests
import (
+ "errors"
"fmt"
"io"
"net/http"
+ "strconv"
+ "strings"
"github.com/frc971/971-Robot-Code/scouting/db"
+ "github.com/frc971/971-Robot-Code/scouting/scraping"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/error_response"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/refresh_match_list"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/refresh_match_list_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_all_matches"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_all_matches_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_data_scouting"
@@ -14,18 +20,21 @@
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_matches_for_team"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_matches_for_team_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_data_scouting"
- _ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_data_scouting_response"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_data_scouting_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/server"
flatbuffers "github.com/google/flatbuffers/go"
)
type SubmitDataScouting = submit_data_scouting.SubmitDataScouting
+type SubmitDataScoutingResponseT = submit_data_scouting_response.SubmitDataScoutingResponseT
type RequestAllMatches = request_all_matches.RequestAllMatches
type RequestAllMatchesResponseT = request_all_matches_response.RequestAllMatchesResponseT
type RequestMatchesForTeam = request_matches_for_team.RequestMatchesForTeam
type RequestMatchesForTeamResponseT = request_matches_for_team_response.RequestMatchesForTeamResponseT
type RequestDataScouting = request_data_scouting.RequestDataScouting
type RequestDataScoutingResponseT = request_data_scouting_response.RequestDataScoutingResponseT
+type RefreshMatchList = refresh_match_list.RefreshMatchList
+type RefreshMatchListResponseT = refresh_match_list_response.RefreshMatchListResponseT
// The interface we expect the database abstraction to conform to.
// We use an interface here because it makes unit testing easier.
@@ -38,6 +47,8 @@
QueryStats(int) ([]db.Stats, error)
}
+type ScrapeMatchList func(int32, string) ([]scraping.Match, error)
+
// Handles unknown requests. Just returns a 404.
func unknown(w http.ResponseWriter, req *http.Request) {
w.WriteHeader(http.StatusNotFound)
@@ -81,16 +92,32 @@
return
}
- _, success := parseSubmitDataScouting(w, requestBytes)
+ request, success := parseSubmitDataScouting(w, requestBytes)
if !success {
return
}
- // TODO(phil): Actually handle the request.
- // We have access to the database via "handler.db" here. For example:
- // stats := handler.db.ReturnStats()
+ stats := db.Stats{
+ TeamNumber: request.Team(),
+ MatchNumber: request.Match(),
+ ShotsMissedAuto: request.MissedShotsAuto(),
+ UpperGoalAuto: request.UpperGoalAuto(),
+ LowerGoalAuto: request.LowerGoalAuto(),
+ ShotsMissed: request.MissedShotsTele(),
+ UpperGoalShots: request.UpperGoalTele(),
+ LowerGoalShots: request.LowerGoalTele(),
+ PlayedDefense: request.DefenseRating(),
+ Climbing: request.Climbing(),
+ }
- respondNotImplemented(w)
+ err = handler.db.AddToStats(stats)
+ if err != nil {
+ respondWithError(w, http.StatusInternalServerError, fmt.Sprint("Failed to submit datascouting data: ", err))
+ }
+
+ builder := flatbuffers.NewBuilder(50 * 1024)
+ builder.Finish((&SubmitDataScoutingResponseT{}).Pack(builder))
+ w.Write(builder.FinishedBytes())
}
// TODO(phil): Can we turn this into a generic?
@@ -126,6 +153,7 @@
matches, err := handler.db.ReturnMatches()
if err != nil {
respondWithError(w, http.StatusInternalServerError, fmt.Sprint("Faled to query database: ", err))
+ return
}
var response RequestAllMatchesResponseT
@@ -181,6 +209,7 @@
matches, err := handler.db.QueryMatches(request.Team())
if err != nil {
respondWithError(w, http.StatusInternalServerError, fmt.Sprint("Faled to query database: ", err))
+ return
}
var response RequestAllMatchesResponseT
@@ -236,6 +265,7 @@
stats, err := handler.db.ReturnStats()
if err != nil {
respondWithError(w, http.StatusInternalServerError, fmt.Sprint("Faled to query database: ", err))
+ return
}
var response RequestDataScoutingResponseT
@@ -259,10 +289,114 @@
w.Write(builder.FinishedBytes())
}
-func HandleRequests(db Database, scoutingServer server.ScoutingServer) {
+// TODO(phil): Can we turn this into a generic?
+func parseRefreshMatchList(w http.ResponseWriter, buf []byte) (*RefreshMatchList, bool) {
+ success := true
+ defer func() {
+ if r := recover(); r != nil {
+ respondWithError(w, http.StatusBadRequest, fmt.Sprintf("Failed to parse RefreshMatchList: %v", r))
+ success = false
+ }
+ }()
+ result := refresh_match_list.GetRootAsRefreshMatchList(buf, 0)
+ return result, success
+}
+
+func parseTeamKey(teamKey string) (int, error) {
+ // TBA prefixes teams with "frc". Not sure why. Get rid of that.
+ teamKey = strings.TrimPrefix(teamKey, "frc")
+ return strconv.Atoi(teamKey)
+}
+
+// Parses the alliance data from the specified match and returns the three red
+// teams and the three blue teams.
+func parseTeamKeys(match *scraping.Match) ([3]int32, [3]int32, error) {
+ redKeys := match.Alliances.Red.TeamKeys
+ blueKeys := match.Alliances.Blue.TeamKeys
+
+ if len(redKeys) != 3 || len(blueKeys) != 3 {
+ return [3]int32{}, [3]int32{}, errors.New(fmt.Sprintf(
+ "Found %d red teams and %d blue teams.", len(redKeys), len(blueKeys)))
+ }
+
+ var red [3]int32
+ for i, key := range redKeys {
+ team, err := parseTeamKey(key)
+ if err != nil {
+ return [3]int32{}, [3]int32{}, errors.New(fmt.Sprintf(
+ "Failed to parse red %d team '%s' as integer: %v", i+1, key, err))
+ }
+ red[i] = int32(team)
+ }
+ var blue [3]int32
+ for i, key := range blueKeys {
+ team, err := parseTeamKey(key)
+ if err != nil {
+ return [3]int32{}, [3]int32{}, errors.New(fmt.Sprintf(
+ "Failed to parse blue %d team '%s' as integer: %v", i+1, key, err))
+ }
+ blue[i] = int32(team)
+ }
+ return red, blue, nil
+}
+
+type refreshMatchListHandler struct {
+ db Database
+ scrape ScrapeMatchList
+}
+
+func (handler refreshMatchListHandler) ServeHTTP(w http.ResponseWriter, req *http.Request) {
+ requestBytes, err := io.ReadAll(req.Body)
+ if err != nil {
+ respondWithError(w, http.StatusBadRequest, fmt.Sprint("Failed to read request bytes:", err))
+ return
+ }
+
+ request, success := parseRefreshMatchList(w, requestBytes)
+ if !success {
+ return
+ }
+
+ matches, err := handler.scrape(request.Year(), string(request.EventCode()))
+ if err != nil {
+ respondWithError(w, http.StatusInternalServerError, fmt.Sprint("Faled to scrape match list: ", err))
+ return
+ }
+
+ for _, match := range matches {
+ // Make sure the data is valid.
+ red, blue, err := parseTeamKeys(&match)
+ if err != nil {
+ respondWithError(w, http.StatusInternalServerError, fmt.Sprintf(
+ "TheBlueAlliance data for match %d is malformed: %v", match.MatchNumber, err))
+ return
+ }
+ // Add the match to the database.
+ handler.db.AddToMatch(db.Match{
+ MatchNumber: int32(match.MatchNumber),
+ // TODO(phil): What does Round mean?
+ Round: 1,
+ CompLevel: match.CompLevel,
+ R1: red[0],
+ R2: red[1],
+ R3: red[2],
+ B1: blue[0],
+ B2: blue[1],
+ B3: blue[2],
+ })
+ }
+
+ var response RefreshMatchListResponseT
+ builder := flatbuffers.NewBuilder(1024)
+ builder.Finish((&response).Pack(builder))
+ w.Write(builder.FinishedBytes())
+}
+
+func HandleRequests(db Database, scrape ScrapeMatchList, scoutingServer server.ScoutingServer) {
scoutingServer.HandleFunc("/requests", unknown)
scoutingServer.Handle("/requests/submit/data_scouting", submitDataScoutingHandler{db})
scoutingServer.Handle("/requests/request/all_matches", requestAllMatchesHandler{db})
scoutingServer.Handle("/requests/request/matches_for_team", requestMatchesForTeamHandler{db})
scoutingServer.Handle("/requests/request/data_scouting", requestDataScoutingHandler{db})
+ scoutingServer.Handle("/requests/refresh_match_list", refreshMatchListHandler{db, scrape})
}
diff --git a/scouting/webserver/requests/requests_test.go b/scouting/webserver/requests/requests_test.go
index e3650ff..60bee0e 100644
--- a/scouting/webserver/requests/requests_test.go
+++ b/scouting/webserver/requests/requests_test.go
@@ -8,8 +8,11 @@
"testing"
"github.com/frc971/971-Robot-Code/scouting/db"
+ "github.com/frc971/971-Robot-Code/scouting/scraping"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/debug"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/error_response"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/refresh_match_list"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/refresh_match_list_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_all_matches"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_all_matches_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_data_scouting"
@@ -17,7 +20,7 @@
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_matches_for_team"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_matches_for_team_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_data_scouting"
- _ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_data_scouting_response"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_data_scouting_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/server"
flatbuffers "github.com/google/flatbuffers/go"
)
@@ -26,7 +29,7 @@
func Test404(t *testing.T) {
db := MockDatabase{}
scoutingServer := server.NewScoutingServer()
- HandleRequests(&db, scoutingServer)
+ HandleRequests(&db, scrapeEmtpyMatchList, scoutingServer)
scoutingServer.Start(8080)
defer scoutingServer.Stop()
@@ -43,7 +46,7 @@
func TestSubmitDataScoutingError(t *testing.T) {
db := MockDatabase{}
scoutingServer := server.NewScoutingServer()
- HandleRequests(&db, scoutingServer)
+ HandleRequests(&db, scrapeEmtpyMatchList, scoutingServer)
scoutingServer.Start(8080)
defer scoutingServer.Stop()
@@ -71,7 +74,7 @@
func TestSubmitDataScouting(t *testing.T) {
db := MockDatabase{}
scoutingServer := server.NewScoutingServer()
- HandleRequests(&db, scoutingServer)
+ HandleRequests(&db, scrapeEmtpyMatchList, scoutingServer)
scoutingServer.Start(8080)
defer scoutingServer.Stop()
@@ -89,15 +92,16 @@
Climbing: 9971,
}).Pack(builder))
- resp, err := http.Post("http://localhost:8080/requests/submit/data_scouting", "application/octet-stream", bytes.NewReader(builder.FinishedBytes()))
+ response, err := debug.SubmitDataScouting("http://localhost:8080", builder.FinishedBytes())
if err != nil {
- t.Fatalf("Failed to send request: %v", err)
+ t.Fatal("Failed to submit data scouting: ", err)
}
- if resp.StatusCode != http.StatusNotImplemented {
- t.Fatal("Unexpected status code. Got", resp.Status)
+
+ // We get an empty response back. Validate that.
+ expected := submit_data_scouting_response.SubmitDataScoutingResponseT{}
+ if !reflect.DeepEqual(expected, *response) {
+ t.Fatal("Expected ", expected, ", but got:", *response)
}
- // TODO(phil): We have nothing to validate yet. Fix that.
- // TODO(phil): Can we use scouting/webserver/requests/debug here?
}
// Validates that we can request the full match list.
@@ -119,7 +123,7 @@
},
}
scoutingServer := server.NewScoutingServer()
- HandleRequests(&db, scoutingServer)
+ HandleRequests(&db, scrapeEmtpyMatchList, scoutingServer)
scoutingServer.Start(8080)
defer scoutingServer.Stop()
@@ -157,6 +161,7 @@
t.Fatal("Expected for match", i, ":", *match, ", but got:", *response.MatchList[i])
}
}
+
}
// Validates that we can request the full match list.
@@ -174,7 +179,7 @@
},
}
scoutingServer := server.NewScoutingServer()
- HandleRequests(&db, scoutingServer)
+ HandleRequests(&db, scrapeEmtpyMatchList, scoutingServer)
scoutingServer.Start(8080)
defer scoutingServer.Stop()
@@ -227,7 +232,7 @@
},
}
scoutingServer := server.NewScoutingServer()
- HandleRequests(&db, scoutingServer)
+ HandleRequests(&db, scrapeEmtpyMatchList, scoutingServer)
scoutingServer.Start(8080)
defer scoutingServer.Stop()
@@ -269,6 +274,79 @@
}
}
+// Validates that we can download the schedule from The Blue Alliance.
+func TestRefreshMatchList(t *testing.T) {
+ scrapeMockSchedule := func(int32, string) ([]scraping.Match, error) {
+ return []scraping.Match{
+ {
+ CompLevel: "qual",
+ MatchNumber: 1,
+ Alliances: scraping.Alliances{
+ Red: scraping.Alliance{
+ TeamKeys: []string{
+ "100",
+ "200",
+ "300",
+ },
+ },
+ Blue: scraping.Alliance{
+ TeamKeys: []string{
+ "101",
+ "201",
+ "301",
+ },
+ },
+ },
+ WinningAlliance: "",
+ EventKey: "",
+ Time: 0,
+ PredictedTime: 0,
+ ActualTime: 0,
+ PostResultTime: 0,
+ ScoreBreakdowns: scraping.ScoreBreakdowns{},
+ },
+ }, nil
+ }
+
+ database := MockDatabase{}
+ scoutingServer := server.NewScoutingServer()
+ HandleRequests(&database, scrapeMockSchedule, scoutingServer)
+ scoutingServer.Start(8080)
+ defer scoutingServer.Stop()
+
+ builder := flatbuffers.NewBuilder(1024)
+ builder.Finish((&refresh_match_list.RefreshMatchListT{}).Pack(builder))
+
+ response, err := debug.RefreshMatchList("http://localhost:8080", builder.FinishedBytes())
+ if err != nil {
+ t.Fatal("Failed to request all matches: ", err)
+ }
+
+ // Validate the response.
+ expected := refresh_match_list_response.RefreshMatchListResponseT{}
+ if !reflect.DeepEqual(expected, *response) {
+ t.Fatal("Expected ", expected, ", but got ", *response)
+ }
+
+ // Make sure that the data made it into the database.
+ expectedMatches := []db.Match{
+ {
+ MatchNumber: 1,
+ Round: 1,
+ CompLevel: "qual",
+ R1: 100,
+ R2: 200,
+ R3: 300,
+ B1: 101,
+ B2: 201,
+ B3: 301,
+ },
+ }
+ if !reflect.DeepEqual(expectedMatches, database.matches) {
+ t.Fatal("Expected ", expectedMatches, ", but got ", database.matches)
+ }
+}
+
// A mocked database we can use for testing. Add functionality to this as
// needed for your tests.
@@ -277,11 +355,13 @@
stats []db.Stats
}
-func (database *MockDatabase) AddToMatch(db.Match) error {
+func (database *MockDatabase) AddToMatch(match db.Match) error {
+ database.matches = append(database.matches, match)
return nil
}
-func (database *MockDatabase) AddToStats(db.Stats) error {
+func (database *MockDatabase) AddToStats(stats db.Stats) error {
+ database.stats = append(database.stats, stats)
return nil
}
@@ -309,3 +389,8 @@
func (database *MockDatabase) QueryStats(int) ([]db.Stats, error) {
return []db.Stats{}, nil
}
+
+// Returns an empty match list from the fake The Blue Alliance scraping.
+func scrapeEmtpyMatchList(int32, string) ([]scraping.Match, error) {
+ return nil, nil
+}
diff --git a/scouting/www/BUILD b/scouting/www/BUILD
index aa2ad7b..8a32f89 100644
--- a/scouting/www/BUILD
+++ b/scouting/www/BUILD
@@ -14,12 +14,15 @@
]),
angular_assets = glob([
"*.ng.html",
+ "*.css",
]),
compiler = "//tools:tsc_wrapped_with_angular",
target_compatible_with = ["@platforms//cpu:x86_64"],
use_angular_plugin = True,
visibility = ["//visibility:public"],
deps = [
+ "//scouting/www/entry",
+ "//scouting/www/import_match_list",
"@npm//@angular/animations",
"@npm//@angular/common",
"@npm//@angular/core",
@@ -76,3 +79,9 @@
],
deps = [":main_bundle_compiled"],
)
+
+filegroup(
+ name = "common_css",
+ srcs = ["common.css"],
+ visibility = ["//scouting/www:__subpackages__"],
+)
diff --git a/scouting/www/app.ng.html b/scouting/www/app.ng.html
index fb9ba26..2fafceb 100644
--- a/scouting/www/app.ng.html
+++ b/scouting/www/app.ng.html
@@ -1,3 +1,13 @@
-<h1>
- This is an app.
-</h1>
+<ul class="nav nav-tabs">
+ <li class="nav-item">
+ <a class="nav-link" [class.active]="tabIs('Entry')" (click)="switchTabTo('Entry')">Data Entry</a>
+ </li>
+ <li class="nav-item">
+ <a class="nav-link" [class.active]="tabIs('ImportMatchList')" (click)="switchTabTo('ImportMatchList')">Import Match List</a>
+ </li>
+</ul>
+
+<ng-container [ngSwitch]="tab">
+ <app-entry *ngSwitchCase="'Entry'"></app-entry>
+ <app-import-match-list *ngSwitchCase="'ImportMatchList'"></app-import-match-list>
+</ng-container>
diff --git a/scouting/www/app.ts b/scouting/www/app.ts
index f6247d3..79c1094 100644
--- a/scouting/www/app.ts
+++ b/scouting/www/app.ts
@@ -1,8 +1,35 @@
import {Component} from '@angular/core';
+type Tab = 'Entry'|'ImportMatchList';
+
@Component({
selector: 'my-app',
templateUrl: './app.ng.html',
+ styleUrls: ['./common.css']
})
export class App {
+ tab: Tab = 'Entry';
+
+ constructor() {
+ window.addEventListener('beforeunload', (e) => {
+ // Based on https://developer.mozilla.org/en-US/docs/Web/API/WindowEventHandlers/onbeforeunload#example
+ // This combination ensures a dialog will be shown on most browsers.
+ e.preventDefault();
+ e.returnValue = '';
+ });
+ }
+
+ tabIs(tab: Tab) {
+ return this.tab == tab;
+ }
+
+ switchTabTo(tab: Tab) {
+ let shouldSwitch = true;
+ if (tab === 'ImportMatchList') {
+ shouldSwitch = window.confirm('Leave data scouting page?');
+ }
+ if (shouldSwitch) {
+ this.tab = tab;
+ }
+ }
}
diff --git a/scouting/www/app_module.ts b/scouting/www/app_module.ts
index 3e34a17..2a514f2 100644
--- a/scouting/www/app_module.ts
+++ b/scouting/www/app_module.ts
@@ -1,6 +1,8 @@
import {NgModule} from '@angular/core';
import {BrowserModule} from '@angular/platform-browser';
import {BrowserAnimationsModule} from '@angular/platform-browser/animations';
+import {EntryModule} from './entry/entry.module';
+import {ImportMatchListModule} from './import_match_list/import_match_list.module';
import {App} from './app';
@@ -9,6 +11,8 @@
imports: [
BrowserModule,
BrowserAnimationsModule,
+ EntryModule,
+ ImportMatchListModule,
],
exports: [App],
bootstrap: [App],
diff --git a/scouting/www/common.css b/scouting/www/common.css
new file mode 100644
index 0000000..35e943f
--- /dev/null
+++ b/scouting/www/common.css
@@ -0,0 +1,10 @@
+/* This CSS is shared between all scouting app tabs. */
+
+.error_message {
+ color: red;
+}
+.error_message:empty, .progress_message:empty {
+ /* TODO(phil): Figure out a way to make these take up no horizontal space.
+ * I.e. It would be nice to keep the error message and the progress message
+ * aligned when they are non-empty. */
+}
diff --git a/scouting/www/counter_button/BUILD b/scouting/www/counter_button/BUILD
new file mode 100644
index 0000000..1dbcdfc
--- /dev/null
+++ b/scouting/www/counter_button/BUILD
@@ -0,0 +1,21 @@
+load("@npm//@bazel/typescript:index.bzl", "ts_library")
+
+ts_library(
+ name = "counter_button",
+ srcs = [
+ "counter_button.component.ts",
+ "counter_button.module.ts",
+ ],
+ angular_assets = [
+ "counter_button.component.css",
+ "counter_button.ng.html",
+ ],
+ compiler = "//tools:tsc_wrapped_with_angular",
+ target_compatible_with = ["@platforms//cpu:x86_64"],
+ use_angular_plugin = True,
+ visibility = ["//visibility:public"],
+ deps = [
+ "@npm//@angular/common",
+ "@npm//@angular/core",
+ ],
+)
diff --git a/scouting/www/counter_button/counter_button.component.css b/scouting/www/counter_button/counter_button.component.css
new file mode 100644
index 0000000..39faea8
--- /dev/null
+++ b/scouting/www/counter_button/counter_button.component.css
@@ -0,0 +1,11 @@
+:host {
+ display: flex;
+ align-items: stretch;
+ flex-direction: column;
+ text-align: center;
+}
+
+* {
+ padding: 10px;
+}
+
diff --git a/scouting/www/counter_button/counter_button.component.ts b/scouting/www/counter_button/counter_button.component.ts
new file mode 100644
index 0000000..fa84dc6
--- /dev/null
+++ b/scouting/www/counter_button/counter_button.component.ts
@@ -0,0 +1,17 @@
+import {Component, Input, Output, EventEmitter} from '@angular/core';
+
+@Component({
+ selector: 'frc971-counter-button',
+ templateUrl: './counter_button.ng.html',
+ styleUrls: ['./counter_button.component.css'],
+})
+export class CounterButton {
+ @Input() value: number = 0;
+ @Output() valueChange = new EventEmitter<number>();
+
+ update(delta: number) {
+ this.value = Math.max(this.value + delta, 0);
+
+ this.valueChange.emit(this.value);
+ }
+}
diff --git a/scouting/www/counter_button/counter_button.module.ts b/scouting/www/counter_button/counter_button.module.ts
new file mode 100644
index 0000000..25bafcb
--- /dev/null
+++ b/scouting/www/counter_button/counter_button.module.ts
@@ -0,0 +1,10 @@
+import {NgModule} from '@angular/core';
+
+import {CounterButton} from './counter_button.component';
+
+@NgModule({
+ declarations: [CounterButton],
+ exports: [CounterButton],
+})
+export class CounterButtonModule {
+}
diff --git a/scouting/www/counter_button/counter_button.ng.html b/scouting/www/counter_button/counter_button.ng.html
new file mode 100644
index 0000000..4abf415
--- /dev/null
+++ b/scouting/www/counter_button/counter_button.ng.html
@@ -0,0 +1,4 @@
+<h4><ng-content></ng-content></h4>
+<button (click)="update(1)" class="btn btn-secondary btn-block">+</button>
+<h3>{{value}}</h3>
+<button (click)="update(-1)" class="btn btn-secondary btn-block">-</button>
diff --git a/scouting/www/entry/BUILD b/scouting/www/entry/BUILD
new file mode 100644
index 0000000..17eed23
--- /dev/null
+++ b/scouting/www/entry/BUILD
@@ -0,0 +1,28 @@
+load("@npm//@bazel/typescript:index.bzl", "ts_library")
+
+ts_library(
+ name = "entry",
+ srcs = [
+ "entry.component.ts",
+ "entry.module.ts",
+ ],
+ angular_assets = [
+ "entry.component.css",
+ "entry.ng.html",
+ "//scouting/www:common_css",
+ ],
+ compiler = "//tools:tsc_wrapped_with_angular",
+ target_compatible_with = ["@platforms//cpu:x86_64"],
+ use_angular_plugin = True,
+ visibility = ["//visibility:public"],
+ deps = [
+ "//scouting/webserver/requests/messages:error_response_ts_fbs",
+ "//scouting/webserver/requests/messages:submit_data_scouting_response_ts_fbs",
+ "//scouting/webserver/requests/messages:submit_data_scouting_ts_fbs",
+ "//scouting/www/counter_button",
+ "@com_github_google_flatbuffers//ts:flatbuffers_ts",
+ "@npm//@angular/common",
+ "@npm//@angular/core",
+ "@npm//@angular/forms",
+ ],
+)
diff --git a/scouting/www/entry/entry.component.css b/scouting/www/entry/entry.component.css
new file mode 100644
index 0000000..e6f81b3
--- /dev/null
+++ b/scouting/www/entry/entry.component.css
@@ -0,0 +1,17 @@
+* {
+ padding: 10px;
+}
+
+.buttons {
+ display: flex;
+ justify-content: space-between;
+}
+
+textarea {
+ width: 300px;
+ height: 150px;
+}
+
+button {
+ touch-action: manipulation;
+}
diff --git a/scouting/www/entry/entry.component.ts b/scouting/www/entry/entry.component.ts
new file mode 100644
index 0000000..3db5f72
--- /dev/null
+++ b/scouting/www/entry/entry.component.ts
@@ -0,0 +1,125 @@
+import { Component, OnInit } from '@angular/core';
+
+import * as flatbuffer_builder from 'org_frc971/external/com_github_google_flatbuffers/ts/builder';
+import {ByteBuffer} from 'org_frc971/external/com_github_google_flatbuffers/ts/byte-buffer';
+import * as error_response from 'org_frc971/scouting/webserver/requests/messages/error_response_generated';
+import * as submit_data_scouting_response from 'org_frc971/scouting/webserver/requests/messages/submit_data_scouting_response_generated';
+import * as submit_data_scouting from 'org_frc971/scouting/webserver/requests/messages/submit_data_scouting_generated';
+import SubmitDataScouting = submit_data_scouting.scouting.webserver.requests.SubmitDataScouting;
+import SubmitDataScoutingResponse = submit_data_scouting_response.scouting.webserver.requests.SubmitDataScoutingResponse;
+import ErrorResponse = error_response.scouting.webserver.requests.ErrorResponse;
+
+type Section = 'Team Selection'|'Auto'|'TeleOp'|'Climb'|'Defense'|'Review and Submit'|'Home'
+type Level = 'Failed'|'Low'|'Medium'|'High'|'Transversal'
+
+@Component({
+ selector: 'app-entry',
+ templateUrl: './entry.ng.html',
+ styleUrls: ['../common.css', './entry.component.css']
+})
+export class EntryComponent {
+ section: Section = 'Team Selection';
+ matchNumber: number = 1
+ teamNumber: number = 1
+ autoUpperShotsMade: number = 0;
+ autoLowerShotsMade: number = 0;
+ autoShotsMissed: number = 0;
+ teleUpperShotsMade: number = 0;
+ teleLowerShotsMade: number = 0;
+ teleShotsMissed: number = 0;
+ defensePlayedOnScore: number = 0;
+ defensePlayedScore: number = 0;
+ level: Level;
+ proper: boolean = false;
+ climbed: boolean = false;
+ errorMessage: string = '';
+
+ toggleProper() {
+ this.proper = !this.proper;
+ }
+
+ setFailed() {
+ this.level = 'Failed';
+ }
+
+ setLow() {
+ this.level = 'Low';
+ }
+
+ setMedium() {
+ this.level = 'Medium';
+ }
+
+ setHigh() {
+ this.level = 'High';
+ }
+
+ setTransversal() {
+ this.level = 'Transversal';
+ }
+
+ nextSection() {
+ if (this.section === 'Team Selection') {
+ this.section = 'Auto';
+ } else if (this.section === 'Auto') {
+ this.section = 'TeleOp';
+ } else if (this.section === 'TeleOp') {
+ this.section = 'Climb';
+ } else if (this.section === 'Climb') {
+ this.section = 'Defense';
+ } else if (this.section === 'Defense') {
+ this.section = 'Review and Submit';
+ } else if (this.section === 'Review and Submit') {
+ this.submitDataScouting();
+ }
+ }
+
+ prevSection() {
+ if (this.section === 'Auto') {
+ this.section = 'Team Selection';
+ } else if (this.section === 'TeleOp') {
+ this.section = 'Auto';
+ } else if (this.section === 'Climb') {
+ this.section = 'TeleOp';
+ } else if (this.section === 'Defense') {
+ this.section = 'Climb';
+ } else if (this.section === 'Review and Submit') {
+ this.section = 'Defense';
+ }
+ }
+
+ async submitDataScouting() {
+ const builder = new flatbuffer_builder.Builder() as unknown as flatbuffers.Builder;
+ SubmitDataScouting.startSubmitDataScouting(builder);
+ SubmitDataScouting.addTeam(builder, this.teamNumber);
+ SubmitDataScouting.addMatch(builder, this.matchNumber);
+ SubmitDataScouting.addMissedShotsAuto(builder, this.autoShotsMissed);
+ SubmitDataScouting.addUpperGoalAuto(builder, this.autoUpperShotsMade);
+ SubmitDataScouting.addLowerGoalAuto(builder, this.autoLowerShotsMade);
+ SubmitDataScouting.addMissedShotsTele(builder, this.teleShotsMissed);
+ SubmitDataScouting.addUpperGoalTele(builder, this.teleUpperShotsMade);
+ SubmitDataScouting.addLowerGoalTele(builder, this.teleLowerShotsMade);
+ SubmitDataScouting.addDefenseRating(builder, this.defensePlayedScore);
+ // TODO(phil): Add support for defensePlayedOnScore.
+ // TODO(phil): Fix the Climbing score.
+ SubmitDataScouting.addClimbing(builder, 1);
+ builder.finish(SubmitDataScouting.endSubmitDataScouting(builder));
+
+ const buffer = builder.asUint8Array();
+ const res = await fetch(
+ '/requests/submit/data_scouting', {method: 'POST', body: buffer});
+
+ if (res.ok) {
+ // We successfully submitted the data. Go back to Home.
+ this.section = 'Home';
+ } else {
+ const resBuffer = await res.arrayBuffer();
+ const fbBuffer = new ByteBuffer(new Uint8Array(resBuffer));
+ const parsedResponse = ErrorResponse.getRootAsErrorResponse(
+ fbBuffer as unknown as flatbuffers.ByteBuffer);
+
+ const errorMessage = parsedResponse.errorMessage();
+ this.errorMessage = `Received ${res.status} ${res.statusText}: "${errorMessage}"`;
+ }
+ }
+}
diff --git a/scouting/www/entry/entry.module.ts b/scouting/www/entry/entry.module.ts
new file mode 100644
index 0000000..b4d81c0
--- /dev/null
+++ b/scouting/www/entry/entry.module.ts
@@ -0,0 +1,14 @@
+import {NgModule} from '@angular/core';
+import {CommonModule} from '@angular/common';
+import {FormsModule} from '@angular/forms';
+
+import {CounterButtonModule} from '../counter_button/counter_button.module';
+import {EntryComponent} from './entry.component';
+
+@NgModule({
+ declarations: [EntryComponent],
+ exports: [EntryComponent],
+ imports: [CommonModule, FormsModule, CounterButtonModule],
+})
+export class EntryModule {
+}
diff --git a/scouting/www/entry/entry.ng.html b/scouting/www/entry/entry.ng.html
new file mode 100644
index 0000000..c5cf233
--- /dev/null
+++ b/scouting/www/entry/entry.ng.html
@@ -0,0 +1,198 @@
+<div class="header">
+ <h2>{{section}}</h2>
+</div>
+
+<ng-container [ngSwitch]="section">
+ <div *ngSwitchCase="'Team Selection'" id="team_selection" class="container-fluid">
+ <div class="row">
+ <label for="match_number">Match Number</label>
+ <input [(ngModel)]="matchNumber" type="number" id="match_number" min="1" max="999">
+ </div>
+ <div class="row">
+ <label for="team_number">Team Number</label>
+ <input [(ngModel)]="teamNumber" type="number" id="team_number" min="1" max="9999">
+ </div>
+ <div class="buttons">
+ <!-- hack to right align the next button -->
+ <div></div>
+ <button class="btn btn-primary" (click)="nextSection()">Next</button>
+ </div>
+ </div>
+
+ <div *ngSwitchCase="'Auto'" id="auto" class="container-fluid">
+ <div class="row">
+ <!--Image here-->
+ <h4>Image</h4>
+ <form>
+ <!--Choice for each ball location-->
+ <input type="checkbox" name="balls" value="1" id="ball-1"><label for="ball-1">Ball 1</label>
+ <input type="checkbox" name="balls" value="2" id="ball-2"><label for="ball-2">Ball 2</label><br>
+ <input type="checkbox" name="balls" value="3" id="ball-3"><label for="ball-3">Ball 3</label>
+ <input type="checkbox" name="balls" value="4" id="ball-4"><label for="ball-4">Ball 4</label><br>
+ <input type="checkbox" name="balls" value="5" id="ball-5"><label for="ball-5">Ball 5</label>
+ <input type="checkbox" name="balls" value="6" id="ball-6"><label for="ball-6">Ball 6</label>
+ </form>
+ </div>
+ <div class="row">
+ <!--Image here-->
+ <h4>Image</h4>
+ <form>
+ <input type="radio" name="quadrant" id="first" value="Quadrant 1">
+ <label for="first">Quadrant 1</label>
+ <input type="radio" name="quadrant" id="second" value="Quadrant 2">
+ <label for="second">Quadrant 2</label><br>
+ <input type="radio" name="quadrant" id="third" value="Quadrant 3">
+ <label for="third">Quadrant 3</label>
+ <input type="radio" name="quadrant" id="fourth" value="Quadrant 4">
+ <label for="fourth">Quadrant 4</label>
+ </form>
+ </div>
+ <div class="row justify-content-center">
+ <frc971-counter-button class="col-4" [(value)]="autoUpperShotsMade">Upper</frc971-counter-button>
+ <frc971-counter-button class="col-4" [(value)]="autoLowerShotsMade">Lower</frc971-counter-button>
+ <frc971-counter-button class="col-4" [(value)]="autoShotsMissed">Missed</frc971-counter-button>
+ </div>
+ <div class="buttons">
+ <button class="btn btn-primary" (click)="prevSection()">Back</button>
+ <button class="btn btn-primary" (click)="nextSection()">Next</button>
+ </div>
+ </div>
+
+ <div *ngSwitchCase="'TeleOp'" id="teleop" class="container-fluid">
+ <div class="row justify-content-center">
+ <frc971-counter-button class="col-4" [(value)]="teleUpperShotsMade">Upper</frc971-counter-button>
+ <frc971-counter-button class="col-4" [(value)]="teleLowerShotsMade">Lower</frc971-counter-button>
+ <frc971-counter-button class="col-4" [(value)]="teleShotsMissed">Missed</frc971-counter-button>
+ </div>
+ <div class="buttons">
+ <button class="btn btn-primary" (click)="prevSection()">Back</button>
+ <button class="btn btn-primary" (click)="nextSection()">Next</button>
+ </div>
+ </div>
+
+ <div *ngSwitchCase="'Climb'" id="climb" class="container-fluid">
+ <div class="row">
+ <form>
+ <input [(ngModel)]="climbed" type="radio" name="climbing" id="continue" [value]="false">
+ <label for="continue">Kept Shooting</label><br>
+ <input [(ngModel)]="climbed" type="radio" name="climbing" id="climbed" [value]="true">
+ <label for="climbed">Attempted to Climb</label><br>
+ </form>
+ </div>
+ <div *ngIf="climbed">
+ <h4>Bar Made</h4>
+ <form>
+ <input [ngModel]="level" (click)="setLow()" type="radio" name="level" id="low" value="Low">
+ <label for="low">Low</label><br>
+ <input [ngModel]="level" (click)="setMedium()" type="radio" name="level" id="medium" value="Medium">
+ <label for="medium">Medium</label><br>
+ <input [ngModel]="level" (click)="setHigh()" type="radio" name="level" id="high" value="High">
+ <label for="high">High</label><br>
+ <input [ngModel]="level" (click)="setTransversal()" type="radio" name="level" id="transversal" value="Transversal">
+ <label for="transversal">Transversal</label><br>
+ <input [ngModel]="level" (click)="setFailed()" type="radio" name="level" id="failed" value="Failed">
+ <label for="failed">Failed</label><br>
+
+ <input (click)="toggleProper()" type="checkbox" id="proper">
+ <label for="proper">~10 seconds to attempt next level?</label>
+ </form>
+ </div>
+ <div class="row">
+ <h4>Comments</h4>
+ <textarea></textarea>
+ </div>
+ <div class="buttons">
+ <button class="btn btn-primary" (click)="prevSection()">Back</button>
+ <button class="btn btn-primary" (click)="nextSection()">Next</button>
+ </div>
+ </div>
+
+ <div *ngSwitchCase="'Defense'" id="defense" class="container-fluid">
+ <h4 class="text-center">How much defense did other robots play on this robot?</h4>
+
+ <div class="row" style="min-height: 50px">
+ <div class="col">
+ <h6>None</h6>
+ </div>
+
+ <div class="col">
+ <input type="range" min="0" max="5" value="0" [(ngModel)]="defensePlayedOnScore">
+ </div>
+
+ <div class="col">
+ <h6>A lot</h6>
+ </div>
+ </div>
+
+ <h6 class="text-center">{{defensePlayedOnScore}}</h6>
+
+ <h4 class="text-center">How much defense did this robot play?</h4>
+
+ <div class="row">
+
+ <div class="col">
+ <h6>None</h6>
+ </div>
+
+ <div class="col">
+ <input type="range" min="0" max="5" value="0" [(ngModel)]="defensePlayedScore">
+ </div>
+
+ <div class="col">
+ <h6>A lot</h6>
+ </div>
+ </div>
+ <h6 class="text-center">{{defensePlayedScore}}</h6>
+
+ <div class="buttons">
+ <button class="btn btn-primary" (click)="prevSection()">Back</button>
+ <button class="btn btn-primary" (click)="nextSection()">Next</button>
+ </div>
+ </div>
+
+ <div *ngSwitchCase="'Review and Submit'" id="review" class="container-fluid">
+ <h4>Team Selection</h4>
+ <ul>
+ <li>Match number: {{matchNumber}}</li>
+ <li>Team number: {{teamNumber}}</li>
+ </ul>
+
+ <h4>Auto</h4>
+ <ul>
+ <li>Upper Shots Made: {{autoUpperShotsMade}}</li>
+ <li>Lower Shots Made: {{autoLowerShotsMade}}</li>
+ <li>Missed Shots: {{autoShotsMissed}}</li>
+ </ul>
+
+ <h4>TeleOp</h4>
+ <ul>
+ <li>Upper Shots Made: {{teleUpperShotsMade}}</li>
+ <li>Lower Shots Made: {{teleLowerShotsMade}}</li>
+ <li>Missed Shots: {{teleShotsMissed}}</li>
+ </ul>
+
+ <h4>Climb</h4>
+ <ul>
+ <div *ngIf="climbed">
+ <li *ngIf="climbed">Attempted to Climb?: Yes</li>
+ <li>Level: {{level}}</li>
+ <li *ngIf="proper">Proper Attempt: Yes</li>
+ <li *ngIf="!proper">Proper Attempt: No</li>
+ </div>
+ <li *ngIf="!climbed">Attempted to Climb: No</li>
+ </ul>
+
+ <h4>Defense</h4>
+ <ul>
+ <li>Defense Played On Rating: {{defensePlayedOnScore}}</li>
+ <li>Defense Played Rating: {{defensePlayedScore}}</li>
+ </ul>
+
+ <span class="error_message">{{ errorMessage }}</span>
+
+ <div class="buttons">
+ <button class="btn btn-primary" (click)="prevSection()">Back</button>
+ <button class="btn btn-primary" (click)="nextSection()">Submit</button>
+ </div>
+ </div>
+</ng-container>
diff --git a/scouting/www/import_match_list/BUILD b/scouting/www/import_match_list/BUILD
new file mode 100644
index 0000000..9e40794
--- /dev/null
+++ b/scouting/www/import_match_list/BUILD
@@ -0,0 +1,27 @@
+load("@npm//@bazel/typescript:index.bzl", "ts_library")
+
+ts_library(
+ name = "import_match_list",
+ srcs = [
+ "import_match_list.component.ts",
+ "import_match_list.module.ts",
+ ],
+ angular_assets = [
+ "import_match_list.component.css",
+ "import_match_list.ng.html",
+ "//scouting/www:common_css",
+ ],
+ compiler = "//tools:tsc_wrapped_with_angular",
+ target_compatible_with = ["@platforms//cpu:x86_64"],
+ use_angular_plugin = True,
+ visibility = ["//visibility:public"],
+ deps = [
+ "//scouting/webserver/requests/messages:error_response_ts_fbs",
+ "//scouting/webserver/requests/messages:refresh_match_list_response_ts_fbs",
+ "//scouting/webserver/requests/messages:refresh_match_list_ts_fbs",
+ "@com_github_google_flatbuffers//ts:flatbuffers_ts",
+ "@npm//@angular/common",
+ "@npm//@angular/core",
+ "@npm//@angular/forms",
+ ],
+)
diff --git a/scouting/www/import_match_list/import_match_list.component.css b/scouting/www/import_match_list/import_match_list.component.css
new file mode 100644
index 0000000..0570c72
--- /dev/null
+++ b/scouting/www/import_match_list/import_match_list.component.css
@@ -0,0 +1,3 @@
+* {
+ padding: 10px;
+}
diff --git a/scouting/www/import_match_list/import_match_list.component.ts b/scouting/www/import_match_list/import_match_list.component.ts
new file mode 100644
index 0000000..7ad4ab6
--- /dev/null
+++ b/scouting/www/import_match_list/import_match_list.component.ts
@@ -0,0 +1,57 @@
+import { Component, OnInit } from '@angular/core';
+
+import * as flatbuffer_builder from 'org_frc971/external/com_github_google_flatbuffers/ts/builder';
+import {ByteBuffer} from 'org_frc971/external/com_github_google_flatbuffers/ts/byte-buffer';
+import * as error_response from 'org_frc971/scouting/webserver/requests/messages/error_response_generated';
+import * as refresh_match_list_response from 'org_frc971/scouting/webserver/requests/messages/refresh_match_list_response_generated';
+import * as refresh_match_list from 'org_frc971/scouting/webserver/requests/messages/refresh_match_list_generated';
+import RefreshMatchList = refresh_match_list.scouting.webserver.requests.RefreshMatchList;
+import RefreshMatchListResponse = refresh_match_list_response.scouting.webserver.requests.RefreshMatchListResponse;
+import ErrorResponse = error_response.scouting.webserver.requests.ErrorResponse;
+
+@Component({
+ selector: 'app-import-match-list',
+ templateUrl: './import_match_list.ng.html',
+ styleUrls: ['../common.css', './import_match_list.component.css']
+})
+export class ImportMatchListComponent {
+ year: number = new Date().getFullYear();
+ eventCode: string = '';
+ progressMessage: string = '';
+ errorMessage: string = '';
+
+ async importMatchList() {
+ if (!window.confirm('Actually import new matches?')) {
+ return;
+ }
+
+ this.errorMessage = '';
+
+ const builder = new flatbuffer_builder.Builder() as unknown as flatbuffers.Builder;
+ const eventCode = builder.createString(this.eventCode);
+ RefreshMatchList.startRefreshMatchList(builder);
+ RefreshMatchList.addYear(builder, this.year);
+ RefreshMatchList.addEventCode(builder, eventCode);
+ builder.finish(RefreshMatchList.endRefreshMatchList(builder));
+
+ this.progressMessage = 'Importing match list. Please be patient.';
+
+ const buffer = builder.asUint8Array();
+ const res = await fetch(
+ '/requests/refresh_match_list', {method: 'POST', body: buffer});
+
+ if (res.ok) {
+ // We successfully submitted the data.
+ this.progressMessage = 'Successfully imported match list.';
+ } else {
+ this.progressMessage = '';
+ const resBuffer = await res.arrayBuffer();
+ const fbBuffer = new ByteBuffer(new Uint8Array(resBuffer));
+ const parsedResponse = ErrorResponse.getRootAsErrorResponse(
+ fbBuffer as unknown as flatbuffers.ByteBuffer);
+
+ const errorMessage = parsedResponse.errorMessage();
+ this.errorMessage = `Received ${res.status} ${res.statusText}: "${errorMessage}"`;
+ }
+ }
+}
diff --git a/scouting/www/import_match_list/import_match_list.module.ts b/scouting/www/import_match_list/import_match_list.module.ts
new file mode 100644
index 0000000..1da8bec
--- /dev/null
+++ b/scouting/www/import_match_list/import_match_list.module.ts
@@ -0,0 +1,12 @@
+import {NgModule} from '@angular/core';
+import {CommonModule} from '@angular/common';
+import {ImportMatchListComponent} from './import_match_list.component';
+import {FormsModule} from '@angular/forms';
+
+@NgModule({
+ declarations: [ImportMatchListComponent],
+ exports: [ImportMatchListComponent],
+ imports: [CommonModule, FormsModule],
+})
+export class ImportMatchListModule {
+}
diff --git a/scouting/www/import_match_list/import_match_list.ng.html b/scouting/www/import_match_list/import_match_list.ng.html
new file mode 100644
index 0000000..3c7ffa0
--- /dev/null
+++ b/scouting/www/import_match_list/import_match_list.ng.html
@@ -0,0 +1,20 @@
+<div class="header">
+ <h2>Import Match List</h2>
+</div>
+
+<div class="container-fluid">
+ <div class="row">
+ <label for="year">Year</label>
+ <input [(ngModel)]="year" type="number" id="year" min="1970" max="2500">
+ </div>
+ <div class="row">
+ <label for="event_code">Event Code</label>
+ <input [(ngModel)]="eventCode" type="text" id="event_code">
+ </div>
+
+ <span class="progress_message">{{ progressMessage }}</span>
+ <span class="error_message">{{ errorMessage }}</span>
+ <div class="text-right">
+ <button class="btn btn-primary" (click)="importMatchList()">Import</button>
+ </div>
+</div>
diff --git a/scouting/www/index.html b/scouting/www/index.html
index cbe8770..3a09dfd 100644
--- a/scouting/www/index.html
+++ b/scouting/www/index.html
@@ -1,7 +1,10 @@
+<!DOCTYPE html>
<html>
<head>
+ <meta name="viewport" content="width=device-width, initial-scale=1">
<base href="/">
<script src="./npm/node_modules/zone.js/dist/zone.min.js"></script>
+ <link href="https://cdn.jsdelivr.net/npm/bootstrap@5.1.3/dist/css/bootstrap.min.css" rel="stylesheet" integrity="sha384-1BmE4kWBq78iYhFldvKuhfTAU6auU8tT94WrHftjDbrCEXSU1oBoqyl2QvZ6jIW3" crossorigin="anonymous">
</head>
<body>
<my-app></my-app>
diff --git a/third_party/rules_pkg/0001-Fix-tree-artifacts.patch b/third_party/rules_pkg/0001-Fix-tree-artifacts.patch
new file mode 100644
index 0000000..567aba7
--- /dev/null
+++ b/third_party/rules_pkg/0001-Fix-tree-artifacts.patch
@@ -0,0 +1,28 @@
+From d654cc64ae71366ea82ac492106e9b2c8fa532d5 Mon Sep 17 00:00:00 2001
+From: Philipp Schrader <philipp.schrader@gmail.com>
+Date: Thu, 10 Mar 2022 23:25:21 -0800
+Subject: [PATCH] Fix tree artifacts
+
+For some reason the upstream code strips the directory names from the
+`babel()` rule that we use. This patch makes it so the directory is
+not stripped. This makes runfiles layout in the tarball match the
+runfiles layout in `bazel-bin`.
+---
+ pkg/pkg.bzl | 4 ++--
+ 1 file changed, 2 insertions(+), 2 deletions(-)
+
+diff --git a/pkg/pkg.bzl b/pkg/pkg.bzl
+index d7adbbc..a241b26 100644
+--- a/pkg/pkg.bzl
++++ b/pkg/pkg.bzl
+@@ -157,8 +157,8 @@ def _pkg_tar_impl(ctx):
+ # Tree artifacts need a name, but the name is never really
+ # the important part. The likely behavior people want is
+ # just the content, so we strip the directory name.
+- dest = "/".join(d_path.split("/")[0:-1])
+- add_tree_artifact(content_map, dest, f, src.label)
++ #dest = "/".join(d_path.split("/")[0:-1])
++ add_tree_artifact(content_map, d_path, f, src.label)
+ else:
+ # Note: This extra remap is the bottleneck preventing this
+ # large block from being a utility method as shown below.
diff --git a/y2016/control_loops/superstructure/superstructure_controls.cc b/y2016/control_loops/superstructure/superstructure_controls.cc
index d16c73c..ee2020e 100644
--- a/y2016/control_loops/superstructure/superstructure_controls.cc
+++ b/y2016/control_loops/superstructure/superstructure_controls.cc
@@ -101,10 +101,12 @@
// Handle zeroing errors
if (estimators_[kShoulderIndex].error()) {
AOS_LOG(ERROR, "zeroing error with shoulder_estimator\n");
+ X_hat_ = loop_->X_hat();
return;
}
if (estimators_[kWristIndex].error()) {
AOS_LOG(ERROR, "zeroing error with wrist_estimator\n");
+ X_hat_ = loop_->X_hat();
return;
}
@@ -130,6 +132,7 @@
Y_ << position_shoulder->encoder(), position_wrist->encoder();
Y_ += offset_;
loop_->Correct(Y_);
+ X_hat_ = loop_->X_hat();
}
}
diff --git a/y2017/control_loops/superstructure/column/column.cc b/y2017/control_loops/superstructure/column/column.cc
index d5e2611..8f36085 100644
--- a/y2017/control_loops/superstructure/column/column.cc
+++ b/y2017/control_loops/superstructure/column/column.cc
@@ -99,6 +99,7 @@
if (estimators_[0].error()) {
AOS_LOG(ERROR, "zeroing error\n");
+ X_hat_ = loop_->X_hat();
return;
}
@@ -120,6 +121,7 @@
Y_ << new_position.indexer()->encoder(), new_position.turret()->encoder();
Y_ += offset_;
loop_->Correct(Y_);
+ X_hat_ = loop_->X_hat();
indexer_history_[indexer_history_position_] =
new_position.indexer()->encoder();
diff --git a/y2020/actors/auto_splines.cc b/y2020/actors/auto_splines.cc
index 0ed59e2..3ad292d 100644
--- a/y2020/actors/auto_splines.cc
+++ b/y2020/actors/auto_splines.cc
@@ -5,8 +5,8 @@
namespace y2020 {
namespace actors {
-constexpr double kFieldLength = 15.983;
-constexpr double kFieldWidth = 8.212;
+constexpr double kFieldLength = 16.4592;
+constexpr double kFieldWidth = 8.2296;
void MaybeFlipSpline(
aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
diff --git a/y2020/control_loops/superstructure/turret/BUILD b/y2020/control_loops/superstructure/turret/BUILD
index 3761868..703c01e 100644
--- a/y2020/control_loops/superstructure/turret/BUILD
+++ b/y2020/control_loops/superstructure/turret/BUILD
@@ -43,6 +43,7 @@
"//frc971/control_loops:control_loops_fbs",
"//frc971/control_loops:pose",
"//frc971/control_loops:profiled_subsystem_fbs",
+ "//frc971/control_loops/aiming",
"//frc971/control_loops/drivetrain:drivetrain_status_fbs",
"//y2020:constants",
"//y2020/control_loops/drivetrain:drivetrain_base",
diff --git a/y2020/control_loops/superstructure/turret/aiming.cc b/y2020/control_loops/superstructure/turret/aiming.cc
index c8f8f6e..4976efa 100644
--- a/y2020/control_loops/superstructure/turret/aiming.cc
+++ b/y2020/control_loops/superstructure/turret/aiming.cc
@@ -9,6 +9,9 @@
namespace turret {
using frc971::control_loops::Pose;
+using frc971::control_loops::aiming::TurretGoal;
+using frc971::control_loops::aiming::ShotConfig;
+using frc971::control_loops::aiming::RobotState;
// Shooting-on-the-fly concept:
// The current way that we manage shooting-on-the fly endeavors to be reasonably
@@ -104,22 +107,6 @@
fbb.Finish(builder.Finish());
return fbb.Release();
}
-
-// This implements the iteration in the described shooting-on-the-fly algorithm.
-// robot_pose: Current robot pose.
-// robot_velocity: Current robot velocity, in the absolute field frame.
-// target_pose: Absolute goal Pose.
-// current_virtual_pose: Current estimate of where we want to shoot at.
-Pose IterateVirtualGoal(const Pose &robot_pose,
- const Eigen::Vector3d &robot_velocity,
- const Pose &target_pose,
- const Pose ¤t_virtual_pose) {
- const double air_time =
- current_virtual_pose.Rebase(&robot_pose).xy_norm() / kBallSpeedOverGround;
- const Eigen::Vector3d virtual_target =
- target_pose.abs_pos() - air_time * robot_velocity;
- return Pose(virtual_target, target_pose.abs_theta());
-}
} // namespace
Pose InnerPortPose(aos::Alliance alliance) {
@@ -176,83 +163,25 @@
aiming_for_inner_port_ =
(std::abs(inner_port_angle_) < max_inner_port_angle) &&
(inner_port_distance > min_inner_port_distance);
+ const Pose goal = aiming_for_inner_port_ ? inner_port : outer_port;
- // This code manages compensating the goal turret heading for the robot's
- // current velocity, to allow for shooting on-the-fly.
- // This works by solving for the correct turret angle numerically, since while
- // we technically could do it analytically, doing so would both make it hard
- // to make small changes (since it would force us to redo the math) and be
- // error-prone since it'd be easy to make typos or other minor math errors.
- Pose virtual_goal;
- {
- const Pose goal = aiming_for_inner_port_ ? inner_port : outer_port;
- target_distance_ = goal.Rebase(&robot_pose).xy_norm();
- virtual_goal = goal;
- if (shot_mode == ShotMode::kShootOnTheFly) {
- for (int ii = 0; ii < 3; ++ii) {
- virtual_goal =
- IterateVirtualGoal(robot_pose, {xdot, ydot, 0}, goal, virtual_goal);
- }
- VLOG(1) << "Shooting-on-the-fly target position: "
- << virtual_goal.abs_pos().transpose();
- }
- virtual_goal = virtual_goal.Rebase(&robot_pose);
- }
+ const struct TurretGoal turret_goal =
+ frc971::control_loops::aiming::AimerGoal(
+ ShotConfig{goal, shot_mode, constants::Values::kTurretRange(),
+ kBallSpeedOverGround,
+ wrap_mode == WrapMode::kAvoidEdges ? kAntiWrapBuffer : 0.0,
+ kTurretZeroOffset},
+ RobotState{robot_pose,
+ {xdot, ydot},
+ linear_angular(1),
+ goal_.message().unsafe_goal()});
- const double heading_to_goal = virtual_goal.heading();
- CHECK(status->has_localizer());
- shot_distance_ = virtual_goal.xy_norm();
+ target_distance_ = turret_goal.target_distance;
+ shot_distance_ = turret_goal.virtual_shot_distance;
- // The following code all works to calculate what the rate of turn of the
- // turret should be. The code only accounts for the rate of turn if we are
- // aiming at a static target, which should be close enough to correct that it
- // doesn't matter that it fails to account for the
- // shooting-on-the-fly compensation.
- const double rel_x = virtual_goal.rel_pos().x();
- const double rel_y = virtual_goal.rel_pos().y();
- const double squared_norm = rel_x * rel_x + rel_y * rel_y;
- // rel_xdot and rel_ydot are the derivatives (with respect to time) of rel_x
- // and rel_y. Since these are in the robot's coordinate frame, and since we
- // are ignoring lateral velocity for this exercise, rel_ydot is zero, and
- // rel_xdot is just the inverse of the robot's velocity.
- const double rel_xdot = -linear_angular(0);
- const double rel_ydot = 0.0;
-
- // If squared_norm gets to be too close to zero, just zero out the relevant
- // term to prevent NaNs. Note that this doesn't address the chattering that
- // would likely occur if we were to get excessively close to the target.
- // Note that x and y terms are swapped relative to what you would normally see
- // in the derivative of atan because xdot and ydot are the derivatives of
- // robot_pos and we are working with the atan of (target_pos - robot_pos).
- const double atan_diff =
- (squared_norm < 1e-3) ? 0.0 : (rel_x * rel_ydot - rel_y * rel_xdot) /
- squared_norm;
- // heading = atan2(relative_y, relative_x) - robot_theta
- // dheading / dt =
- // (rel_x * rel_y' - rel_y * rel_x') / (rel_x^2 + rel_y^2) - dtheta / dt
- const double dheading_dt = atan_diff - linear_angular(1);
-
- double range = kTurretRange;
- if (wrap_mode == WrapMode::kAvoidEdges) {
- range -= 2.0 * kAntiWrapBuffer;
- }
- // Calculate a goal turret heading such that it is within +/- pi of the
- // current position (i.e., a goal that would minimize the amount the turret
- // would have to travel).
- // We then check if this goal would bring us out of range of the valid angles,
- // and if it would, we reset to be within +/- pi of zero.
- double turret_heading =
- goal_.message().unsafe_goal() +
- aos::math::NormalizeAngle(heading_to_goal - kTurretZeroOffset -
- goal_.message().unsafe_goal());
- if (std::abs(turret_heading - constants::Values::kTurretRange().middle()) >
- range / 2.0) {
- turret_heading = aos::math::NormalizeAngle(turret_heading);
- }
-
- goal_.mutable_message()->mutate_unsafe_goal(turret_heading);
+ goal_.mutable_message()->mutate_unsafe_goal(turret_goal.position);
goal_.mutable_message()->mutate_goal_velocity(
- std::clamp(dheading_dt, -2.0, 2.0));
+ std::clamp(turret_goal.velocity, -2.0, 2.0));
}
flatbuffers::Offset<AimerStatus> Aimer::PopulateStatus(
diff --git a/y2020/control_loops/superstructure/turret/aiming.h b/y2020/control_loops/superstructure/turret/aiming.h
index ed00972..217085c 100644
--- a/y2020/control_loops/superstructure/turret/aiming.h
+++ b/y2020/control_loops/superstructure/turret/aiming.h
@@ -6,6 +6,7 @@
#include "frc971/control_loops/pose.h"
#include "frc971/control_loops/profiled_subsystem_generated.h"
#include "frc971/input/joystick_state_generated.h"
+#include "frc971/control_loops/aiming/aiming.h"
#include "y2020/control_loops/superstructure/superstructure_status_generated.h"
namespace y2020 {
@@ -39,14 +40,7 @@
kAvoidWrapping,
};
- // Control modes for managing how we manage shooting on the fly.
- enum class ShotMode {
- // Don't do any shooting-on-the-fly compensation--just point straight at the
- // target. Primarily used in tests.
- kStatic,
- // Do do shooting-on-the-fly compensation.
- kShootOnTheFly,
- };
+ typedef frc971::control_loops::aiming::ShotMode ShotMode;
Aimer();
diff --git a/y2020/vision/BUILD b/y2020/vision/BUILD
index de85213..1fd48cf 100644
--- a/y2020/vision/BUILD
+++ b/y2020/vision/BUILD
@@ -128,6 +128,8 @@
deps = [
"//aos:init",
"//aos/events/logging:log_reader",
+ "//frc971/control_loops:profiled_subsystem_fbs",
"//frc971/vision:extrinsics_calibration",
+ "//y2020/control_loops/superstructure:superstructure_status_fbs",
],
)
diff --git a/y2020/vision/extrinsics_calibration.cc b/y2020/vision/extrinsics_calibration.cc
index c54a5cf..c561652 100644
--- a/y2020/vision/extrinsics_calibration.cc
+++ b/y2020/vision/extrinsics_calibration.cc
@@ -1,6 +1,7 @@
+#include "frc971/vision/extrinsics_calibration.h"
+
#include "Eigen/Dense"
#include "Eigen/Geometry"
-
#include "absl/strings/str_format.h"
#include "aos/events/logging/log_reader.h"
#include "aos/init.h"
@@ -9,15 +10,15 @@
#include "aos/util/file.h"
#include "frc971/control_loops/quaternion_utils.h"
#include "frc971/vision/vision_generated.h"
-#include "frc971/vision/extrinsics_calibration.h"
#include "frc971/wpilib/imu_batch_generated.h"
+#include "y2020/control_loops/superstructure/superstructure_status_generated.h"
#include "y2020/vision/sift/sift_generated.h"
#include "y2020/vision/sift/sift_training_generated.h"
#include "y2020/vision/tools/python_code/sift_training_data.h"
-DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate.");
DEFINE_bool(plot, false, "Whether to plot the resulting data.");
+DEFINE_bool(turret, false, "If true, the camera is on the turret");
namespace frc971 {
namespace vision {
@@ -60,6 +61,21 @@
Calibration extractor(&factory, pi_event_loop.get(),
roborio_event_loop.get(), FLAGS_pi, &data);
+ if (FLAGS_turret) {
+ aos::NodeEventLoopFactory *roborio_factory =
+ factory.GetNodeEventLoopFactory(roborio_node->name()->string_view());
+ roborio_event_loop->MakeWatcher(
+ "/superstructure",
+ [roborio_factory, roborio_event_loop = roborio_event_loop.get(),
+ &data](const y2020::control_loops::superstructure::Status &status) {
+ data.AddTurret(
+ roborio_factory->ToDistributedClock(
+ roborio_event_loop->context().monotonic_event_time),
+ Eigen::Vector2d(status.turret()->position(),
+ status.turret()->velocity()));
+ });
+ }
+
factory.Run();
reader.Deregister();
@@ -71,26 +87,26 @@
const Eigen::Quaternion<double> nominal_initial_orientation(
frc971::controls::ToQuaternionFromRotationVector(
Eigen::Vector3d(0.0, 0.0, M_PI)));
- const Eigen::Quaternion<double> nominal_imu_to_camera(
+ const Eigen::Quaternion<double> nominal_pivot_to_camera(
Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
const Eigen::Quaternion<double> nominal_board_to_world(
Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
CalibrationParameters calibration_parameters;
calibration_parameters.initial_orientation = nominal_initial_orientation;
- calibration_parameters.imu_to_camera = nominal_imu_to_camera;
+ calibration_parameters.pivot_to_camera = nominal_pivot_to_camera;
calibration_parameters.board_to_world = nominal_board_to_world;
Solve(data, &calibration_parameters);
LOG(INFO) << "Nominal initial_orientation "
<< nominal_initial_orientation.coeffs().transpose();
- LOG(INFO) << "Nominal imu_to_camera "
- << nominal_imu_to_camera.coeffs().transpose();
+ LOG(INFO) << "Nominal pivot_to_camera "
+ << nominal_pivot_to_camera.coeffs().transpose();
- LOG(INFO) << "imu_to_camera delta "
+ LOG(INFO) << "pivot_to_camera delta "
<< frc971::controls::ToRotationVectorFromQuaternion(
- calibration_parameters.imu_to_camera *
- nominal_imu_to_camera.inverse())
+ calibration_parameters.pivot_to_camera *
+ nominal_pivot_to_camera.inverse())
.transpose();
LOG(INFO) << "board_to_world delta "
<< frc971::controls::ToRotationVectorFromQuaternion(
diff --git a/y2022/BUILD b/y2022/BUILD
index cc3aa93..f2bdb8b 100644
--- a/y2022/BUILD
+++ b/y2022/BUILD
@@ -1,9 +1,11 @@
load("//frc971:downloader.bzl", "robot_downloader")
load("//aos:config.bzl", "aos_config")
+load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
load("//tools/build_rules:template.bzl", "jinja2_template")
robot_downloader(
binaries = [
+ ":setpoint_setter",
"//aos/network:web_proxy_main",
],
data = [
@@ -12,6 +14,7 @@
"@ctre_phoenix_cci_athena//:shared_libraries",
],
dirs = [
+ "//y2022/actors:splines",
"//y2022/www:www_files",
],
start_binaries = [
@@ -36,10 +39,14 @@
"//y2022/vision:viewer",
"//y2022/localizer:imu_main",
"//y2022/localizer:localizer_main",
+ "//y2022/vision:image_decimator",
],
data = [
":aos_config",
],
+ dirs = [
+ "//y2022/www:www_files",
+ ],
start_binaries = [
"//aos/events/logging:logger_main",
"//aos/network:message_bridge_client",
@@ -85,6 +92,7 @@
"//aos/network:timestamp_fbs",
"//aos/network:remote_message_fbs",
"//frc971/vision:vision_fbs",
+ "//y2022/localizer:localizer_output_fbs",
"//y2022/vision:calibration_fbs",
"//y2022/vision:target_estimate_fbs",
],
@@ -114,6 +122,7 @@
"//aos/network:remote_message_fbs",
"//y2022/localizer:localizer_status_fbs",
"//y2022/localizer:localizer_output_fbs",
+ "//y2022/localizer:localizer_visualization_fbs",
],
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//visibility:public"],
@@ -147,6 +156,7 @@
name = "config_roborio",
src = "y2022_roborio.json",
flatbuffers = [
+ ":setpoint_fbs",
"//aos/network:remote_message_fbs",
"//aos/network:message_bridge_client_fbs",
"//aos/network:message_bridge_server_fbs",
@@ -193,6 +203,7 @@
"//frc971:constants",
"//frc971/control_loops:pose",
"//frc971/control_loops:static_zeroing_single_dof_profiled_subsystem",
+ "//frc971/shooter_interpolation:interpolation",
"//y2022/control_loops/drivetrain:polydrivetrain_plants",
"//y2022/control_loops/superstructure/catapult:catapult_plants",
"//y2022/control_loops/superstructure/climber:climber_plants",
@@ -252,6 +263,8 @@
":joystick_reader.cc",
],
deps = [
+ ":constants",
+ ":setpoint_fbs",
"//aos:init",
"//aos/actions:action_lib",
"//aos/logging",
@@ -267,9 +280,42 @@
],
)
+flatbuffer_cc_library(
+ name = "setpoint_fbs",
+ srcs = [
+ "setpoint.fbs",
+ ],
+ gen_reflections = 1,
+ target_compatible_with = ["@platforms//os:linux"],
+)
+
+cc_binary(
+ name = "setpoint_setter",
+ srcs = ["setpoint_setter.cc"],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ ":constants",
+ ":setpoint_fbs",
+ "//aos:init",
+ "//aos/events:shm_event_loop",
+ ],
+)
+
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",
+ "//y2022/www:field_main_bundle.min.js",
+ "//y2022/www:files",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+)
diff --git a/y2022/actors/BUILD b/y2022/actors/BUILD
index 57b1222..3c8c6b8 100644
--- a/y2022/actors/BUILD
+++ b/y2022/actors/BUILD
@@ -1,3 +1,5 @@
+load("//frc971/downloader:downloader.bzl", "aos_downloader_dir")
+
filegroup(
name = "binaries.stripped",
srcs = [
@@ -14,6 +16,24 @@
visibility = ["//visibility:public"],
)
+filegroup(
+ name = "spline_jsons",
+ srcs = glob([
+ "splines/*.json",
+ ]),
+ visibility = ["//visibility:public"],
+)
+
+aos_downloader_dir(
+ name = "splines",
+ srcs = [
+ ":spline_jsons",
+ ],
+ dir = "splines",
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+)
+
cc_library(
name = "autonomous_action_lib",
srcs = [
@@ -33,6 +53,7 @@
"//frc971/control_loops:profiled_subsystem_fbs",
"//frc971/control_loops/drivetrain:drivetrain_config",
"//frc971/control_loops/drivetrain:localizer_fbs",
+ "//y2022:constants",
"//y2022/control_loops/drivetrain:drivetrain_base",
"//y2022/control_loops/superstructure:superstructure_goal_fbs",
"//y2022/control_loops/superstructure:superstructure_status_fbs",
diff --git a/y2022/actors/auto_splines.cc b/y2022/actors/auto_splines.cc
index ce206c8..b06ec99 100644
--- a/y2022/actors/auto_splines.cc
+++ b/y2022/actors/auto_splines.cc
@@ -19,84 +19,85 @@
}
}
-flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::BasicSSpline(
- aos::Sender<frc971::control_loops::drivetrain::Goal>::Builder *builder) {
- flatbuffers::Offset<frc971::Constraint> longitudinal_constraint_offset;
- flatbuffers::Offset<frc971::Constraint> lateral_constraint_offset;
- flatbuffers::Offset<frc971::Constraint> voltage_constraint_offset;
+flatbuffers::Offset<frc971::MultiSpline> FixSpline(
+ aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+ *builder,
+ flatbuffers::Offset<frc971::MultiSpline> spline_offset,
+ aos::Alliance alliance) {
+ frc971::MultiSpline *spline =
+ GetMutableTemporaryPointer(*builder->fbb(), spline_offset);
+ flatbuffers::Vector<float> *spline_x = spline->mutable_spline_x();
+ flatbuffers::Vector<float> *spline_y = spline->mutable_spline_y();
- {
- frc971::Constraint::Builder longitudinal_constraint_builder =
- builder->MakeBuilder<frc971::Constraint>();
- longitudinal_constraint_builder.add_constraint_type(
- frc971::ConstraintType::LONGITUDINAL_ACCELERATION);
- longitudinal_constraint_builder.add_value(1.0);
- longitudinal_constraint_offset = longitudinal_constraint_builder.Finish();
+ if (alliance == aos::Alliance::kBlue) {
+ for (size_t ii = 0; ii < spline_x->size(); ++ii) {
+ spline_x->Mutate(ii, -spline_x->Get(ii));
+ }
+ for (size_t ii = 0; ii < spline_y->size(); ++ii) {
+ spline_y->Mutate(ii, -spline_y->Get(ii));
+ }
}
-
- {
- frc971::Constraint::Builder lateral_constraint_builder =
- builder->MakeBuilder<frc971::Constraint>();
- lateral_constraint_builder.add_constraint_type(
- frc971::ConstraintType::LATERAL_ACCELERATION);
- lateral_constraint_builder.add_value(1.0);
- lateral_constraint_offset = lateral_constraint_builder.Finish();
- }
-
- {
- frc971::Constraint::Builder voltage_constraint_builder =
- builder->MakeBuilder<frc971::Constraint>();
- voltage_constraint_builder.add_constraint_type(
- frc971::ConstraintType::VOLTAGE);
- voltage_constraint_builder.add_value(6.0);
- voltage_constraint_offset = voltage_constraint_builder.Finish();
- }
-
- flatbuffers::Offset<
- flatbuffers::Vector<flatbuffers::Offset<frc971::Constraint>>>
- constraints_offset =
- builder->fbb()->CreateVector<flatbuffers::Offset<frc971::Constraint>>(
- {longitudinal_constraint_offset, lateral_constraint_offset,
- voltage_constraint_offset});
-
- const float startx = 0.4;
- const float starty = 3.4;
- flatbuffers::Offset<flatbuffers::Vector<float>> spline_x_offset =
- builder->fbb()->CreateVector<float>({0.0f + startx, 0.6f + startx,
- 0.6f + startx, 0.4f + startx,
- 0.4f + startx, 1.0f + startx});
- flatbuffers::Offset<flatbuffers::Vector<float>> spline_y_offset =
- builder->fbb()->CreateVector<float>({starty - 0.0f, starty - 0.0f,
- starty - 0.3f, starty - 0.7f,
- starty - 1.0f, starty - 1.0f});
-
- frc971::MultiSpline::Builder multispline_builder =
- builder->MakeBuilder<frc971::MultiSpline>();
-
- multispline_builder.add_spline_count(1);
- multispline_builder.add_constraints(constraints_offset);
- multispline_builder.add_spline_x(spline_x_offset);
- multispline_builder.add_spline_y(spline_y_offset);
-
- return multispline_builder.Finish();
+ return spline_offset;
}
-flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::StraightLine(
- aos::Sender<frc971::control_loops::drivetrain::Goal>::Builder *builder) {
- flatbuffers::Offset<flatbuffers::Vector<float>> spline_x_offset =
- builder->fbb()->CreateVector<float>(
- {-12.3, -11.9, -11.5, -11.1, -10.6, -10.0});
- flatbuffers::Offset<flatbuffers::Vector<float>> spline_y_offset =
- builder->fbb()->CreateVector<float>({1.25, 1.25, 1.25, 1.25, 1.25, 1.25});
+flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::TestSpline(
+ aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+ *builder,
+ aos::Alliance alliance) {
+ return FixSpline(
+ builder,
+ aos::CopyFlatBuffer<frc971::MultiSpline>(test_spline_, builder->fbb()),
+ alliance);
+}
- frc971::MultiSpline::Builder multispline_builder =
- builder->MakeBuilder<frc971::MultiSpline>();
+flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::Spline1(
+ aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+ *builder,
+ aos::Alliance alliance) {
+ return FixSpline(
+ builder,
+ aos::CopyFlatBuffer<frc971::MultiSpline>(spline_1_, builder->fbb()),
+ alliance);
+}
- multispline_builder.add_spline_count(1);
- multispline_builder.add_spline_x(spline_x_offset);
- multispline_builder.add_spline_y(spline_y_offset);
+flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::Spline2(
+ aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+ *builder,
+ aos::Alliance alliance) {
+ return FixSpline(
+ builder,
+ aos::CopyFlatBuffer<frc971::MultiSpline>(spline_2_, builder->fbb()),
+ alliance);
+}
- return multispline_builder.Finish();
+flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::Spline3(
+ aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+ *builder,
+ aos::Alliance alliance) {
+ return FixSpline(
+ builder,
+ aos::CopyFlatBuffer<frc971::MultiSpline>(spline_3_, builder->fbb()),
+ alliance);
+}
+
+flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::Spline4(
+ aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+ *builder,
+ aos::Alliance alliance) {
+ return FixSpline(
+ builder,
+ aos::CopyFlatBuffer<frc971::MultiSpline>(spline_4_, builder->fbb()),
+ alliance);
+}
+
+flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::Spline5(
+ aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+ *builder,
+ aos::Alliance alliance) {
+ return FixSpline(
+ builder,
+ aos::CopyFlatBuffer<frc971::MultiSpline>(spline_5_, builder->fbb()),
+ alliance);
}
} // namespace actors
diff --git a/y2022/actors/auto_splines.h b/y2022/actors/auto_splines.h
index 70c3569..4d532f4 100644
--- a/y2022/actors/auto_splines.h
+++ b/y2022/actors/auto_splines.h
@@ -2,8 +2,10 @@
#define Y2022_ACTORS_AUTO_SPLINES_H_
#include "aos/events/event_loop.h"
+#include "aos/flatbuffer_merge.h"
#include "frc971/control_loops/control_loops_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
+#include "frc971/input/joystick_state_generated.h"
/*
The cooridinate system for the autonomous splines is the same as the spline
@@ -16,10 +18,58 @@
class AutonomousSplines {
public:
+ AutonomousSplines()
+ : test_spline_(aos::JsonFileToFlatbuffer<frc971::MultiSpline>(
+ "splines/test_spline.json")),
+ spline_1_(aos::JsonFileToFlatbuffer<frc971::MultiSpline>(
+ "splines/spline_1.json")),
+ spline_2_(aos::JsonFileToFlatbuffer<frc971::MultiSpline>(
+ "splines/spline_2.json")),
+ spline_3_(aos::JsonFileToFlatbuffer<frc971::MultiSpline>(
+ "splines/spline_3.json")),
+ spline_4_(aos::JsonFileToFlatbuffer<frc971::MultiSpline>(
+ "splines/spline_4.json")),
+ spline_5_(aos::JsonFileToFlatbuffer<frc971::MultiSpline>(
+ "splines/spline_5.json")) {}
+
static flatbuffers::Offset<frc971::MultiSpline> BasicSSpline(
aos::Sender<frc971::control_loops::drivetrain::Goal>::Builder *builder);
static flatbuffers::Offset<frc971::MultiSpline> StraightLine(
aos::Sender<frc971::control_loops::drivetrain::Goal>::Builder *builder);
+
+ flatbuffers::Offset<frc971::MultiSpline> TestSpline(
+ aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+ *builder,
+ aos::Alliance alliance);
+
+ flatbuffers::Offset<frc971::MultiSpline> Spline1(
+ aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+ *builder,
+ aos::Alliance alliance);
+ flatbuffers::Offset<frc971::MultiSpline> Spline2(
+ aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+ *builder,
+ aos::Alliance alliance);
+ flatbuffers::Offset<frc971::MultiSpline> Spline3(
+ aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+ *builder,
+ aos::Alliance alliance);
+ flatbuffers::Offset<frc971::MultiSpline> Spline4(
+ aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+ *builder,
+ aos::Alliance alliance);
+ flatbuffers::Offset<frc971::MultiSpline> Spline5(
+ aos::Sender<frc971::control_loops::drivetrain::SplineGoal>::Builder
+ *builder,
+ aos::Alliance alliance);
+
+ private:
+ aos::FlatbufferDetachedBuffer<frc971::MultiSpline> test_spline_;
+ aos::FlatbufferDetachedBuffer<frc971::MultiSpline> spline_1_;
+ aos::FlatbufferDetachedBuffer<frc971::MultiSpline> spline_2_;
+ aos::FlatbufferDetachedBuffer<frc971::MultiSpline> spline_3_;
+ aos::FlatbufferDetachedBuffer<frc971::MultiSpline> spline_4_;
+ aos::FlatbufferDetachedBuffer<frc971::MultiSpline> spline_5_;
};
} // namespace actors
diff --git a/y2022/actors/autonomous_actor.cc b/y2022/actors/autonomous_actor.cc
index d96dd03..bf4fd13 100644
--- a/y2022/actors/autonomous_actor.cc
+++ b/y2022/actors/autonomous_actor.cc
@@ -5,33 +5,400 @@
#include <cmath>
#include "aos/logging/logging.h"
+#include "aos/network/team_number.h"
+#include "aos/util/math.h"
#include "frc971/control_loops/drivetrain/localizer_generated.h"
+#include "y2022/actors/auto_splines.h"
+#include "y2022/constants.h"
#include "y2022/control_loops/drivetrain/drivetrain_base.h"
+DEFINE_bool(spline_auto, false, "If true, define a spline autonomous mode");
+DEFINE_bool(rapid_react, false,
+ "If true, run the main rapid react autonomous mode");
+
namespace y2022 {
namespace actors {
+namespace {
+constexpr double kExtendIntakeGoal = 0.0;
+constexpr double kRetractIntakeGoal = 1.47;
+constexpr double kRollerVoltage = 12.0;
+constexpr double kCatapultReturnPosition = -0.908;
+} // namespace
using ::aos::monotonic_clock;
+using frc971::CreateProfileParameters;
using ::frc971::ProfileParametersT;
+using frc971::control_loops::CreateStaticZeroingSingleDOFProfiledSubsystemGoal;
+using frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
using frc971::control_loops::drivetrain::LocalizerControl;
+
namespace chrono = ::std::chrono;
AutonomousActor::AutonomousActor(::aos::EventLoop *event_loop)
: frc971::autonomous::BaseAutonomousActor(
- event_loop, control_loops::drivetrain::GetDrivetrainConfig()) {}
+ event_loop, control_loops::drivetrain::GetDrivetrainConfig()),
+ localizer_control_sender_(
+ event_loop->MakeSender<
+ ::frc971::control_loops::drivetrain::LocalizerControl>(
+ "/drivetrain")),
+ superstructure_goal_sender_(
+ event_loop->MakeSender<control_loops::superstructure::Goal>(
+ "/superstructure")),
+ superstructure_status_fetcher_(
+ event_loop->MakeFetcher<control_loops::superstructure::Status>(
+ "/superstructure")),
+ joystick_state_fetcher_(
+ event_loop->MakeFetcher<aos::JoystickState>("/aos")),
+ robot_state_fetcher_(event_loop->MakeFetcher<aos::RobotState>("/aos")),
+ auto_splines_() {
+ set_max_drivetrain_voltage(12.0);
+ replan_timer_ = event_loop->AddTimer([this]() { Replan(); });
+ event_loop->OnRun([this, event_loop]() {
+ replan_timer_->Setup(event_loop->monotonic_now());
+ button_poll_->Setup(event_loop->monotonic_now(), chrono::milliseconds(50));
+ });
+
+ button_poll_ = event_loop->AddTimer([this]() {
+ const aos::monotonic_clock::time_point now =
+ this->event_loop()->context().monotonic_event_time;
+ if (robot_state_fetcher_.Fetch()) {
+ if (robot_state_fetcher_->user_button()) {
+ user_indicated_safe_to_reset_ = true;
+ MaybeSendStartingPosition();
+ }
+ }
+ if (joystick_state_fetcher_.Fetch()) {
+ if (joystick_state_fetcher_->has_alliance() &&
+ (joystick_state_fetcher_->alliance() != alliance_)) {
+ alliance_ = joystick_state_fetcher_->alliance();
+ is_planned_ = false;
+ // Only kick the planning out by 2 seconds. If we end up enabled in that
+ // second, then we will kick it out further based on the code below.
+ replan_timer_->Setup(now + std::chrono::seconds(2));
+ }
+ if (joystick_state_fetcher_->enabled()) {
+ if (!is_planned_) {
+ // Only replan once we've been disabled for 5 seconds.
+ replan_timer_->Setup(now + std::chrono::seconds(5));
+ }
+ }
+ }
+ });
+}
+
+void AutonomousActor::Replan() {
+ LOG(INFO) << "Alliance " << static_cast<int>(alliance_);
+ if (alliance_ == aos::Alliance::kInvalid) {
+ return;
+ }
+ sent_starting_position_ = false;
+ if (FLAGS_spline_auto) {
+ test_spline_ =
+ PlanSpline(std::bind(&AutonomousSplines::TestSpline, &auto_splines_,
+ std::placeholders::_1, alliance_),
+ SplineDirection::kForward);
+
+ starting_position_ = test_spline_->starting_position();
+ } else if (FLAGS_rapid_react) {
+ rapid_react_splines_ = {
+ PlanSpline(std::bind(&AutonomousSplines::Spline1, &auto_splines_,
+ std::placeholders::_1, alliance_),
+ SplineDirection::kForward),
+ PlanSpline(std::bind(&AutonomousSplines::Spline2, &auto_splines_,
+ std::placeholders::_1, alliance_),
+ SplineDirection::kForward),
+ PlanSpline(std::bind(&AutonomousSplines::Spline3, &auto_splines_,
+ std::placeholders::_1, alliance_),
+ SplineDirection::kForward),
+ PlanSpline(std::bind(&AutonomousSplines::Spline4, &auto_splines_,
+ std::placeholders::_1, alliance_),
+ SplineDirection::kBackward),
+ PlanSpline(std::bind(&AutonomousSplines::Spline5, &auto_splines_,
+ std::placeholders::_1, alliance_),
+ SplineDirection::kBackward)};
+ starting_position_ = rapid_react_splines_.value()[0].starting_position();
+ CHECK(starting_position_);
+ }
+
+ is_planned_ = true;
+
+ MaybeSendStartingPosition();
+}
+
+void AutonomousActor::MaybeSendStartingPosition() {
+ if (is_planned_ && user_indicated_safe_to_reset_ &&
+ !sent_starting_position_) {
+ CHECK(starting_position_);
+ SendStartingPosition(starting_position_.value());
+ }
+}
void AutonomousActor::Reset() {
InitializeEncoders();
ResetDrivetrain();
+ RetractFrontIntake();
+ RetractBackIntake();
+
+ joystick_state_fetcher_.Fetch();
+ CHECK(joystick_state_fetcher_.get() != nullptr)
+ << "Expect at least one JoystickState message before running auto...";
+ alliance_ = joystick_state_fetcher_->alliance();
}
bool AutonomousActor::RunAction(
const ::frc971::autonomous::AutonomousActionParams *params) {
Reset();
+ if (!user_indicated_safe_to_reset_) {
+ AOS_LOG(WARNING, "Didn't send starting position prior to starting auto.");
+ CHECK(starting_position_);
+ SendStartingPosition(starting_position_.value());
+ }
+ // Clear this so that we don't accidentally resend things as soon as we replan
+ // later.
+ user_indicated_safe_to_reset_ = false;
+ is_planned_ = false;
+ starting_position_.reset();
AOS_LOG(INFO, "Params are %d\n", params->mode());
+ if (alliance_ == aos::Alliance::kInvalid) {
+ AOS_LOG(INFO, "Aborting autonomous due to invalid alliance selection.");
+ return false;
+ }
+ if (FLAGS_spline_auto) {
+ SplineAuto();
+ } else if (FLAGS_rapid_react) {
+ RapidReact();
+ }
+
return true;
}
+void AutonomousActor::SendStartingPosition(const Eigen::Vector3d &start) {
+ // Set up the starting position for the blue alliance.
+
+ // TODO(james): Resetting the localizer breaks the left/right statespace
+ // controller. That is a bug, but we can fix that later by not resetting.
+ auto builder = localizer_control_sender_.MakeBuilder();
+
+ LocalizerControl::Builder localizer_control_builder =
+ builder.MakeBuilder<LocalizerControl>();
+ localizer_control_builder.add_x(start(0));
+ localizer_control_builder.add_y(start(1));
+ localizer_control_builder.add_theta(start(2));
+ localizer_control_builder.add_theta_uncertainty(0.00001);
+ LOG(INFO) << "User button pressed, x: " << start(0) << " y: " << start(1)
+ << " theta: " << start(2);
+ if (builder.Send(localizer_control_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
+ AOS_LOG(ERROR, "Failed to reset localizer.\n");
+ }
+}
+
+void AutonomousActor::SplineAuto() {
+ CHECK(test_spline_);
+
+ if (!test_spline_->WaitForPlan()) return;
+ test_spline_->Start();
+
+ if (!test_spline_->WaitForSplineDistanceRemaining(0.02)) return;
+}
+
+void AutonomousActor::RapidReact() {
+ aos::monotonic_clock::time_point start_time = aos::monotonic_clock::now();
+
+ CHECK(rapid_react_splines_);
+
+ auto &splines = *rapid_react_splines_;
+
+ // Tell the superstructure a ball was preloaded
+
+ if (!WaitForPreloaded()) return;
+ // Drive and intake the 2nd ball
+ ExtendFrontIntake();
+ if (!splines[0].WaitForPlan()) return;
+ splines[0].Start();
+ if (!splines[0].WaitForSplineDistanceRemaining(0.02)) return;
+
+ // Fire the two balls once we stopped
+ set_fire_at_will(true);
+ SendSuperstructureGoal();
+ if (!WaitForBallsShot(2)) return;
+ set_fire_at_will(false);
+
+ // Drive and intake the 3rd ball
+ if (!splines[1].WaitForPlan()) return;
+ splines[1].Start();
+ if (!splines[1].WaitForSplineDistanceRemaining(0.02)) return;
+
+ // Fire the 3rd once we stopped.
+ set_fire_at_will(true);
+ SendSuperstructureGoal();
+ if (!WaitForBallsShot(1)) return;
+ set_fire_at_will(false);
+
+ // Drive to the human player station while intaking two balls.
+ // Once is already placed down,
+ // and one will be rolled to the robot by the human player
+ if (!splines[2].WaitForPlan()) return;
+ splines[2].Start();
+ if (!splines[2].WaitForSplineDistanceRemaining(0.02)) return;
+
+ // Drive to the shooting position
+ if (!splines[3].WaitForPlan()) return;
+ splines[3].Start();
+ if (!splines[3].WaitForSplineDistanceRemaining(0.02)) return;
+
+ // Fire the two balls once we stopped
+ set_fire_at_will(true);
+ SendSuperstructureGoal();
+ if (!WaitForBallsShot(2)) return;
+ set_fire_at_will(false);
+
+ // Done intaking
+ RetractFrontIntake();
+
+ // Drive to the middle of the field to get ready for teleop
+ if (!splines[4].WaitForPlan()) return;
+ splines[4].Start();
+ if (!splines[4].WaitForSplineDistanceRemaining(0.02)) return;
+
+ LOG(INFO) << "Took "
+ << chrono::duration<double>(aos::monotonic_clock::now() -
+ start_time)
+ .count()
+ << 's';
+}
+
+[[nodiscard]] bool AutonomousActor::WaitForPreloaded() {
+ set_preloaded(true);
+ SendSuperstructureGoal();
+
+ ::aos::time::PhasedLoop phased_loop(frc971::controls::kLoopFrequency,
+ event_loop()->monotonic_now(),
+ ActorBase::kLoopOffset);
+
+ bool loaded = false;
+ while (!loaded) {
+ if (ShouldCancel()) {
+ return false;
+ }
+
+ phased_loop.SleepUntilNext();
+ superstructure_status_fetcher_.Fetch();
+ CHECK(superstructure_status_fetcher_.get() != nullptr);
+
+ loaded = (superstructure_status_fetcher_->state() ==
+ control_loops::superstructure::SuperstructureState::LOADED);
+ }
+
+ set_preloaded(false);
+ SendSuperstructureGoal();
+
+ return true;
+}
+
+void AutonomousActor::SendSuperstructureGoal() {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+
+ flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
+ intake_front_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *builder.fbb(), intake_front_goal_,
+ CreateProfileParameters(*builder.fbb(), 20.0, 60.0));
+
+ flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
+ intake_back_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *builder.fbb(), intake_back_goal_,
+ CreateProfileParameters(*builder.fbb(), 20.0, 60.0));
+
+ flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
+ catapult_return_position_offset =
+ CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *builder.fbb(), kCatapultReturnPosition,
+ CreateProfileParameters(*builder.fbb(), 9.0, 50.0));
+
+ superstructure::CatapultGoal::Builder catapult_goal_builder(*builder.fbb());
+ catapult_goal_builder.add_shot_position(0.03);
+ catapult_goal_builder.add_shot_velocity(18.0);
+ catapult_goal_builder.add_return_position(catapult_return_position_offset);
+ flatbuffers::Offset<superstructure::CatapultGoal> catapult_goal_offset =
+ catapult_goal_builder.Finish();
+
+ superstructure::Goal::Builder superstructure_builder =
+ builder.MakeBuilder<superstructure::Goal>();
+
+ superstructure_builder.add_intake_front(intake_front_offset);
+ superstructure_builder.add_intake_back(intake_back_offset);
+ superstructure_builder.add_roller_speed_compensation(1.5);
+ superstructure_builder.add_roller_speed_front(roller_front_voltage_);
+ superstructure_builder.add_roller_speed_back(roller_back_voltage_);
+ superstructure_builder.add_transfer_roller_speed_front(
+ transfer_roller_front_voltage_);
+ superstructure_builder.add_transfer_roller_speed_back(
+ transfer_roller_back_voltage_);
+ superstructure_builder.add_catapult(catapult_goal_offset);
+ superstructure_builder.add_fire(fire_);
+ superstructure_builder.add_preloaded(preloaded_);
+ superstructure_builder.add_auto_aim(true);
+
+ if (builder.Send(superstructure_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
+ AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
+ }
+}
+
+void AutonomousActor::ExtendFrontIntake() {
+ set_intake_front_goal(kExtendIntakeGoal);
+ set_roller_front_voltage(kRollerVoltage);
+ set_transfer_roller_front_voltage(kRollerVoltage);
+ set_transfer_roller_back_voltage(-kRollerVoltage);
+ SendSuperstructureGoal();
+}
+
+void AutonomousActor::RetractFrontIntake() {
+ set_intake_front_goal(kRetractIntakeGoal);
+ set_roller_front_voltage(kRollerVoltage);
+ set_transfer_roller_front_voltage(0.0);
+ set_transfer_roller_back_voltage(0.0);
+ SendSuperstructureGoal();
+}
+
+void AutonomousActor::ExtendBackIntake() {
+ set_intake_back_goal(kExtendIntakeGoal);
+ set_roller_back_voltage(kRollerVoltage);
+ set_transfer_roller_back_voltage(kRollerVoltage);
+ set_transfer_roller_front_voltage(-kRollerVoltage);
+ SendSuperstructureGoal();
+}
+
+void AutonomousActor::RetractBackIntake() {
+ set_intake_back_goal(kRetractIntakeGoal);
+ set_roller_back_voltage(kRollerVoltage);
+ set_transfer_roller_front_voltage(0.0);
+ set_transfer_roller_back_voltage(0.0);
+ SendSuperstructureGoal();
+}
+
+[[nodiscard]] bool AutonomousActor::WaitForBallsShot(int num_wanted) {
+ ::aos::time::PhasedLoop phased_loop(frc971::controls::kLoopFrequency,
+ event_loop()->monotonic_now(),
+ ActorBase::kLoopOffset);
+ superstructure_status_fetcher_.Fetch();
+ CHECK(superstructure_status_fetcher_.get() != nullptr);
+ int initial_balls = superstructure_status_fetcher_->shot_count();
+ LOG(INFO) << "Waiting for balls, started with " << initial_balls;
+ while (true) {
+ if (ShouldCancel()) {
+ return false;
+ }
+ phased_loop.SleepUntilNext();
+ superstructure_status_fetcher_.Fetch();
+ CHECK(superstructure_status_fetcher_.get() != nullptr);
+ if (superstructure_status_fetcher_->shot_count() - initial_balls >=
+ num_wanted) {
+ return true;
+ }
+ }
+}
+
} // namespace actors
} // namespace y2022
diff --git a/y2022/actors/autonomous_actor.h b/y2022/actors/autonomous_actor.h
index ca13d38..3286f10 100644
--- a/y2022/actors/autonomous_actor.h
+++ b/y2022/actors/autonomous_actor.h
@@ -6,10 +6,18 @@
#include "frc971/autonomous/base_autonomous_actor.h"
#include "frc971/control_loops/control_loops_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+#include "frc971/control_loops/drivetrain/localizer_generated.h"
+#include "y2022/actors/auto_splines.h"
+#include "y2022/control_loops/superstructure/superstructure_goal_generated.h"
+#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
namespace y2022 {
namespace actors {
+using frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
+
+namespace superstructure = y2022::control_loops::superstructure;
+
class AutonomousActor : public ::frc971::autonomous::BaseAutonomousActor {
public:
explicit AutonomousActor(::aos::EventLoop *event_loop);
@@ -19,6 +27,80 @@
private:
void Reset();
+
+ void set_intake_front_goal(double intake_front_goal) {
+ intake_front_goal_ = intake_front_goal;
+ }
+ void set_intake_back_goal(double intake_back_goal) {
+ intake_back_goal_ = intake_back_goal;
+ }
+ void set_roller_front_voltage(double roller_front_voltage) {
+ roller_front_voltage_ = roller_front_voltage;
+ }
+ void set_roller_back_voltage(double roller_back_voltage) {
+ roller_back_voltage_ = roller_back_voltage;
+ }
+ void set_transfer_roller_front_voltage(double voltage) {
+ transfer_roller_front_voltage_ = voltage;
+ }
+ void set_transfer_roller_back_voltage(double voltage) {
+ transfer_roller_back_voltage_ = voltage;
+ }
+
+ void set_fire_at_will(bool fire) { fire_ = fire; }
+ void set_preloaded(bool preloaded) { preloaded_ = preloaded; }
+
+ void SendSuperstructureGoal();
+ void ExtendFrontIntake();
+ void RetractFrontIntake();
+ void ExtendBackIntake();
+ void RetractBackIntake();
+ void SendStartingPosition(const Eigen::Vector3d &start);
+ void MaybeSendStartingPosition();
+
+ // Tells the superstructure the ball was preloaded and waits until it updates
+ // the state
+ [[nodiscard]] bool WaitForPreloaded();
+ // Waits for a certain number of balls to be shot
+ [[nodiscard]] bool WaitForBallsShot(int num_shot);
+
+ void SplineAuto();
+ void RapidReact();
+
+ void Replan();
+
+ double intake_front_goal_ = 0.0;
+ double intake_back_goal_ = 0.0;
+ double roller_front_voltage_ = 0.0;
+ double roller_back_voltage_ = 0.0;
+ double transfer_roller_front_voltage_ = 0.0;
+ double transfer_roller_back_voltage_ = 0.0;
+ bool fire_ = false;
+ bool preloaded_ = false;
+
+ aos::Sender<frc971::control_loops::drivetrain::LocalizerControl>
+ localizer_control_sender_;
+ aos::Sender<y2022::control_loops::superstructure::Goal>
+ superstructure_goal_sender_;
+ aos::Fetcher<y2022::control_loops::superstructure::Status>
+ superstructure_status_fetcher_;
+ aos::Fetcher<aos::JoystickState> joystick_state_fetcher_;
+ aos::Fetcher<aos::RobotState> robot_state_fetcher_;
+
+ aos::TimerHandler *replan_timer_;
+ aos::TimerHandler *button_poll_;
+
+ std::optional<SplineHandle> test_spline_;
+ std::optional<std::array<SplineHandle, 5>> rapid_react_splines_;
+
+ aos::Alliance alliance_ = aos::Alliance::kInvalid;
+ AutonomousSplines auto_splines_;
+ bool user_indicated_safe_to_reset_ = false;
+ bool sent_starting_position_ = false;
+
+ bool is_planned_ = false;
+
+ std::optional<Eigen::Vector3d> starting_position_;
};
} // namespace actors
diff --git a/y2022/actors/splines/README.md b/y2022/actors/splines/README.md
new file mode 100644
index 0000000..c655416
--- /dev/null
+++ b/y2022/actors/splines/README.md
@@ -0,0 +1,3 @@
+# Spline Descriptions
+This folder contains reference material for what each spline does
+
diff --git a/y2022/actors/splines/spline_1.json b/y2022/actors/splines/spline_1.json
new file mode 100644
index 0000000..861666f
--- /dev/null
+++ b/y2022/actors/splines/spline_1.json
@@ -0,0 +1 @@
+{"spline_count": 2, "spline_x": [-0.2256402886254385, -0.24061367759192365, -0.28728163091905445, 0.1786412134696551, 0.30022168717049524, 0.6726955312497593, 1.0451693753290234, 1.6685365897867115, 2.269065889291825, 2.438724256360172, 2.628171375352151], "spline_y": [2.3309349464975493, 2.6154293368607635, 2.9503640153538404, 3.66356656451471, 3.5787923664108376, 3.5787923664108376, 3.5787923664108376, 3.66356656451471, 3.517591006104223, 3.241928074677876, 2.979616679150519], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2}, {"constraint_type": "VOLTAGE", "value": 10}]}
\ No newline at end of file
diff --git a/y2022/actors/splines/spline_2.json b/y2022/actors/splines/spline_2.json
new file mode 100644
index 0000000..f261325
--- /dev/null
+++ b/y2022/actors/splines/spline_2.json
@@ -0,0 +1 @@
+{"spline_count": 1, "spline_x": [2.628171375352151, 2.7183463717109815, 2.769386307986923, 2.963347047414885, 3.0216384686431867, 3.313095574784694], "spline_y": [2.979616679150519, 2.8646708974512585, 2.7753740109934886, 2.5570038752453335, 2.2218282031826, 2.148963926647223], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2}, {"constraint_type": "VOLTAGE", "value": 10}]}
\ No newline at end of file
diff --git a/y2022/actors/splines/spline_3.json b/y2022/actors/splines/spline_3.json
new file mode 100644
index 0000000..c5bcdb8
--- /dev/null
+++ b/y2022/actors/splines/spline_3.json
@@ -0,0 +1 @@
+{"spline_count": 1, "spline_x": [3.313095574784694, 4.157153183357088, 5.650873561635817, 6.001252415799964, 6.333190277639684, 6.720451116452686], "spline_y": [2.148963926647223, 1.9988483070418415, 2.2385812072594153, 2.5520780767747038, 2.699606015370134, 2.847133953965564], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2}, {"constraint_type": "VOLTAGE", "value": 10}]}
diff --git a/y2022/actors/splines/spline_4.json b/y2022/actors/splines/spline_4.json
new file mode 100644
index 0000000..d9e872f
--- /dev/null
+++ b/y2022/actors/splines/spline_4.json
@@ -0,0 +1 @@
+{"spline_count": 1, "spline_x": [6.720451116452686, 5.982811423475535, 5.766318367346939, 4.702628571428573, 3.5269714285714286, 3.313095574784694], "spline_y": [2.847133953965564, 2.5520780767747038, 2.435289795918367, 1.4275836734693876, 1.9874204081632652, 2.148963926647223], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2}, {"constraint_type": "VOLTAGE", "value": 10}]}
\ No newline at end of file
diff --git a/y2022/actors/splines/spline_5.json b/y2022/actors/splines/spline_5.json
new file mode 100644
index 0000000..a37911b
--- /dev/null
+++ b/y2022/actors/splines/spline_5.json
@@ -0,0 +1 @@
+{"spline_count": 1, "spline_x": [3.313095574784694, 2.4072979591836745, 1.5115591836734694, 0.6718056340400533, -0.48997688239895876, -0.821914744238676], "spline_y": [2.148963926647223, 2.911151020408163, 3.638938775510204, 3.381922731373998, 3.5663326546182854, 3.5663326546182854], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 3}, {"constraint_type": "LATERAL_ACCELERATION", "value": 2}, {"constraint_type": "VOLTAGE", "value": 10}]}
\ No newline at end of file
diff --git a/y2022/actors/splines/test_spline.json b/y2022/actors/splines/test_spline.json
new file mode 100644
index 0000000..733d516
--- /dev/null
+++ b/y2022/actors/splines/test_spline.json
@@ -0,0 +1 @@
+{"spline_count": 1, "spline_x": [0, 0.4, 0.4, 0.6, 0.6, 1.0], "spline_y": [0, 0, 0.05, 0.1, 0.15, 0.15], "constraints": [{"constraint_type": "LONGITUDINAL_ACCELERATION", "value": 1}, {"constraint_type": "LATERAL_ACCELERATION", "value": 1}, {"constraint_type": "VOLTAGE", "value": 2}]}
diff --git a/y2022/constants.cc b/y2022/constants.cc
index 1ec0349..2e7c5a9 100644
--- a/y2022/constants.cc
+++ b/y2022/constants.cc
@@ -68,7 +68,7 @@
auto *const turret_params = &turret->subsystem_params;
turret_params->zeroing_voltage = 4.0;
- turret_params->operating_voltage = 8.0;
+ turret_params->operating_voltage = 12.0;
turret_params->zeroing_profile_params = {0.5, 2.0};
turret_params->default_profile_params = {15.0, 40.0};
turret_params->range = Values::kTurretRange();
@@ -101,8 +101,8 @@
flipper_arms.subsystem_params.default_profile_params = {6.0, 1.0};
flipper_arms.subsystem_params.range = Values::kFlipperArmRange();
- auto *const flipper_arm_right = &r.flipper_arm_left;
- auto *const flipper_arm_left = &r.flipper_arm_right;
+ auto *const flipper_arm_right = &r.flipper_arm_right;
+ auto *const flipper_arm_left = &r.flipper_arm_left;
*flipper_arm_right = flipper_arms;
*flipper_arm_left = flipper_arms;
@@ -130,9 +130,20 @@
catapult_params->zeroing_constants.moving_buffer_size = 20;
catapult_params->zeroing_constants.allowable_encoder_error = 0.9;
+ // Interpolation table for comp and practice robots
+ r.shot_interpolation_table = InterpolationTable<Values::ShotParams>({
+ {2, {0.08, 8.0}},
+ {5, {0.6, 10.0}},
+ });
+
switch (team) {
// A set of constants for tests.
case 1:
+ r.shot_interpolation_table = InterpolationTable<Values::ShotParams>({
+ {2, {0.08, 8.0}},
+ {5, {0.6, 10.0}},
+ });
+
climber->potentiometer_offset = 0.0;
intake_front->potentiometer_offset = 0.0;
intake_front->subsystem_params.zeroing_constants
@@ -152,20 +163,26 @@
case kCompTeamNumber:
climber->potentiometer_offset = 0.0;
- intake_front->potentiometer_offset = 0.0;
- intake_front->subsystem_params.zeroing_constants
- .measured_absolute_position = 0.0;
- intake_back->potentiometer_offset = 0.0;
- intake_back->subsystem_params.zeroing_constants
- .measured_absolute_position = 0.0;
- turret->potentiometer_offset = 0.0;
- turret->subsystem_params.zeroing_constants.measured_absolute_position =
- 0.0;
- flipper_arm_left->potentiometer_offset = 0.0;
- flipper_arm_right->potentiometer_offset = 0.0;
- catapult_params->zeroing_constants.measured_absolute_position = 0.0;
- catapult->potentiometer_offset = 0.0;
+ intake_front->potentiometer_offset = 2.79628370453323;
+ intake_front->subsystem_params.zeroing_constants
+ .measured_absolute_position = 0.248921954833972;
+
+ intake_back->potentiometer_offset = 3.1409576474047;
+ intake_back->subsystem_params.zeroing_constants
+ .measured_absolute_position = 0.280099007470002;
+
+ turret->potentiometer_offset = -9.99970387166721 + 0.06415943 +
+ 0.073290115367682 - 0.0634440443622909;
+ turret->subsystem_params.zeroing_constants.measured_absolute_position =
+ 0.568649928102931;
+
+ flipper_arm_left->potentiometer_offset = -6.4;
+ flipper_arm_right->potentiometer_offset = 5.56;
+
+ catapult_params->zeroing_constants.measured_absolute_position =
+ 1.71723370408082;
+ catapult->potentiometer_offset = -2.03383240293769;
break;
case kPracticeTeamNumber:
@@ -187,6 +204,11 @@
break;
case kCodingRobotTeamNumber:
+ r.shot_interpolation_table = InterpolationTable<Values::ShotParams>({
+ {2, {0.08, 8.0}},
+ {5, {0.6, 10.0}},
+ });
+
climber->potentiometer_offset = 0.0;
intake_front->potentiometer_offset = 0.0;
intake_front->subsystem_params.zeroing_constants
diff --git a/y2022/constants.h b/y2022/constants.h
index fc9083a..21ea7a4 100644
--- a/y2022/constants.h
+++ b/y2022/constants.h
@@ -8,12 +8,15 @@
#include "frc971/constants.h"
#include "frc971/control_loops/pose.h"
#include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h"
+#include "frc971/shooter_interpolation/interpolation.h"
#include "y2022/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
#include "y2022/control_loops/superstructure/catapult/catapult_plant.h"
#include "y2022/control_loops/superstructure/climber/climber_plant.h"
#include "y2022/control_loops/superstructure/intake/intake_plant.h"
#include "y2022/control_loops/superstructure/turret/turret_plant.h"
+using ::frc971::shooter_interpolation::InterpolationTable;
+
namespace y2022 {
namespace constants {
@@ -63,7 +66,7 @@
static constexpr double kIntakeEncoderCountsPerRevolution() { return 4096.0; }
static constexpr double kIntakeEncoderRatio() {
- return (16.0 / 64.0) * (20.0 / 50.0);
+ return (16.0 / 64.0) * (18.0 / 62.0);
}
static constexpr double kIntakePotRatio() { return 16.0 / 64.0; }
@@ -87,10 +90,10 @@
// TODO (Yash): Constants need to be tuned
static constexpr ::frc971::constants::Range kIntakeRange() {
return ::frc971::constants::Range{
- .lower_hard = -0.5, // Back Hard
- .upper_hard = 2.85 + 0.05, // Front Hard
- .lower = -0.300, // Back Soft
- .upper = 2.725 // Front Soft
+ .lower_hard = -0.85, // Back Hard
+ .upper_hard = 1.85, // Front Hard
+ .lower = -0.400, // Back Soft
+ .upper = 1.57 // Front Soft
};
}
@@ -98,20 +101,28 @@
static constexpr double kIntakeRollerSupplyCurrentLimit() { return 40.0; }
static constexpr double kIntakeRollerStatorCurrentLimit() { return 60.0; }
+ // Transfer rollers
+ static constexpr double kTransferRollerVoltage() { return 12.0; }
+
+ // Voltage to wiggle the transfer rollers and keep a ball in.
+ static constexpr double kTransferRollerWiggleVoltage() { return 3.0; }
+
// Turret
PotAndAbsEncoderConstants turret;
// TODO (Yash): Constants need to be tuned
static constexpr ::frc971::constants::Range kTurretRange() {
return ::frc971::constants::Range{
- .lower_hard = -0.1, // Back Hard
- .upper_hard = 4.71, // Front Hard
- .lower = 0.0, // Back Soft
+ .lower_hard = -6.0, // Back Hard
+ .upper_hard = 4.0, // Front Hard
+ .lower = -5.0, // Back Soft
.upper = 3.3 // Front Soft
};
}
- // Turret
+ static constexpr double kTurretBackIntakePos() { return M_PI; }
+ static constexpr double kTurretFrontIntakePos() { return 0; }
+
static constexpr double kTurretPotRatio() { return 27.0 / 110.0; }
static constexpr double kTurretEncoderRatio() { return kTurretPotRatio(); }
static constexpr double kTurretEncoderCountsPerRevolution() { return 4096.0; }
@@ -123,14 +134,47 @@
}
// Flipper arms
- static constexpr double kFlipperArmSupplyCurrentLimit() { return 30.0; }
- static constexpr double kFlipperArmStatorCurrentLimit() { return 40.0; }
+ static constexpr double kFlipperArmSupplyCurrentLimit() { return 40.0; }
+ static constexpr double kFlipperArmStatorCurrentLimit() { return 60.0; }
+
+ // Voltage to open the flippers for firing
+ static constexpr double kFlipperOpenVoltage() { return 3.0; }
+ // Voltage to keep the flippers open for firing once they already are
+ static constexpr double kFlipperHoldVoltage() { return 2.5; }
+ // Voltage to feed a ball from the transfer rollers to the catpult with the
+ // flippers
+ static constexpr double kFlipperFeedVoltage() { return -12.0; }
+
+ // Ball is fed into catapult for atleast this time no matter what
+ static constexpr std::chrono::milliseconds kExtraLoadingTime() {
+ return std::chrono::milliseconds(100);
+ }
+ // If we have been trying to transfer the ball for this amount of time, it
+ // probably got lost so abort
+ static constexpr std::chrono::seconds kBallLostTime() {
+ return std::chrono::seconds(2);
+ }
+ // If the flippers took more than this amount of time to open for firing,
+ // reseat the ball
+ static constexpr std::chrono::milliseconds kFlipperOpeningTimeout() {
+ return std::chrono::milliseconds(1000);
+ }
+ // Don't use flipper velocity readings more than this amount of time in the
+ // past
+ static constexpr std::chrono::milliseconds kFlipperVelocityValidTime() {
+ return std::chrono::milliseconds(100);
+ }
// TODO: (Griffin) this needs to be set
static constexpr ::frc971::constants::Range kFlipperArmRange() {
return ::frc971::constants::Range{
- .lower_hard = -0.01, .upper_hard = 0.6, .lower = 0.0, .upper = 0.5};
+ .lower_hard = -0.01, .upper_hard = 0.4, .lower = 0.0, .upper = 0.5};
}
+ // Position of the flippers when they are open
+ static constexpr double kFlipperOpenPosition() { return 0.20; }
+ // If the flippers were open but now moved back, reseat the ball if they go
+ // below this position
+ static constexpr double kReseatFlipperPosition() { return 0.1; }
static constexpr double kFlipperArmsPotRatio() { return 16.0 / 36.0; }
@@ -153,14 +197,34 @@
}
static constexpr ::frc971::constants::Range kCatapultRange() {
return ::frc971::constants::Range{
- .lower_hard = -1.2,
+ .lower_hard = -1.0,
.upper_hard = 2.0,
- .lower = -1.00,
+ .lower = -0.91,
.upper = 1.57,
};
}
PotAndAbsEncoderConstants catapult;
+
+ // TODO(milind): set this
+ static constexpr double kImuHeight() { return 0.0; }
+
+ struct ShotParams {
+ // Measured in radians
+ double shot_angle;
+ // Muzzle velocity (m/s) of the ball as it is released from the catapult.
+ double shot_velocity;
+
+ static ShotParams BlendY(double coefficient, ShotParams a1, ShotParams a2) {
+ using ::frc971::shooter_interpolation::Blend;
+ return ShotParams{
+ Blend(coefficient, a1.shot_angle, a2.shot_angle),
+ Blend(coefficient, a1.shot_velocity, a2.shot_velocity),
+ };
+ }
+ };
+
+ InterpolationTable<ShotParams> shot_interpolation_table;
};
// Creates and returns a Values instance for the constants.
diff --git a/y2022/control_loops/drivetrain/drivetrain_base.cc b/y2022/control_loops/drivetrain/drivetrain_base.cc
index 1a76afc..f18ebf2 100644
--- a/y2022/control_loops/drivetrain/drivetrain_base.cc
+++ b/y2022/control_loops/drivetrain/drivetrain_base.cc
@@ -24,7 +24,7 @@
const DrivetrainConfig<double> &GetDrivetrainConfig() {
// Yaw of the IMU relative to the robot frame.
- static constexpr double kImuYaw = -M_PI_2 + 0.15;
+ static constexpr double kImuYaw = 0.0;
static DrivetrainConfig<double> kDrivetrainConfig{
::frc971::control_loops::drivetrain::ShifterType::SIMPLE_SHIFTER,
::frc971::control_loops::drivetrain::LoopType::CLOSED_LOOP,
diff --git a/y2022/control_loops/drivetrain/localizer.cc b/y2022/control_loops/drivetrain/localizer.cc
index 3d02312..0735534 100644
--- a/y2022/control_loops/drivetrain/localizer.cc
+++ b/y2022/control_loops/drivetrain/localizer.cc
@@ -71,8 +71,15 @@
monotonic_offset);
// TODO: Finish implementing simple x/y/theta updater with state_at_capture.
// TODO: Implement turret/camera processing logic on pi side.
- const std::optional<State> state_at_capture =
+ std::optional<State> state_at_capture =
ekf_.LastStateBeforeTime(capture_time);
+ if (!state_at_capture.has_value()) {
+ state_at_capture = ekf_.OldestState();
+ if (!state_at_capture.has_value()) {
+ return;
+ }
+ }
+
Eigen::Matrix<float, HybridEkf::kNOutputs, HybridEkf::kNStates> H;
H.setZero();
H(0, StateIdx::kX) = 1;
diff --git a/y2022/control_loops/python/catapult.py b/y2022/control_loops/python/catapult.py
index ce7496a..2d0588a 100755
--- a/y2022/control_loops/python/catapult.py
+++ b/y2022/control_loops/python/catapult.py
@@ -41,25 +41,25 @@
J_cup = M_cup * lever**2.0 + M_cup * (ball_diameter / 2.)**2.0
-J = (J_ball + J_bar + J_cup * 1.5)
-JEmpty = (J_bar + J_cup * 1.5)
+J = (0.6 * J_ball + J_bar + J_cup * 0.0)
+JEmpty = (J_bar + J_cup * 0.0)
kCatapultWithBall = catapult_lib.CatapultParams(
name='Catapult',
- motor=AddResistance(control_loop.NMotor(control_loop.Falcon(), 2), 0.03),
+ motor=AddResistance(control_loop.NMotor(control_loop.Falcon(), 2), 0.01),
G=G,
J=J,
radius=lever,
q_pos=2.8,
q_vel=20.0,
- kalman_q_pos=0.12,
+ kalman_q_pos=0.01,
kalman_q_vel=1.0,
kalman_q_voltage=1.5,
- kalman_r_position=0.05)
+ kalman_r_position=0.001)
kCatapultEmpty = catapult_lib.CatapultParams(
name='Catapult',
- motor=AddResistance(control_loop.NMotor(control_loop.Falcon(), 2), 0.03),
+ motor=AddResistance(control_loop.NMotor(control_loop.Falcon(), 2), 0.02),
G=G,
J=JEmpty,
radius=lever,
diff --git a/y2022/control_loops/superstructure/BUILD b/y2022/control_loops/superstructure/BUILD
index 57b37f3..4739cd1 100644
--- a/y2022/control_loops/superstructure/BUILD
+++ b/y2022/control_loops/superstructure/BUILD
@@ -77,15 +77,18 @@
],
deps = [
":collision_avoidance_lib",
+ ":superstructure_can_position_fbs",
":superstructure_goal_fbs",
":superstructure_output_fbs",
":superstructure_position_fbs",
":superstructure_status_fbs",
+ "//aos:flatbuffer_merge",
"//aos/events:event_loop",
"//frc971/control_loops:control_loop",
"//frc971/control_loops/drivetrain:drivetrain_status_fbs",
"//y2022:constants",
"//y2022/control_loops/superstructure/catapult",
+ "//y2022/control_loops/superstructure/turret:aiming",
],
)
diff --git a/y2022/control_loops/superstructure/catapult/catapult.cc b/y2022/control_loops/superstructure/catapult/catapult.cc
index e4d76d3..8b5c7eb 100644
--- a/y2022/control_loops/superstructure/catapult/catapult.cc
+++ b/y2022/control_loops/superstructure/catapult/catapult.cc
@@ -23,7 +23,7 @@
instance.constraint_matrix =
Eigen::SparseMatrix<double, Eigen::ColMajor, osqp::c_int>(horizon,
- horizon);
+ horizon);
instance.constraint_matrix.setIdentity();
instance.lower_bounds =
@@ -312,27 +312,29 @@
const flatbuffers::Offset<
frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus>
-Catapult::Iterate(const Goal *unsafe_goal, const Position *position,
- double *catapult_voltage,
+Catapult::Iterate(const CatapultGoal *catapult_goal, const Position *position,
+ double battery_voltage, double *catapult_voltage, bool fire,
flatbuffers::FlatBufferBuilder *fbb) {
const frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal
- *catapult_goal = unsafe_goal != nullptr && unsafe_goal->has_catapult()
- ? (unsafe_goal->catapult()->return_position())
- : nullptr;
+ *return_goal =
+ catapult_goal != nullptr && catapult_goal->has_return_position()
+ ? catapult_goal->return_position()
+ : nullptr;
const bool catapult_disabled = catapult_.Correct(
- catapult_goal, position->catapult(), catapult_voltage == nullptr);
+ return_goal, position->catapult(), catapult_voltage == nullptr);
if (catapult_disabled) {
catapult_state_ = CatapultState::PROFILE;
- } else if (catapult_.running() && unsafe_goal &&
- unsafe_goal->has_catapult() && unsafe_goal->catapult()->fire() &&
+ } else if (catapult_.running() && catapult_goal != nullptr && fire &&
!last_firing_) {
catapult_state_ = CatapultState::FIRING;
+ latched_shot_position = catapult_goal->shot_position();
+ latched_shot_velocity = catapult_goal->shot_velocity();
}
- if (catapult_.running() && unsafe_goal && unsafe_goal->has_catapult()) {
- last_firing_ = unsafe_goal->catapult()->fire();
+ if (catapult_.running()) {
+ last_firing_ = fire;
}
use_profile_ = true;
@@ -355,8 +357,7 @@
catapult_mpc_.SetState(
next_X.block<2, 1>(0, 0),
- Eigen::Vector2d(unsafe_goal->catapult()->shot_position(),
- unsafe_goal->catapult()->shot_velocity()));
+ Eigen::Vector2d(latched_shot_position, latched_shot_velocity));
const bool solved = catapult_mpc_.Solve();
@@ -374,27 +375,34 @@
} else {
// TODO(austin): Voltage error?
CHECK_NOTNULL(catapult_voltage);
- *catapult_voltage =
- std::max(0.0, std::min(12.0, *solution - 0.0 * next_X(2, 0)));
+ *catapult_voltage = std::max(
+ 0.0, std::min(12.0, (*solution - 0.0 * next_X(2, 0)) * 12.0 /
+ std::max(battery_voltage, 8.0)));
use_profile_ = false;
}
} else {
- if (unsafe_goal && unsafe_goal->has_catapult() &&
- !unsafe_goal->catapult()->fire()) {
+ if (!fire) {
// Eh, didn't manage to solve before it was time to fire. Give up.
catapult_state_ = CatapultState::PROFILE;
}
}
- if (!use_profile_ || catapult_state_ == CatapultState::RESETTING) {
+ if (!use_profile_) {
catapult_.ForceGoal(catapult_.estimated_position(),
catapult_.estimated_velocity());
}
- } break;
+ }
+ if (catapult_state_ != CatapultState::RESETTING) {
+ break;
+ } else {
+ [[fallthrough]];
+ }
case CatapultState::RESETTING:
- if (catapult_.controller().R(1, 0) > 0.0) {
- catapult_.AdjustProfile(7.0, 500.0);
+ if (catapult_.controller().R(1, 0) > 7.0) {
+ catapult_.AdjustProfile(7.0, 2000.0);
+ } else if (catapult_.controller().R(1, 0) > 0.0) {
+ catapult_.AdjustProfile(7.0, 1000.0);
} else {
catapult_state_ = CatapultState::PROFILE;
}
@@ -417,7 +425,9 @@
}
}
- catapult_.UpdateObserver(catapult_voltage != nullptr ? *catapult_voltage : 0.0);
+ catapult_.UpdateObserver(catapult_voltage != nullptr
+ ? (*catapult_voltage * battery_voltage / 12.0)
+ : 0.0);
return catapult_.MakeStatus(fbb);
}
diff --git a/y2022/control_loops/superstructure/catapult/catapult.h b/y2022/control_loops/superstructure/catapult/catapult.h
index a8141a0..6a2c834 100644
--- a/y2022/control_loops/superstructure/catapult/catapult.h
+++ b/y2022/control_loops/superstructure/catapult/catapult.h
@@ -192,6 +192,8 @@
// Resets all state for when WPILib restarts.
void Reset() { catapult_.Reset(); }
+ void Estop() { catapult_.Estop(); }
+
bool zeroed() const { return catapult_.zeroed(); }
bool estopped() const { return catapult_.estopped(); }
double solve_time() const { return catapult_mpc_.solve_time(); }
@@ -201,17 +203,18 @@
// Returns the number of shots taken.
int shot_count() const { return shot_count_; }
+ // Returns the estimated position
+ double estimated_position() const { return catapult_.estimated_position(); }
+
// Runs either the MPC or the profiled subsystem depending on if we are
// shooting or not. Returns the status.
const flatbuffers::Offset<
frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus>
- Iterate(const Goal *unsafe_goal, const Position *position,
- double *catapult_voltage, flatbuffers::FlatBufferBuilder *fbb);
+ Iterate(const CatapultGoal *unsafe_goal, const Position *position,
+ double battery_voltage, double *catapult_voltage, bool fire,
+ flatbuffers::FlatBufferBuilder *fbb);
private:
- // TODO(austin): Prototype is just an encoder. Catapult has both an encoder
- // and pot. Switch back once we have a catapult.
- // PotAndAbsoluteEncoderSubsystem catapult_;
PotAndAbsoluteEncoderSubsystem catapult_;
catapult::CatapultController catapult_mpc_;
@@ -220,6 +223,9 @@
CatapultState catapult_state_ = CatapultState::PROFILE;
+ double latched_shot_position = 0.0;
+ double latched_shot_velocity = 0.0;
+
bool last_firing_ = false;
bool use_profile_ = true;
diff --git a/y2022/control_loops/superstructure/collision_avoidance.cc b/y2022/control_loops/superstructure/collision_avoidance.cc
index 5d0fe27..0c13295 100644
--- a/y2022/control_loops/superstructure/collision_avoidance.cc
+++ b/y2022/control_loops/superstructure/collision_avoidance.cc
@@ -33,6 +33,25 @@
return true;
}
+ // If we aren't firing, no need to check the catapult
+ if (!status.shooting) {
+ return false;
+ }
+
+ // Checks if intake front is collided with catapult.
+ if (TurretCollided(
+ status.intake_front_position, status.turret_position + M_PI,
+ kMinCollisionZoneFrontTurret, kMaxCollisionZoneFrontTurret)) {
+ return true;
+ }
+
+ // Checks if intake back is collided with catapult.
+ if (TurretCollided(status.intake_back_position, status.turret_position + M_PI,
+ kMinCollisionZoneBackTurret,
+ kMaxCollisionZoneBackTurret)) {
+ return true;
+ }
+
return false;
}
@@ -47,6 +66,12 @@
return wrapped + 2.0 * M_PI * wraps;
}
+bool AngleInRange(double theta, double theta_min, double theta_max) {
+ return (
+ (theta >= theta_min && theta <= theta_max) ||
+ (theta_min > theta_max && (theta >= theta_min || theta <= theta_max)));
+}
+
bool CollisionAvoidance::TurretCollided(double intake_position,
double turret_position,
double min_turret_collision_position,
@@ -55,10 +80,10 @@
const double turret_position_wrapped = turret_position_wrapped_pair.first;
// Checks if turret is in the collision area.
- if (turret_position_wrapped >= min_turret_collision_position &&
- turret_position_wrapped <= max_turret_collision_position) {
+ if (AngleInRange(turret_position_wrapped, min_turret_collision_position,
+ max_turret_collision_position)) {
// Reterns true if the intake is raised.
- if (intake_position <= kCollisionZoneIntake) {
+ if (intake_position > kCollisionZoneIntake) {
return true;
}
} else {
@@ -67,8 +92,10 @@
return false;
}
-void CollisionAvoidance::UpdateGoal(const CollisionAvoidance::Status &status,
- const Goal *unsafe_goal) {
+void CollisionAvoidance::UpdateGoal(
+ const CollisionAvoidance::Status &status,
+ const frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal
+ *unsafe_turret_goal) {
// Start with our constraints being wide open.
clear_max_turret_goal();
clear_min_turret_goal();
@@ -81,36 +108,54 @@
const double intake_back_position = status.intake_back_position;
const double turret_position = status.turret_position;
- const double turret_goal =
- (unsafe_goal != nullptr && unsafe_goal->turret() != nullptr
- ? unsafe_goal->turret()->unsafe_goal()
- : std::numeric_limits<double>::quiet_NaN());
+ const double turret_goal = (unsafe_turret_goal != nullptr
+ ? unsafe_turret_goal->unsafe_goal()
+ : std::numeric_limits<double>::quiet_NaN());
// Calculating the avoidance with either intake, and when the turret is
// wrapped.
- CalculateAvoidance(true, intake_front_position, turret_goal,
- kMinCollisionZoneFrontTurret, kMaxCollisionZoneFrontTurret,
- turret_position);
- CalculateAvoidance(false, intake_back_position, turret_goal,
- kMinCollisionZoneBackTurret, kMaxCollisionZoneBackTurret,
- turret_position);
+ CalculateAvoidance(true, false, intake_front_position, turret_position,
+ turret_goal, kMinCollisionZoneFrontTurret,
+ kMaxCollisionZoneFrontTurret);
+ CalculateAvoidance(false, false, intake_back_position, turret_position,
+ turret_goal, kMinCollisionZoneBackTurret,
+ kMaxCollisionZoneBackTurret);
+
+ // If we aren't firing, no need to check the catapult
+ if (!status.shooting) {
+ return;
+ }
+
+ CalculateAvoidance(true, true, intake_front_position, turret_position,
+ turret_goal, kMinCollisionZoneFrontTurret,
+ kMaxCollisionZoneFrontTurret);
+ CalculateAvoidance(false, true, intake_back_position, turret_position,
+ turret_goal, kMinCollisionZoneBackTurret,
+ kMaxCollisionZoneBackTurret);
}
-void CollisionAvoidance::CalculateAvoidance(bool intake_front,
+void CollisionAvoidance::CalculateAvoidance(bool intake_front, bool catapult,
double intake_position,
+ double turret_position,
double turret_goal,
double min_turret_collision_goal,
- double max_turret_collision_goal,
- double turret_position) {
+ double max_turret_collision_goal) {
+ // If we are checking the catapult, offset the turret angle to represent where
+ // the catapult is
+ if (catapult) {
+ turret_position += M_PI;
+ turret_goal += M_PI;
+ }
+
auto [turret_position_wrapped, turret_position_wraps] =
WrapTurretAngle(turret_position);
// If the turret goal is in a collison zone or moving through one, limit
// intake.
const bool turret_pos_unsafe =
- (turret_position_wrapped >= min_turret_collision_goal &&
- turret_position_wrapped <= max_turret_collision_goal);
+ AngleInRange(turret_position_wrapped, min_turret_collision_goal,
+ max_turret_collision_goal);
const bool turret_moving_forward = (turret_goal > turret_position);
@@ -128,8 +173,11 @@
}
min_turret_collision_goal_unwrapped =
UnwrapTurretAngle(min_turret_collision_goal, bounds_wraps);
+ // If we are checking the back intake, the max turret angle is on the wrap
+ // after the min, so add 1 to the number of wraps for it
const double max_turret_collision_goal_unwrapped =
- UnwrapTurretAngle(max_turret_collision_goal, bounds_wraps);
+ UnwrapTurretAngle(max_turret_collision_goal,
+ intake_front ? bounds_wraps : bounds_wraps + 1);
// Check if the closest unwrapped angles are going to be passed
const bool turret_moving_past_intake =
@@ -143,20 +191,23 @@
if (turret_pos_unsafe || turret_moving_past_intake) {
// If the turret is unsafe, limit the intake
if (intake_front) {
- update_min_intake_front_goal(kCollisionZoneIntake + kEpsIntake);
+ update_max_intake_front_goal(kCollisionZoneIntake - kEpsIntake);
} else {
- update_min_intake_back_goal(kCollisionZoneIntake + kEpsIntake);
+ update_max_intake_back_goal(kCollisionZoneIntake - kEpsIntake);
}
// If the intake is in the way, limit the turret until moved. Otherwise,
// let'errip!
- if (!turret_pos_unsafe && (intake_position <= kCollisionZoneIntake)) {
+ if (!turret_pos_unsafe && (intake_position > kCollisionZoneIntake)) {
+ // If we were comparing the position of the catapult,
+ // remove that offset of pi to get the turret position
+ const double bounds_offset = (catapult ? -M_PI : 0);
if (turret_position < min_turret_collision_goal_unwrapped) {
- update_max_turret_goal(min_turret_collision_goal_unwrapped -
- kEpsTurret);
+ update_max_turret_goal(min_turret_collision_goal_unwrapped +
+ bounds_offset - kEpsTurret);
} else {
update_min_turret_goal(max_turret_collision_goal_unwrapped +
- kEpsTurret);
+ bounds_offset + kEpsTurret);
}
}
}
diff --git a/y2022/control_loops/superstructure/collision_avoidance.h b/y2022/control_loops/superstructure/collision_avoidance.h
index 94b454c..3cd5344 100644
--- a/y2022/control_loops/superstructure/collision_avoidance.h
+++ b/y2022/control_loops/superstructure/collision_avoidance.h
@@ -19,7 +19,13 @@
// Returns the absolute angle given the wrapped angle and number of wraps.
double UnwrapTurretAngle(double wrapped, int wraps);
+// Checks if theta is between theta_min and theta_max. Expects all angles to be
+// wrapped from 0 to 2pi
+bool AngleInRange(double theta, double theta_min, double theta_max);
+
// 1. Prevent the turret from moving if the intake is up
+// and prevent the back of the turret (where the catapult is)
+// from colliding with the intake when it's up.
// 2. If the intake is up, drop it so it is not in the way
// 3. Move the turret to the desired position.
// 4. When the turret moves away, if the intake is down, move it back up.
@@ -29,11 +35,12 @@
double intake_front_position;
double intake_back_position;
double turret_position;
+ bool shooting;
bool operator==(const Status &s) const {
return (intake_front_position == s.intake_front_position &&
intake_back_position == s.intake_back_position &&
- turret_position == s.turret_position);
+ turret_position == s.turret_position && shooting == s.shooting);
}
bool operator!=(const Status &s) const { return !(*this == s); }
};
@@ -49,15 +56,15 @@
static constexpr double kMaxCollisionZoneFrontTurret =
M_PI + kCollisionZoneTurret;
- static constexpr double kMinCollisionZoneBackTurret = -kCollisionZoneTurret;
+ static constexpr double kMinCollisionZoneBackTurret =
+ (2.0 * M_PI) - kCollisionZoneTurret;
static constexpr double kMaxCollisionZoneBackTurret = kCollisionZoneTurret;
- // Minimum (highest in reality) of the intake, in order to avoid collisions
- static constexpr double kCollisionZoneIntake = M_PI / 6.0;
+ // Maximum position of the intake to avoid collisions
+ static constexpr double kCollisionZoneIntake = 1.4;
- // Tolerance for the turret.
+ // Tolerances for the subsystems
static constexpr double kEpsTurret = 0.05;
- // Tolerance for the intake.
static constexpr double kEpsIntake = 0.05;
CollisionAvoidance();
@@ -69,12 +76,15 @@
double min_turret_collision_position,
double max_turret_collision_position);
// Checks and alters goals to make sure they're safe.
- void UpdateGoal(const Status &status, const Goal *unsafe_goal);
+ void UpdateGoal(
+ const Status &status,
+ const frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal
+ *unsafe_turret_goal);
// Limits if goal is in collision spots.
- void CalculateAvoidance(bool intake_front, double intake_position,
- double turret_goal, double mix_turret_collision_goal,
- double max_turret_collision_goal,
- double turret_position);
+ void CalculateAvoidance(bool intake_front, bool catapult,
+ double intake_position, double turret_position,
+ double turret_goal, double min_turret_collision_goal,
+ double max_turret_collision_goal);
// Returns the goals to give to the respective control loops in
// superstructure.
diff --git a/y2022/control_loops/superstructure/collision_avoidance_test.cc b/y2022/control_loops/superstructure/collision_avoidance_test.cc
index 616a10b..7c53be3 100644
--- a/y2022/control_loops/superstructure/collision_avoidance_test.cc
+++ b/y2022/control_loops/superstructure/collision_avoidance_test.cc
@@ -2,8 +2,8 @@
#include "aos/commonmath.h"
#include "aos/flatbuffers.h"
-#include "gtest/gtest.h"
#include "gmock/gmock.h"
+#include "gtest/gtest.h"
#include "y2022/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
@@ -76,33 +76,30 @@
kNegativeUnsafeFrontWrapped,
kNegativeUnsafeBackWrapped,
};
+enum class CatapultState { kIdle, kShooting };
class CollisionAvoidanceTest : public ::testing::Test {
public:
CollisionAvoidanceTest()
: unsafe_goal_(MakeZeroGoal()),
- status_({0.0, 0.0, 0.0}),
- prev_status_({0.0, 0.0, 0.0}) {}
+ status_({0.0, 0.0, 0.0, false}),
+ prev_status_({0.0, 0.0, 0.0, false}) {}
- int t = 0;
- int d = 0;
void Simulate() {
FlatbufferDetachedBuffer<Goal> safe_goal = MakeZeroGoal();
-
- t++;
- // Don't simulate if already collided
- if (avoidance_.IsCollided(status_)) {
- d++;
- return;
- }
+ bool was_collided = avoidance_.IsCollided(status_);
bool moving = true;
while (moving) {
// Compute the safe goal
- avoidance_.UpdateGoal(status_, &unsafe_goal_.message());
+ avoidance_.UpdateGoal(status_, unsafe_goal_.message().turret());
- // The system should never be collided
- ASSERT_FALSE(avoidance_.IsCollided(status_));
+ if (!was_collided) {
+ // The system should never be collided if it didn't start off collided
+ EXPECT_FALSE(avoidance_.IsCollided(status_));
+ } else {
+ was_collided = avoidance_.IsCollided(status_);
+ }
safe_goal.mutable_message()->mutable_intake_front()->mutate_unsafe_goal(
::aos::Clip(intake_front_goal(), avoidance_.min_intake_front_goal(),
@@ -132,6 +129,8 @@
}
}
+ EXPECT_FALSE(avoidance_.IsCollided(status_));
+
CheckGoals();
}
@@ -142,11 +141,11 @@
switch (intake_state) {
case IntakeState::kSafe:
- intake_angle = CollisionAvoidance::kCollisionZoneIntake +
+ intake_angle = CollisionAvoidance::kCollisionZoneIntake -
CollisionAvoidance::kEpsIntake;
break;
case IntakeState::kUnsafe:
- intake_angle = CollisionAvoidance::kCollisionZoneIntake -
+ intake_angle = CollisionAvoidance::kCollisionZoneIntake +
CollisionAvoidance::kEpsIntake;
break;
}
@@ -236,10 +235,12 @@
void Test(IntakeState intake_front_pos_state,
IntakeState intake_back_pos_state, TurretState turret_pos_state,
IntakeState intake_front_goal_state,
- IntakeState intake_back_goal_state, TurretState turret_goal_state) {
+ IntakeState intake_back_goal_state, TurretState turret_goal_state,
+ CatapultState catapult_state) {
status_ = {ComputeIntakeAngle(intake_front_pos_state),
ComputeIntakeAngle(intake_back_pos_state),
- ComputeTurretAngle(turret_pos_state)};
+ ComputeTurretAngle(turret_pos_state),
+ catapult_state == CatapultState::kShooting};
unsafe_goal_.mutable_message()->mutable_intake_front()->mutate_unsafe_goal(
ComputeIntakeAngle(intake_front_goal_state));
@@ -264,14 +265,19 @@
// Turret is highest priority and should always reach the unsafe goal
EXPECT_NEAR(turret_goal(), status_.turret_position, kIterationMove);
- // If the unsafe goal had an intake colliding with the turret, the intake
- // position should be at least the collision zone angle.
+ // If the unsafe goal had an intake colliding with the turret or catapult,
+ // the intake position should be at least the collision zone angle.
// Otherwise, the intake should be at the unsafe goal
if (avoidance_.TurretCollided(
intake_front_goal(), turret_goal(),
CollisionAvoidance::kMinCollisionZoneFrontTurret,
- CollisionAvoidance::kMaxCollisionZoneFrontTurret)) {
- EXPECT_GE(status_.intake_front_position,
+ CollisionAvoidance::kMaxCollisionZoneFrontTurret) ||
+ (status_.shooting &&
+ avoidance_.TurretCollided(
+ intake_front_goal(), turret_goal() + M_PI,
+ CollisionAvoidance::kMinCollisionZoneFrontTurret,
+ CollisionAvoidance::kMaxCollisionZoneFrontTurret))) {
+ EXPECT_LE(status_.intake_front_position,
CollisionAvoidance::kCollisionZoneIntake);
} else {
EXPECT_NEAR(intake_front_goal(), status_.intake_front_position,
@@ -281,8 +287,13 @@
if (avoidance_.TurretCollided(
intake_back_goal(), turret_goal(),
CollisionAvoidance::kMinCollisionZoneBackTurret,
- CollisionAvoidance::kMaxCollisionZoneBackTurret)) {
- EXPECT_GE(status_.intake_back_position,
+ CollisionAvoidance::kMaxCollisionZoneBackTurret) ||
+ (status_.shooting &&
+ avoidance_.TurretCollided(
+ intake_back_goal(), turret_goal() + M_PI,
+ CollisionAvoidance::kMinCollisionZoneBackTurret,
+ CollisionAvoidance::kMaxCollisionZoneBackTurret))) {
+ EXPECT_LE(status_.intake_back_position,
CollisionAvoidance::kCollisionZoneIntake);
} else {
EXPECT_NEAR(intake_back_goal(), status_.intake_back_position, 0.001);
@@ -327,8 +338,13 @@
{TurretState::kSafeFront, TurretState::kSafeBack,
TurretState::kSafeFrontWrapped, TurretState::kSafeBackWrapped,
TurretState::kUnsafeFront, TurretState::kUnsafeBack,
- TurretState::kUnsafeFrontWrapped,
- TurretState::kUnsafeBackWrapped}) {
+ TurretState::kUnsafeFrontWrapped, TurretState::kUnsafeBackWrapped,
+ TurretState::kNegativeSafeFront, TurretState::kNegativeSafeBack,
+ TurretState::kNegativeSafeFrontWrapped,
+ TurretState::kNegativeSafeBackWrapped,
+ TurretState::kNegativeUnsafeFront, TurretState::kNegativeUnsafeBack,
+ TurretState::kNegativeUnsafeFrontWrapped,
+ TurretState::kNegativeUnsafeBackWrapped}) {
// Intake front goal
for (IntakeState intake_front_goal :
{IntakeState::kSafe, IntakeState::kUnsafe}) {
@@ -341,9 +357,22 @@
TurretState::kSafeFrontWrapped, TurretState::kSafeBackWrapped,
TurretState::kUnsafeFront, TurretState::kUnsafeBack,
TurretState::kUnsafeFrontWrapped,
- TurretState::kUnsafeBackWrapped}) {
- Test(intake_front_pos, intake_back_pos, turret_pos,
- intake_front_goal, intake_back_goal, turret_goal);
+ TurretState::kUnsafeBackWrapped,
+ TurretState::kNegativeSafeFront,
+ TurretState::kNegativeSafeBack,
+ TurretState::kNegativeSafeFrontWrapped,
+ TurretState::kNegativeSafeBackWrapped,
+ TurretState::kNegativeUnsafeFront,
+ TurretState::kNegativeUnsafeBack,
+ TurretState::kNegativeUnsafeFrontWrapped,
+ TurretState::kNegativeUnsafeBackWrapped}) {
+ // Catapult state
+ for (CatapultState catapult_state :
+ {CatapultState::kIdle, CatapultState::kShooting}) {
+ Test(intake_front_pos, intake_back_pos, turret_pos,
+ intake_front_goal, intake_back_goal, turret_goal,
+ catapult_state);
+ }
}
}
}
@@ -420,4 +449,12 @@
}
}
+// Test that AngleInRange works correctly for wrapped angles
+TEST(AngleTest, AngleInRange) {
+ EXPECT_TRUE(AngleInRange(0.5, 0.4, 0.6));
+ EXPECT_TRUE(AngleInRange(0, (2.0 * M_PI) - 0.2, 0.2));
+ EXPECT_FALSE(AngleInRange(0, (2.0 * M_PI) - 0.2, (2.0 * M_PI) - 0.1));
+ EXPECT_TRUE(AngleInRange(0.5, (2.0 * M_PI) - 0.1, 0.6));
+}
+
} // namespace y2022::control_loops::superstructure::testing
diff --git a/y2022/control_loops/superstructure/intake_plotter.ts b/y2022/control_loops/superstructure/intake_plotter.ts
index 8667473..8904d8b 100644
--- a/y2022/control_loops/superstructure/intake_plotter.ts
+++ b/y2022/control_loops/superstructure/intake_plotter.ts
@@ -9,7 +9,7 @@
const DEFAULT_WIDTH = AosPlotter.DEFAULT_WIDTH * 5 / 2;
const DEFAULT_HEIGHT = AosPlotter.DEFAULT_HEIGHT * 3;
-export function plotIntake(conn: Connection, element: Element) : void {
+export function plotIntakeFront(conn: Connection, element: Element) : void {
const aosPlotter = new AosPlotter(conn);
const goal = aosPlotter.addMessageSource('/superstructure', 'y2022.control_loops.superstructure.Goal');
const output = aosPlotter.addMessageSource('/superstructure', 'y2022.control_loops.superstructure.Output');
@@ -30,6 +30,35 @@
positionPlotFront.addMessageLine(status, ['intake_front', 'goal_velocity']).setColor(ORANGE).setPointSize(4.0);
positionPlotFront.addMessageLine(status, ['intake_front', 'estimator_state', 'position']).setColor(CYAN).setPointSize(1.0);
+ const voltagePlotFront =
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ voltagePlotFront.plot.getAxisLabels().setTitle('Voltage');
+ voltagePlotFront.plot.getAxisLabels().setXLabel(TIME);
+ voltagePlotFront.plot.getAxisLabels().setYLabel('Volts');
+ voltagePlotFront.plot.setDefaultYRange([-4.0, 14.0]);
+
+ voltagePlotFront.addMessageLine(output, ['intake_voltage_front']).setColor(BLUE).setPointSize(4.0);
+ voltagePlotFront.addMessageLine(status, ['intake_front', 'voltage_error']).setColor(RED).setPointSize(1.0);
+ voltagePlotFront.addMessageLine(status, ['intake_front', 'position_power']).setColor(BROWN).setPointSize(1.0);
+ voltagePlotFront.addMessageLine(status, ['intake_front', 'velocity_power']).setColor(CYAN).setPointSize(1.0);
+ voltagePlotFront.addMessageLine(robotState, ['voltage_battery']).setColor(GREEN).setPointSize(1.0);
+}
+
+export function plotIntakeBack(conn: Connection, element: Element) : void {
+ const aosPlotter = new AosPlotter(conn);
+ const goal = aosPlotter.addMessageSource('/superstructure', 'y2022.control_loops.superstructure.Goal');
+ const output = aosPlotter.addMessageSource('/superstructure', 'y2022.control_loops.superstructure.Output');
+ const status = aosPlotter.addMessageSource('/superstructure', 'y2022.control_loops.superstructure.Status');
+ const robotState = aosPlotter.addMessageSource('/aos', 'aos.RobotState');
+
+ // Robot Enabled/Disabled and Mode
+ const positionPlotFront =
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ positionPlotFront.plot.getAxisLabels().setTitle('Position');
+ positionPlotFront.plot.getAxisLabels().setXLabel(TIME);
+ positionPlotFront.plot.getAxisLabels().setYLabel('rad');
+ positionPlotFront.plot.setDefaultYRange([-1.0, 2.0]);
+
const positionPlotBack =
aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
positionPlotBack.plot.getAxisLabels().setTitle('Position');
@@ -43,19 +72,6 @@
positionPlotBack.addMessageLine(status, ['intake_back', 'goal_velocity']).setColor(ORANGE).setPointSize(4.0);
positionPlotBack.addMessageLine(status, ['intake_back', 'estimator_state', 'position']).setColor(CYAN).setPointSize(1.0);
- const voltagePlotFront =
- aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
- voltagePlotFront.plot.getAxisLabels().setTitle('Voltage');
- voltagePlotFront.plot.getAxisLabels().setXLabel(TIME);
- voltagePlotFront.plot.getAxisLabels().setYLabel('Volts');
- voltagePlotFront.plot.setDefaultYRange([-4.0, 14.0]);
-
- voltagePlotFront.addMessageLine(output, ['intake_front_voltage']).setColor(BLUE).setPointSize(4.0);
- voltagePlotFront.addMessageLine(status, ['intake_front', 'voltage_error']).setColor(RED).setPointSize(1.0);
- voltagePlotFront.addMessageLine(status, ['intake_front', 'position_power']).setColor(BROWN).setPointSize(1.0);
- voltagePlotFront.addMessageLine(status, ['intake_front', 'velocity_power']).setColor(CYAN).setPointSize(1.0);
- voltagePlotFront.addMessageLine(robotState, ['voltage_battery']).setColor(GREEN).setPointSize(1.0);
-
const voltagePlotBack =
aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
@@ -64,7 +80,7 @@
voltagePlotBack.plot.getAxisLabels().setYLabel('Volts');
voltagePlotBack.plot.setDefaultYRange([-4.0, 14.0]);
- voltagePlotBack.addMessageLine(output, ['intake_back_voltage']).setColor(BLUE).setPointSize(4.0);
+ voltagePlotBack.addMessageLine(output, ['intake_voltage_back']).setColor(BLUE).setPointSize(4.0);
voltagePlotBack.addMessageLine(status, ['intake_back', 'voltage_error']).setColor(RED).setPointSize(1.0);
voltagePlotBack.addMessageLine(status, ['intake_back', 'position_power']).setColor(BROWN).setPointSize(1.0);
voltagePlotBack.addMessageLine(status, ['intake_back', 'velocity_power']).setColor(CYAN).setPointSize(1.0);
diff --git a/y2022/control_loops/superstructure/superstructure.cc b/y2022/control_loops/superstructure/superstructure.cc
index bf94b08..56e58cc 100644
--- a/y2022/control_loops/superstructure/superstructure.cc
+++ b/y2022/control_loops/superstructure/superstructure.cc
@@ -1,6 +1,7 @@
#include "y2022/control_loops/superstructure/superstructure.h"
#include "aos/events/event_loop.h"
+#include "aos/flatbuffer_merge.h"
#include "y2022/control_loops/superstructure/collision_avoidance.h"
namespace y2022 {
@@ -21,10 +22,12 @@
intake_front_(values_->intake_front.subsystem_params),
intake_back_(values_->intake_back.subsystem_params),
turret_(values_->turret.subsystem_params),
+ catapult_(*values_),
drivetrain_status_fetcher_(
event_loop->MakeFetcher<frc971::control_loops::drivetrain::Status>(
"/drivetrain")),
- catapult_(*values_) {
+ can_position_fetcher_(
+ event_loop->MakeFetcher<CANPosition>("/superstructure")) {
event_loop->SetRuntimeRealtimePriority(30);
}
@@ -32,8 +35,6 @@
const Position *position,
aos::Sender<Output>::Builder *output,
aos::Sender<Status>::Builder *status) {
- OutputT output_struct;
-
if (WasReset()) {
AOS_LOG(ERROR, "WPILib reset, restarting\n");
intake_front_.Reset();
@@ -43,25 +44,34 @@
catapult_.Reset();
}
- collision_avoidance_.UpdateGoal(
- {.intake_front_position = intake_front_.estimated_position(),
- .intake_back_position = intake_back_.estimated_position(),
- .turret_position = turret_.estimated_position()},
- unsafe_goal);
+ OutputT output_struct;
- turret_.set_min_position(collision_avoidance_.min_turret_goal());
- turret_.set_max_position(collision_avoidance_.max_turret_goal());
- intake_front_.set_min_position(collision_avoidance_.min_intake_front_goal());
- intake_front_.set_max_position(collision_avoidance_.max_intake_front_goal());
- intake_back_.set_min_position(collision_avoidance_.min_intake_back_goal());
- intake_back_.set_max_position(collision_avoidance_.max_intake_back_goal());
+ aos::FlatbufferFixedAllocatorArray<
+ frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal, 64>
+ turret_goal_buffer;
+ aos::FlatbufferFixedAllocatorArray<CatapultGoal, 64> catapult_goal_buffer;
+
+ const aos::monotonic_clock::time_point timestamp =
+ event_loop()->context().monotonic_event_time;
drivetrain_status_fetcher_.Fetch();
const float velocity = robot_velocity();
- double roller_speed_compensated_front = 0;
- double roller_speed_compensated_back = 0;
- double transfer_roller_speed = 0;
+ const turret::Aimer::Goal *auto_aim_goal = nullptr;
+ if (drivetrain_status_fetcher_.get() != nullptr) {
+ aimer_.Update(drivetrain_status_fetcher_.get(),
+ turret::Aimer::ShotMode::kShootOnTheFly);
+ auto_aim_goal = aimer_.TurretGoal();
+ }
+
+ const frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal
+ *turret_goal = nullptr;
+ const CatapultGoal *catapult_goal = nullptr;
+ double roller_speed_compensated_front = 0.0;
+ double roller_speed_compensated_back = 0.0;
+ double transfer_roller_speed_front = 0.0;
+ double transfer_roller_speed_back = 0.0;
+ double flipper_arms_voltage = 0.0;
if (unsafe_goal != nullptr) {
roller_speed_compensated_front =
@@ -72,48 +82,386 @@
unsafe_goal->roller_speed_back() -
std::min(velocity * unsafe_goal->roller_speed_compensation(), 0.0);
- transfer_roller_speed = unsafe_goal->transfer_roller_speed();
+ transfer_roller_speed_front = unsafe_goal->transfer_roller_speed_front();
+ transfer_roller_speed_back = unsafe_goal->transfer_roller_speed_back();
+
+ turret_goal =
+ unsafe_goal->auto_aim() ? auto_aim_goal : unsafe_goal->turret();
+
+ catapult_goal = unsafe_goal->catapult();
+
+ constants::Values::ShotParams shot_params;
+ const double distance_to_goal = aimer_.DistanceToGoal();
+ if (unsafe_goal->auto_aim() && values_->shot_interpolation_table.GetInRange(
+ distance_to_goal, &shot_params)) {
+ std::optional<flatbuffers::Offset<
+ frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal>>
+ return_position_offset;
+ if (unsafe_goal != nullptr && unsafe_goal->has_catapult() &&
+ unsafe_goal->catapult()->has_return_position()) {
+ return_position_offset = {
+ aos::CopyFlatBuffer(unsafe_goal->catapult()->return_position(),
+ catapult_goal_buffer.fbb())};
+ }
+ CatapultGoal::Builder builder(*catapult_goal_buffer.fbb());
+ builder.add_shot_position(shot_params.shot_angle);
+ builder.add_shot_velocity(shot_params.shot_velocity);
+ if (return_position_offset.has_value()) {
+ builder.add_return_position(return_position_offset.value());
+ }
+ catapult_goal_buffer.Finish(builder.Finish());
+ catapult_goal = &catapult_goal_buffer.message();
+ }
}
+ // Superstructure state machine:
+ // 1. IDLE: Wait until an intake beambreak is triggerred, meaning that a ball
+ // is being intaked. This means that the transfer rollers have a ball. If
+ // we've been waiting here for too long without any beambreak triggered, the
+ // ball got lost, so reset.
+ // 2. TRANSFERRING: Until the turret reaches the loading position where the
+ // ball can be transferred into the catapult, wiggle the ball in place.
+ // Once the turret reaches the loading position, send the ball forward with
+ // the transfer rollers until the turret beambreak is triggered.
+ // If we have been in this state for too long, the ball probably got lost so
+ // reset back to IDLE.
+ // 3. LOADING: To load the ball into the catapult, put the flippers at the
+ // feeding speed. Wait for a timeout, and then wait until the ball has gone
+ // past the turret beambreak and the flippers have stopped moving, meaning
+ // that the ball is fully loaded in the catapult.
+ // 4. LOADED: Wait until the user asks us to fire to transition to the
+ // shooting stage. If asked to cancel the shot, reset back to the IDLE state.
+ // 5. SHOOTING: Open the flippers to get ready for the shot. If they don't
+ // open quickly enough, try reseating the ball and going back to the LOADING
+ // stage, which moves the flippers in the opposite direction first.
+ // Now, hold the flippers open and wait until the turret has reached its
+ // aiming goal. Once the turret is ready, tell the catapult to fire.
+ // If the flippers move back for some reason now, it could damage the
+ // catapult, so estop it. Otherwise, wait until the catapult shoots a ball and
+ // goes back to its return position. We have now finished the shot, so return
+ // to IDLE.
+ // If we started off preloaded, skip to the loaded state.
+ // Make sure we weren't already there just in case.
+ if (unsafe_goal != nullptr && unsafe_goal->preloaded()) {
+ switch (state_) {
+ case SuperstructureState::IDLE:
+ case SuperstructureState::TRANSFERRING:
+ case SuperstructureState::LOADING:
+ state_ = SuperstructureState::LOADED;
+ loading_timer_ = timestamp;
+ break;
+ case SuperstructureState::LOADED:
+ case SuperstructureState::SHOOTING:
+ break;
+ }
+ }
+
+ const bool is_spitting = ((intake_state_ == IntakeState::INTAKE_FRONT_BALL &&
+ transfer_roller_speed_front < 0) ||
+ (intake_state_ == IntakeState::INTAKE_BACK_BALL &&
+ transfer_roller_speed_back < 0));
+
+ // Intake handling should happen regardless of the turret state
+ if (position->intake_beambreak_front() || position->intake_beambreak_back()) {
+ if (intake_state_ == IntakeState::NO_BALL) {
+ if (position->intake_beambreak_front()) {
+ intake_state_ = IntakeState::INTAKE_FRONT_BALL;
+ } else if (position->intake_beambreak_back()) {
+ intake_state_ = IntakeState::INTAKE_BACK_BALL;
+ }
+ }
+
+ intake_beambreak_timer_ = timestamp;
+ }
+
+ if (timestamp >
+ intake_beambreak_timer_ + constants::Values::kBallLostTime()) {
+ intake_state_ = IntakeState::NO_BALL;
+ }
+
+ if (intake_state_ != IntakeState::NO_BALL) {
+ roller_speed_compensated_front = 0.0;
+ roller_speed_compensated_back = 0.0;
+
+ const double wiggle_voltage =
+ constants::Values::kTransferRollerWiggleVoltage();
+ // Wiggle transfer rollers: send the ball back and forth while waiting
+ // for the turret or waiting for another shot to be completed
+ if (intake_state_ == IntakeState::INTAKE_FRONT_BALL) {
+ if (position->intake_beambreak_front()) {
+ transfer_roller_speed_front = -wiggle_voltage;
+ transfer_roller_speed_back = wiggle_voltage;
+ } else {
+ transfer_roller_speed_front = wiggle_voltage;
+ transfer_roller_speed_back = -wiggle_voltage;
+ }
+ } else {
+ if (position->intake_beambreak_back()) {
+ transfer_roller_speed_back = -wiggle_voltage;
+ transfer_roller_speed_front = wiggle_voltage;
+ } else {
+ transfer_roller_speed_back = wiggle_voltage;
+ transfer_roller_speed_front = -wiggle_voltage;
+ }
+ }
+ }
+
+ // Send the turret to the loading position if we have a ball in the intake, or
+ // are trying to intake one
+ double turret_loading_position = std::numeric_limits<double>::quiet_NaN();
+ if (state_ == SuperstructureState::TRANSFERRING &&
+ intake_state_ != IntakeState::NO_BALL) {
+ turret_loading_position = (intake_state_ == IntakeState::INTAKE_FRONT_BALL
+ ? constants::Values::kTurretFrontIntakePos()
+ : constants::Values::kTurretBackIntakePos());
+ } else if (state_ == SuperstructureState::IDLE && unsafe_goal != nullptr) {
+ if (unsafe_goal->roller_speed_front() > 0) {
+ turret_loading_position = constants::Values::kTurretFrontIntakePos();
+ } else if (unsafe_goal->roller_speed_back() > 0) {
+ turret_loading_position = constants::Values::kTurretBackIntakePos();
+ }
+ }
+
+ if (!std::isnan(turret_loading_position)) {
+ // Turn to the loading position as close to the current position as
+ // possible
+ // Strategy is copied from frc971/control_loops/aiming/aiming.cc
+ turret_loading_position =
+ turret_.estimated_position() +
+ aos::math::NormalizeAngle(turret_loading_position -
+ turret_.estimated_position());
+ // if out of range, reset back to within +/- pi of zero.
+ if (turret_loading_position > constants::Values::kTurretRange().upper ||
+ turret_loading_position < constants::Values::kTurretRange().lower) {
+ turret_loading_position =
+ aos::math::NormalizeAngle(turret_loading_position);
+ }
+
+ turret_goal_buffer.Finish(
+ frc971::control_loops::
+ CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *turret_goal_buffer.fbb(), turret_loading_position));
+ turret_goal = &turret_goal_buffer.message();
+ }
+
+ switch (state_) {
+ case SuperstructureState::IDLE: {
+ if (is_spitting) {
+ intake_state_ = IntakeState::NO_BALL;
+ }
+
+ if (intake_state_ == IntakeState::NO_BALL ||
+ !(position->intake_beambreak_front() ||
+ position->intake_beambreak_back())) {
+ break;
+ }
+
+ state_ = SuperstructureState::TRANSFERRING;
+ // Save the side the ball is on for later
+
+ break;
+ }
+ case SuperstructureState::TRANSFERRING: {
+ // If we've been transferring for too long, the ball probably got lost
+ if (intake_state_ == IntakeState::NO_BALL) {
+ state_ = SuperstructureState::IDLE;
+ break;
+ }
+
+ const bool turret_near_goal =
+ std::abs(turret_.estimated_position() - turret_loading_position) <
+ kTurretGoalThreshold;
+ if (!turret_near_goal) {
+ break; // Wait for turret to reach the chosen intake
+ }
+
+ // Transfer rollers and flipper arm belt on
+ if (intake_state_ == IntakeState::INTAKE_FRONT_BALL) {
+ transfer_roller_speed_front =
+ constants::Values::kTransferRollerVoltage();
+ transfer_roller_speed_back =
+ -constants::Values::kTransferRollerVoltage();
+ } else {
+ transfer_roller_speed_back =
+ constants::Values::kTransferRollerVoltage();
+ transfer_roller_speed_front =
+ -constants::Values::kTransferRollerVoltage();
+ }
+ flipper_arms_voltage = constants::Values::kFlipperFeedVoltage();
+
+ // Ball is in catapult
+ if (position->turret_beambreak()) {
+ intake_state_ = IntakeState::NO_BALL;
+ state_ = SuperstructureState::LOADING;
+ loading_timer_ = timestamp;
+ }
+ break;
+ }
+ case SuperstructureState::LOADING: {
+ flipper_arms_voltage = constants::Values::kFlipperFeedVoltage();
+
+ // Keep feeding for kExtraLoadingTime
+
+ // The ball should go past the turret beambreak to be loaded.
+ // If we got a CAN reading not too long ago, the flippers should have
+ // also stopped.
+ if (position->turret_beambreak()) {
+ loading_timer_ = timestamp;
+ } else if (timestamp >
+ loading_timer_ + constants::Values::kExtraLoadingTime()) {
+ state_ = SuperstructureState::LOADED;
+ reseating_in_catapult_ = false;
+ }
+ break;
+ }
+ case SuperstructureState::LOADED: {
+ if (unsafe_goal != nullptr) {
+ if (unsafe_goal->cancel_shot()) {
+ // Cancel the shot process
+ state_ = SuperstructureState::IDLE;
+ } else if (unsafe_goal->fire()) {
+ // Start if we were asked to and the turret is at goal
+ state_ = SuperstructureState::SHOOTING;
+ prev_shot_count_ = catapult_.shot_count();
+
+ // Reset opening timeout
+ flipper_opening_start_time_ = timestamp;
+ }
+ }
+ break;
+ }
+ case SuperstructureState::SHOOTING: {
+ // Opening flipper arms could fail, wait until they are open using their
+ // potentiometers (the member below is just named encoder).
+ // Be a little more lenient if the flippers were already open in case of
+ // noise or collisions.
+ const double flipper_open_position =
+ (flippers_open_ ? constants::Values::kReseatFlipperPosition()
+ : constants::Values::kFlipperOpenPosition());
+
+ // TODO(milind): add left arm back once it's fixed
+ flippers_open_ =
+ position->flipper_arm_right()->encoder() >= flipper_open_position;
+
+ if (flippers_open_) {
+ // Hold at kFlipperHoldVoltage
+ flipper_arms_voltage = constants::Values::kFlipperHoldVoltage();
+ } else {
+ // Open at kFlipperOpenVoltage
+ flipper_arms_voltage = constants::Values::kFlipperOpenVoltage();
+ }
+
+ if (!flippers_open_ &&
+ timestamp >
+ loading_timer_ + constants::Values::kFlipperOpeningTimeout()) {
+ // Reseat the ball and try again
+ state_ = SuperstructureState::LOADING;
+ loading_timer_ = timestamp;
+ reseating_in_catapult_ = true;
+ break;
+ }
+
+ const bool turret_near_goal =
+ turret_goal != nullptr &&
+ std::abs(turret_goal->unsafe_goal() - turret_.position()) <
+ kTurretGoalThreshold;
+ const bool collided = collision_avoidance_.IsCollided(
+ {.intake_front_position = intake_front_.estimated_position(),
+ .intake_back_position = intake_back_.estimated_position(),
+ .turret_position = turret_.estimated_position(),
+ .shooting = true});
+
+ // If the turret reached the aiming goal and the catapult is safe to move
+ // up, fire!
+ if (flippers_open_ && turret_near_goal && !collided) {
+ fire_ = true;
+ }
+
+ // If we started firing and the flippers closed a bit, estop to prevent
+ // damage
+ if (fire_ && !flippers_open_) {
+ catapult_.Estop();
+ }
+
+ const bool near_return_position =
+ (unsafe_goal != nullptr && unsafe_goal->has_catapult() &&
+ unsafe_goal->catapult()->has_return_position() &&
+ std::abs(unsafe_goal->catapult()->return_position()->unsafe_goal() -
+ catapult_.estimated_position()) < kCatapultGoalThreshold);
+
+ // Once the shot is complete and the catapult is back to its return
+ // position, go back to IDLE
+ if (catapult_.shot_count() > prev_shot_count_ && near_return_position) {
+ prev_shot_count_ = catapult_.shot_count();
+ fire_ = false;
+ state_ = SuperstructureState::IDLE;
+ }
+
+ break;
+ }
+ }
+
+ collision_avoidance_.UpdateGoal(
+ {.intake_front_position = intake_front_.estimated_position(),
+ .intake_back_position = intake_back_.estimated_position(),
+ .turret_position = turret_.estimated_position(),
+ .shooting = state_ == SuperstructureState::SHOOTING},
+ turret_goal);
+
+ turret_.set_min_position(collision_avoidance_.min_turret_goal());
+ turret_.set_max_position(collision_avoidance_.max_turret_goal());
+ intake_front_.set_min_position(collision_avoidance_.min_intake_front_goal());
+ intake_front_.set_max_position(collision_avoidance_.max_intake_front_goal());
+ intake_back_.set_min_position(collision_avoidance_.min_intake_back_goal());
+ intake_back_.set_max_position(collision_avoidance_.max_intake_back_goal());
+
+ const flatbuffers::Offset<AimerStatus> aimer_offset =
+ aimer_.PopulateStatus(status->fbb());
+
+ // Disable the catapult if we want to restart to prevent damage with
+ // flippers
const flatbuffers::Offset<PotAndAbsoluteEncoderProfiledJointStatus>
catapult_status_offset = catapult_.Iterate(
- unsafe_goal, position,
- output != nullptr ? &(output_struct.catapult_voltage) : nullptr,
- status->fbb());
+ catapult_goal, position, robot_state().voltage_battery(),
+ output != nullptr && !catapult_.estopped()
+ ? &(output_struct.catapult_voltage)
+ : nullptr,
+ fire_, status->fbb());
- flatbuffers::Offset<RelativeEncoderProfiledJointStatus>
+ const flatbuffers::Offset<RelativeEncoderProfiledJointStatus>
climber_status_offset = climber_.Iterate(
unsafe_goal != nullptr ? unsafe_goal->climber() : nullptr,
position->climber(),
- output != nullptr ? &(output_struct.climber_voltage) : nullptr,
+ output != nullptr ? &output_struct.climber_voltage : nullptr,
status->fbb());
- flatbuffers::Offset<PotAndAbsoluteEncoderProfiledJointStatus>
+ const flatbuffers::Offset<PotAndAbsoluteEncoderProfiledJointStatus>
intake_status_offset_front = intake_front_.Iterate(
unsafe_goal != nullptr ? unsafe_goal->intake_front() : nullptr,
position->intake_front(),
- output != nullptr ? &(output_struct.intake_voltage_front) : nullptr,
+ output != nullptr ? &output_struct.intake_voltage_front : nullptr,
status->fbb());
- flatbuffers::Offset<PotAndAbsoluteEncoderProfiledJointStatus>
+ const flatbuffers::Offset<PotAndAbsoluteEncoderProfiledJointStatus>
intake_status_offset_back = intake_back_.Iterate(
unsafe_goal != nullptr ? unsafe_goal->intake_back() : nullptr,
position->intake_back(),
- output != nullptr ? &(output_struct.intake_voltage_back) : nullptr,
+ output != nullptr ? &output_struct.intake_voltage_back : nullptr,
status->fbb());
- flatbuffers::Offset<PotAndAbsoluteEncoderProfiledJointStatus>
+ const flatbuffers::Offset<PotAndAbsoluteEncoderProfiledJointStatus>
turret_status_offset = turret_.Iterate(
- unsafe_goal != nullptr ? unsafe_goal->turret() : nullptr,
- position->turret(),
- output != nullptr ? &(output_struct.turret_voltage) : nullptr,
+ turret_goal, position->turret(),
+ output != nullptr ? &output_struct.turret_voltage : nullptr,
status->fbb());
if (output != nullptr) {
output_struct.roller_voltage_front = roller_speed_compensated_front;
output_struct.roller_voltage_back = roller_speed_compensated_back;
- output_struct.transfer_roller_voltage = transfer_roller_speed;
+ output_struct.transfer_roller_voltage_front = transfer_roller_speed_front;
+ output_struct.transfer_roller_voltage_back = transfer_roller_speed_back;
+ output_struct.flipper_arms_voltage = flipper_arms_voltage;
output->CheckOk(output->Send(Output::Pack(*output->fbb(), &output_struct)));
}
@@ -121,9 +469,11 @@
Status::Builder status_builder = status->MakeBuilder<Status>();
const bool zeroed = intake_front_.zeroed() && intake_back_.zeroed() &&
- turret_.zeroed() && climber_.zeroed() && catapult_.zeroed();
+ turret_.zeroed() && climber_.zeroed() &&
+ catapult_.zeroed();
const bool estopped = intake_front_.estopped() || intake_back_.estopped() ||
- turret_.estopped() || climber_.estopped() || catapult_.estopped();
+ turret_.estopped() || climber_.estopped() ||
+ catapult_.estopped();
status_builder.add_zeroed(zeroed);
status_builder.add_estopped(estopped);
@@ -132,10 +482,23 @@
status_builder.add_intake_back(intake_status_offset_back);
status_builder.add_turret(turret_status_offset);
status_builder.add_climber(climber_status_offset);
+
status_builder.add_catapult(catapult_status_offset);
status_builder.add_solve_time(catapult_.solve_time());
- status_builder.add_mpc_active(catapult_.mpc_active());
status_builder.add_shot_count(catapult_.shot_count());
+ status_builder.add_mpc_active(catapult_.mpc_active());
+ if (catapult_goal != nullptr) {
+ status_builder.add_shot_position(catapult_goal->shot_position());
+ status_builder.add_shot_velocity(catapult_goal->shot_velocity());
+ }
+
+ status_builder.add_flippers_open(flippers_open_);
+ status_builder.add_reseating_in_catapult(reseating_in_catapult_);
+ status_builder.add_fire(fire_);
+ status_builder.add_state(state_);
+ status_builder.add_intake_state(intake_state_);
+
+ status_builder.add_aimer(aimer_offset);
(void)status->Send(status_builder.Finish());
}
diff --git a/y2022/control_loops/superstructure/superstructure.h b/y2022/control_loops/superstructure/superstructure.h
index dfd4265..e9afcc1 100644
--- a/y2022/control_loops/superstructure/superstructure.h
+++ b/y2022/control_loops/superstructure/superstructure.h
@@ -7,10 +7,12 @@
#include "y2022/constants.h"
#include "y2022/control_loops/superstructure/catapult/catapult.h"
#include "y2022/control_loops/superstructure/collision_avoidance.h"
+#include "y2022/control_loops/superstructure/superstructure_can_position_generated.h"
#include "y2022/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2022/control_loops/superstructure/superstructure_output_generated.h"
#include "y2022/control_loops/superstructure/superstructure_position_generated.h"
#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
+#include "y2022/control_loops/superstructure/turret/aiming.h"
namespace y2022 {
namespace control_loops {
@@ -29,6 +31,11 @@
::frc971::zeroing::PotAndAbsoluteEncoderZeroingEstimator,
::frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus>;
+ static constexpr double kTurretGoalThreshold = 0.05;
+ static constexpr double kCatapultGoalThreshold = 0.05;
+ // potentiometer will be more noisy
+ static constexpr double kFlipperGoalThreshold = 0.05;
+
explicit Superstructure(::aos::EventLoop *event_loop,
std::shared_ptr<const constants::Values> values,
const ::std::string &name = "/superstructure");
@@ -58,15 +65,34 @@
PotAndAbsoluteEncoderSubsystem intake_front_;
PotAndAbsoluteEncoderSubsystem intake_back_;
PotAndAbsoluteEncoderSubsystem turret_;
+ catapult::Catapult catapult_;
CollisionAvoidance collision_avoidance_;
aos::Fetcher<frc971::control_loops::drivetrain::Status>
drivetrain_status_fetcher_;
+ aos::Fetcher<CANPosition> can_position_fetcher_;
+
+ int prev_shot_count_ = 0;
+
+ turret::Aimer aimer_;
+
+ bool flippers_open_ = false;
+ bool reseating_in_catapult_ = false;
+ bool fire_ = false;
+
+ aos::monotonic_clock::time_point intake_beambreak_timer_ =
+ aos::monotonic_clock::min_time;
+ aos::monotonic_clock::time_point transferring_timer_ =
+ aos::monotonic_clock::min_time;
+ aos::monotonic_clock::time_point loading_timer_ =
+ aos::monotonic_clock::min_time;
+ aos::monotonic_clock::time_point flipper_opening_start_time_ =
+ aos::monotonic_clock::min_time;
+ SuperstructureState state_ = SuperstructureState::IDLE;
+ IntakeState intake_state_ = IntakeState::NO_BALL;
DISALLOW_COPY_AND_ASSIGN(Superstructure);
-
- catapult::Catapult catapult_;
};
} // namespace superstructure
diff --git a/y2022/control_loops/superstructure/superstructure_goal.fbs b/y2022/control_loops/superstructure/superstructure_goal.fbs
index ada39a2..7816563 100644
--- a/y2022/control_loops/superstructure/superstructure_goal.fbs
+++ b/y2022/control_loops/superstructure/superstructure_goal.fbs
@@ -3,8 +3,9 @@
namespace y2022.control_loops.superstructure;
table CatapultGoal {
- // If true, fire! The robot will only fire when ready.
- fire:bool (id: 0);
+ // Old fire flag, only kept for backwards-compatability with logs.
+ // Use the fire flag in the root Goal instead
+ fire:bool (id: 0, deprecated);
// The target shot position and velocity. If these are provided before fire
// is called, the optimizer can pre-compute the trajectory.
@@ -25,10 +26,13 @@
intake_back:frc971.control_loops.StaticZeroingSingleDOFProfiledSubsystemGoal (id: 2);
// Positive is rollers intaking.
+ // When spinning the rollers, the turret will be moved to that side,
+ // so both shouldn't be positive at the same time.
roller_speed_front:double (id: 3);
roller_speed_back:double (id: 4);
- // One transfer motor for both sides
- transfer_roller_speed:double (id: 5);
+
+ transfer_roller_speed_front:double (id: 5);
+ transfer_roller_speed_back:double (id: 12);
// Factor to multiply robot velocity by and add to roller voltage.
roller_speed_compensation:double (id: 6);
@@ -37,6 +41,21 @@
// Catapult goal state.
catapult:CatapultGoal (id: 8);
+
+ // If true, fire! The robot will only fire when ready.
+ fire:bool (id: 9);
+
+ // Aborts the shooting process if the ball has been loaded into the catapult
+ // and the superstructure is in the LOADED state.
+ cancel_shot:bool (id: 10);
+
+ // If true, auto-track the turret to point at the goal.
+ auto_aim:bool (id: 11);
+
+ // If true, we started with the ball loaded and should proceed to that state.
+ preloaded:bool (id: 13);
}
+
+
root_type Goal;
diff --git a/y2022/control_loops/superstructure/superstructure_lib_test.cc b/y2022/control_loops/superstructure/superstructure_lib_test.cc
index 06dee7b..e6ff227 100644
--- a/y2022/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2022/control_loops/superstructure/superstructure_lib_test.cc
@@ -244,6 +244,18 @@
flatbuffers::Offset<frc971::RelativePosition> climber_offset =
climber_.encoder()->GetSensorValues(&climber_builder);
+ frc971::RelativePosition::Builder flipper_arm_left_builder =
+ builder.MakeBuilder<frc971::RelativePosition>();
+ flipper_arm_left_builder.add_encoder(flipper_arm_left_);
+ flatbuffers::Offset<frc971::RelativePosition> flipper_arm_left_offset =
+ flipper_arm_left_builder.Finish();
+
+ frc971::RelativePosition::Builder flipper_arm_right_builder =
+ builder.MakeBuilder<frc971::RelativePosition>();
+ flipper_arm_right_builder.add_encoder(flipper_arm_right_);
+ flatbuffers::Offset<frc971::RelativePosition> flipper_arm_right_offset =
+ flipper_arm_left_builder.Finish();
+
Position::Builder position_builder = builder.MakeBuilder<Position>();
position_builder.add_intake_front(intake_front_offset);
@@ -251,6 +263,11 @@
position_builder.add_turret(turret_offset);
position_builder.add_catapult(catapult_offset);
position_builder.add_climber(climber_offset);
+ position_builder.add_intake_beambreak_front(intake_beambreak_front_);
+ position_builder.add_intake_beambreak_back(intake_beambreak_back_);
+ position_builder.add_turret_beambreak(turret_beambreak_);
+ position_builder.add_flipper_arm_left(flipper_arm_left_offset);
+ position_builder.add_flipper_arm_right(flipper_arm_right_offset);
CHECK_EQ(builder.Send(position_builder.Finish()),
aos::RawSender::Error::kOk);
@@ -262,6 +279,19 @@
PotAndAbsoluteEncoderSimulator *catapult() { return &catapult_; }
RelativeEncoderSimulator *climber() { return &climber_; }
+ void set_intake_beambreak_front(bool triggered) {
+ intake_beambreak_front_ = triggered;
+ }
+
+ void set_intake_beambreak_back(bool triggered) {
+ intake_beambreak_back_ = triggered;
+ }
+
+ void set_turret_beambreak(bool triggered) { turret_beambreak_ = triggered; }
+
+ void set_flipper_arm_left(double pos) { flipper_arm_left_ = pos; }
+ void set_flipper_arm_right(double pos) { flipper_arm_right_ = pos; }
+
private:
::aos::EventLoop *event_loop_;
const chrono::nanoseconds dt_;
@@ -273,6 +303,11 @@
bool first_ = true;
+ bool intake_beambreak_front_ = false;
+ bool intake_beambreak_back_ = false;
+ bool turret_beambreak_ = false;
+ double flipper_arm_left_ = 0.0;
+ double flipper_arm_right_ = 0.0;
PotAndAbsoluteEncoderSimulator intake_front_;
PotAndAbsoluteEncoderSimulator intake_back_;
PotAndAbsoluteEncoderSimulator turret_;
@@ -321,7 +356,7 @@
unlink(FLAGS_output_folder.c_str());
logger_event_loop_ = MakeEventLoop("logger", roborio_);
logger_ = std::make_unique<aos::logger::Logger>(logger_event_loop_.get());
- logger_->StartLoggingLocalNamerOnRun(FLAGS_output_folder);
+ logger_->StartLoggingOnRun(FLAGS_output_folder);
}
}
@@ -343,11 +378,6 @@
0.001);
}
- if (superstructure_goal_fetcher_->has_turret()) {
- EXPECT_NEAR(superstructure_goal_fetcher_->turret()->unsafe_goal(),
- superstructure_status_fetcher_->turret()->position(), 0.001);
- }
-
if (superstructure_goal_fetcher_->has_catapult() &&
superstructure_goal_fetcher_->catapult()->has_return_position()) {
EXPECT_NEAR(superstructure_goal_fetcher_->catapult()
@@ -361,7 +391,23 @@
EXPECT_NEAR(superstructure_goal_fetcher_->climber()->unsafe_goal(),
superstructure_status_fetcher_->climber()->position(), 0.001);
}
- }
+
+ if (superstructure_status_fetcher_->intake_state() !=
+ IntakeState::NO_BALL) {
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_front(), 0.0);
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_back(), 0.0);
+ }
+
+ EXPECT_NEAR(superstructure_goal_fetcher_->climber()->unsafe_goal(),
+ superstructure_status_fetcher_->climber()->position(), 0.001);
+
+ if (superstructure_goal_fetcher_->has_turret() &&
+ superstructure_status_fetcher_->state() !=
+ SuperstructureState::TRANSFERRING) {
+ EXPECT_NEAR(superstructure_goal_fetcher_->turret()->unsafe_goal(),
+ superstructure_status_fetcher_->turret()->position(), 0.001);
+ }
+ } // namespace testing
void CheckIfZeroed() {
superstructure_status_fetcher_.Fetch();
@@ -384,15 +430,25 @@
}
void SendRobotVelocity(double robot_velocity) {
+ SendDrivetrainStatus(robot_velocity, {0.0, 0.0}, 0.0);
+ }
+
+ void SendDrivetrainStatus(double robot_velocity, Eigen::Vector2d pos,
+ double theta) {
// Send a robot velocity to test compensation
auto builder = drivetrain_status_sender_.MakeBuilder();
auto drivetrain_status_builder = builder.MakeBuilder<DrivetrainStatus>();
drivetrain_status_builder.add_robot_speed(robot_velocity);
+ drivetrain_status_builder.add_estimated_left_velocity(robot_velocity);
+ drivetrain_status_builder.add_estimated_right_velocity(robot_velocity);
+ drivetrain_status_builder.add_x(pos.x());
+ drivetrain_status_builder.add_y(pos.y());
+ drivetrain_status_builder.add_theta(theta);
builder.CheckOk(builder.Send(drivetrain_status_builder.Finish()));
}
void TestRollerFront(double roller_speed_front,
- double roller_speed_compensation) {
+ double roller_speed_compensation, double expected) {
auto builder = superstructure_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_roller_speed_front(roller_speed_front);
@@ -400,18 +456,11 @@
builder.CheckOk(builder.Send(goal_builder.Finish()));
RunFor(dt() * 2);
ASSERT_TRUE(superstructure_output_fetcher_.Fetch());
- EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_front(),
- roller_speed_front + std::max((superstructure_.robot_velocity() *
- roller_speed_compensation),
- 0.0));
- if (superstructure_.robot_velocity() <= 0) {
- EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_front(),
- roller_speed_front);
- }
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_front(), expected);
}
void TestRollerBack(double roller_speed_back,
- double roller_speed_compensation) {
+ double roller_speed_compensation, double expected) {
auto builder = superstructure_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
goal_builder.add_roller_speed_back(roller_speed_back);
@@ -420,28 +469,8 @@
RunFor(dt() * 2);
ASSERT_TRUE(superstructure_output_fetcher_.Fetch());
ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
- EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_back(),
- roller_speed_back - std::min(superstructure_.robot_velocity() *
- roller_speed_compensation,
- 0.0));
- if (superstructure_.robot_velocity() >= 0) {
- EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_back(),
- roller_speed_back);
- }
- }
- void TestTransferRoller(double transfer_roller_speed,
- double roller_speed_compensation) {
- auto builder = superstructure_goal_sender_.MakeBuilder();
- Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
- goal_builder.add_transfer_roller_speed(transfer_roller_speed);
- goal_builder.add_roller_speed_compensation(roller_speed_compensation);
- builder.CheckOk(builder.Send(goal_builder.Finish()));
- RunFor(dt() * 2);
- ASSERT_TRUE(superstructure_output_fetcher_.Fetch());
- ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
- EXPECT_EQ(superstructure_output_fetcher_->transfer_roller_voltage(),
- transfer_roller_speed);
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_back(), expected);
}
std::shared_ptr<const constants::Values> values_;
@@ -466,7 +495,7 @@
std::unique_ptr<aos::EventLoop> logger_event_loop_;
std::unique_ptr<aos::logger::Logger> logger_;
-};
+}; // namespace testing
// Tests that the superstructure does nothing when the goal is to remain
// still.
@@ -537,22 +566,22 @@
auto builder = superstructure_goal_sender_.MakeBuilder();
flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
intake_offset_front = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
- *builder.fbb(), constants::Values::kIntakeRange().upper,
+ *builder.fbb(), constants::Values::kIntakeRange().lower,
CreateProfileParameters(*builder.fbb(), 1.0, 0.2));
flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
intake_offset_back = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
- *builder.fbb(), constants::Values::kIntakeRange().upper,
+ *builder.fbb(), constants::Values::kIntakeRange().lower,
CreateProfileParameters(*builder.fbb(), 1.0, 0.2));
flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
turret_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
- *builder.fbb(), constants::Values::kTurretRange().upper,
+ *builder.fbb(), constants::Values::kTurretRange().lower,
CreateProfileParameters(*builder.fbb(), 1.0, 0.2));
flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
climber_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
- *builder.fbb(), constants::Values::kClimberRange().upper,
+ *builder.fbb(), constants::Values::kClimberRange().lower,
CreateProfileParameters(*builder.fbb(), 1.0, 0.2));
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
@@ -587,11 +616,11 @@
flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
intake_offset_front = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
- *builder.fbb(), constants::Values::kIntakeRange().lower);
+ *builder.fbb(), constants::Values::kIntakeRange().upper);
flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
intake_offset_back = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
- *builder.fbb(), constants::Values::kIntakeRange().lower);
+ *builder.fbb(), constants::Values::kIntakeRange().upper);
// Keep the turret away from the intakes because they start in the collision
// area
@@ -601,7 +630,7 @@
flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
climber_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
- *builder.fbb(), constants::Values::kClimberRange().lower);
+ *builder.fbb(), constants::Values::kClimberRange().upper);
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
@@ -624,22 +653,22 @@
flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
intake_offset_front = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
- *builder.fbb(), constants::Values::kIntakeRange().upper,
+ *builder.fbb(), constants::Values::kIntakeRange().lower,
CreateProfileParameters(*builder.fbb(), 20.0, 0.1));
flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
intake_offset_back = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
- *builder.fbb(), constants::Values::kIntakeRange().upper,
+ *builder.fbb(), constants::Values::kIntakeRange().lower,
CreateProfileParameters(*builder.fbb(), 20.0, 0.1));
flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
turret_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
- *builder.fbb(), constants::Values::kTurretRange().upper,
+ *builder.fbb(), constants::Values::kTurretRange().lower,
CreateProfileParameters(*builder.fbb(), 20.0, 0.1));
flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
climber_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
- *builder.fbb(), constants::Values::kClimberRange().upper,
+ *builder.fbb(), constants::Values::kClimberRange().lower,
CreateProfileParameters(*builder.fbb(), 20.0, 0.1));
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
@@ -699,28 +728,320 @@
WaitUntilZeroed();
SendRobotVelocity(3.0);
- TestRollerFront(-12.0, 1.5);
- TestRollerFront(12.0, 1.5);
- TestRollerFront(0.0, 1.5);
+ TestRollerFront(-12.0, 1.5, -7.5);
+ TestRollerFront(12.0, 1.5, 16.5);
+ TestRollerFront(0.0, 1.5, 4.5);
SendRobotVelocity(-3.0);
- TestRollerFront(-12.0, 1.5);
- TestRollerFront(12.0, 1.5);
- TestRollerFront(0.0, 1.5);
+ TestRollerFront(-12.0, 1.5, -12.0);
+ TestRollerFront(12.0, 1.5, 12.0);
+ TestRollerFront(0.0, 1.5, 0.0);
SendRobotVelocity(3.0);
- TestRollerBack(-12.0, 1.5);
- TestRollerBack(12.0, 1.5);
- TestRollerBack(0.0, 1.5);
+ TestRollerBack(-12.0, 1.5, -12.0);
+ TestRollerBack(12.0, 1.5, 12.0);
+ TestRollerBack(0.0, 1.5, 0.0);
SendRobotVelocity(-3.0);
- TestRollerBack(-12.0, 1.5);
- TestRollerBack(12.0, 1.5);
- TestRollerBack(0.0, 1.5);
+ TestRollerBack(-12.0, 1.5, -7.5);
+ TestRollerBack(12.0, 1.5, 16.5);
+ TestRollerBack(0.0, 1.5, 4.5);
+}
- TestTransferRoller(-12.0, 1.5);
- TestTransferRoller(12.0, 1.5);
- TestTransferRoller(0.0, 1.5);
+// Tests the whole shooting statemachine - from loading to shooting
+TEST_F(SuperstructureTest, LoadingToShooting) {
+ SetEnabled(true);
+ WaitUntilZeroed();
+
+ SendRobotVelocity(3.0);
+
+ constexpr double kTurretGoal = 3.0;
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+ flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
+ turret_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *builder.fbb(), kTurretGoal);
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+ goal_builder.add_roller_speed_front(12.0);
+ goal_builder.add_roller_speed_back(12.0);
+ goal_builder.add_roller_speed_compensation(0.0);
+ goal_builder.add_turret(turret_offset);
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
+ }
+ RunFor(std::chrono::seconds(2));
+
+ // Make sure that the rollers are spinning, but the superstructure hasn't
+ // transitioned away from idle because the beambreaks haven't been triggered.
+ ASSERT_TRUE(superstructure_output_fetcher_.Fetch());
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_front(), 12.0);
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_back(), 12.0);
+
+ EXPECT_EQ(superstructure_output_fetcher_->transfer_roller_voltage_front(),
+ 0.0);
+ EXPECT_EQ(superstructure_output_fetcher_->transfer_roller_voltage_back(),
+ 0.0);
+ EXPECT_EQ(superstructure_status_fetcher_->state(), SuperstructureState::IDLE);
+ EXPECT_EQ(superstructure_status_fetcher_->intake_state(),
+ IntakeState::NO_BALL);
+ // Since we spun the front rollers, the turret should be trying to intake from
+ // there
+ EXPECT_NEAR(superstructure_status_fetcher_->turret()->position(),
+ constants::Values::kTurretFrontIntakePos(), 0.001);
+ EXPECT_EQ(superstructure_status_fetcher_->shot_count(), 0);
+
+ superstructure_plant_.set_intake_beambreak_front(true);
+ superstructure_plant_.set_intake_beambreak_back(false);
+ RunFor(dt());
+
+ // Make sure that the turret goal is set to be loading from the front intake
+ // and the supersturcture is transferring from the front intake, since that
+ // beambreak was trigerred. Also, the outside rollers should be stopped
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ ASSERT_TRUE(superstructure_output_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_status_fetcher_->state(),
+ SuperstructureState::TRANSFERRING);
+ EXPECT_EQ(superstructure_status_fetcher_->intake_state(),
+ IntakeState::INTAKE_FRONT_BALL);
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_front(), 0.0);
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_back(), 0.0);
+
+ RunFor(chrono::seconds(2));
+
+ // Make sure that we are still transferring and the front transfer rollers
+ // still have a ball. The turret should now be at the loading position and the
+ // flippers should be feeding the ball.
+ ASSERT_TRUE(superstructure_output_fetcher_.Fetch());
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_front(), 0.0);
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_back(), 0.0);
+ EXPECT_EQ(superstructure_status_fetcher_->state(),
+ SuperstructureState::TRANSFERRING);
+ EXPECT_EQ(superstructure_status_fetcher_->intake_state(),
+ IntakeState::INTAKE_FRONT_BALL);
+ EXPECT_EQ(superstructure_output_fetcher_->flipper_arms_voltage(),
+ constants::Values::kFlipperFeedVoltage());
+ EXPECT_EQ(superstructure_output_fetcher_->transfer_roller_voltage_front(),
+ constants::Values::kTransferRollerVoltage());
+ EXPECT_EQ(superstructure_output_fetcher_->transfer_roller_voltage_back(),
+ -constants::Values::kTransferRollerVoltage());
+ EXPECT_NEAR(superstructure_status_fetcher_->turret()->position(),
+ constants::Values::kTurretFrontIntakePos(), 0.001);
+ EXPECT_EQ(superstructure_status_fetcher_->shot_count(), 0);
+
+ superstructure_plant_.set_intake_beambreak_front(false);
+ superstructure_plant_.set_intake_beambreak_back(false);
+ superstructure_plant_.set_turret_beambreak(true);
+ RunFor(dt() * 2);
+
+ // Now that the turret beambreak has been triggered, we should be loading the
+ // ball. The outside rollers shouldn't be limited anymore, and the transfer
+ // rollers should be off. The flippers should still be feeding the ball, and
+ // the intake state should reflect that the ball has been transferred away
+ ASSERT_TRUE(superstructure_output_fetcher_.Fetch());
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_front(), 12.0);
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_back(), 12.0);
+ EXPECT_EQ(superstructure_output_fetcher_->transfer_roller_voltage_front(),
+ 0.0);
+ EXPECT_EQ(superstructure_output_fetcher_->transfer_roller_voltage_back(),
+ 0.0);
+ EXPECT_EQ(superstructure_status_fetcher_->state(),
+ SuperstructureState::LOADING);
+ EXPECT_EQ(superstructure_status_fetcher_->intake_state(),
+ IntakeState::NO_BALL);
+ EXPECT_EQ(superstructure_output_fetcher_->flipper_arms_voltage(),
+ constants::Values::kFlipperFeedVoltage());
+ EXPECT_EQ(superstructure_status_fetcher_->shot_count(), 0);
+
+ superstructure_plant_.set_turret_beambreak(false);
+ RunFor(constants::Values::kExtraLoadingTime() + dt() * 2);
+
+ // Now that the ball has gone past the turret beambreak,
+ // it should be loaded in the catapult and ready for firing.
+ // The flippers should be off.
+ ASSERT_TRUE(superstructure_output_fetcher_.Fetch());
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_front(), 12.0);
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_back(), 12.0);
+ EXPECT_EQ(superstructure_output_fetcher_->transfer_roller_voltage_front(),
+ 0.0);
+ EXPECT_EQ(superstructure_output_fetcher_->transfer_roller_voltage_back(),
+ 0.0);
+ EXPECT_EQ(superstructure_status_fetcher_->state(),
+ SuperstructureState::LOADED);
+ EXPECT_EQ(superstructure_status_fetcher_->intake_state(),
+ IntakeState::NO_BALL);
+ EXPECT_EQ(superstructure_output_fetcher_->flipper_arms_voltage(), 0.0);
+ EXPECT_EQ(superstructure_status_fetcher_->shot_count(), 0);
+
+ RunFor(std::chrono::seconds(2));
+
+ // After a few seconds, the turret should be at it's aiming goal. The flippers
+ // should still be off and we should still be loaded and ready to fire.
+ ASSERT_TRUE(superstructure_output_fetcher_.Fetch());
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_front(), 12.0);
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_back(), 12.0);
+ EXPECT_EQ(superstructure_output_fetcher_->transfer_roller_voltage_front(),
+ 0.0);
+ EXPECT_EQ(superstructure_output_fetcher_->transfer_roller_voltage_back(),
+ 0.0);
+ EXPECT_EQ(superstructure_status_fetcher_->state(),
+ SuperstructureState::LOADED);
+ EXPECT_EQ(superstructure_status_fetcher_->intake_state(),
+ IntakeState::NO_BALL);
+ EXPECT_EQ(superstructure_output_fetcher_->flipper_arms_voltage(), 0.0);
+ EXPECT_NEAR(superstructure_status_fetcher_->turret()->position(), kTurretGoal,
+ 0.001);
+ EXPECT_EQ(superstructure_status_fetcher_->shot_count(), 0);
+
+ superstructure_plant_.set_intake_beambreak_front(false);
+ superstructure_plant_.set_intake_beambreak_back(true);
+ RunFor(dt() * 2);
+
+ // A ball being intaked from the back should be held by wiggling the transfer
+ // rollers, but we shound't abort the shot from the front intake for it and
+ // move the turret.
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ ASSERT_TRUE(superstructure_output_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_front(), 0.0);
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_back(), 0.0);
+ EXPECT_TRUE(superstructure_output_fetcher_->transfer_roller_voltage_front() !=
+ 0.0 &&
+ superstructure_output_fetcher_->transfer_roller_voltage_front() <=
+ constants::Values::kTransferRollerWiggleVoltage() &&
+ superstructure_output_fetcher_->transfer_roller_voltage_front() >=
+ -constants::Values::kTransferRollerWiggleVoltage());
+ EXPECT_EQ(superstructure_output_fetcher_->transfer_roller_voltage_back(),
+ -superstructure_output_fetcher_->transfer_roller_voltage_front());
+ EXPECT_EQ(superstructure_status_fetcher_->state(),
+ SuperstructureState::LOADED);
+ EXPECT_EQ(superstructure_status_fetcher_->intake_state(),
+ IntakeState::INTAKE_BACK_BALL);
+ EXPECT_NEAR(superstructure_status_fetcher_->turret()->position(), kTurretGoal,
+ 0.001);
+
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+ flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
+ turret_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *builder.fbb(), kTurretGoal);
+
+ const auto catapult_return_offset =
+ CreateStaticZeroingSingleDOFProfiledSubsystemGoal(*builder.fbb(),
+ -0.87);
+ auto catapult_builder = builder.MakeBuilder<CatapultGoal>();
+ catapult_builder.add_shot_position(0.3);
+ catapult_builder.add_shot_velocity(15.0);
+ catapult_builder.add_return_position(catapult_return_offset);
+ auto catapult_offset = catapult_builder.Finish();
+
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+ goal_builder.add_roller_speed_front(12.0);
+ goal_builder.add_roller_speed_back(12.0);
+ goal_builder.add_roller_speed_compensation(0.0);
+ goal_builder.add_catapult(catapult_offset);
+ goal_builder.add_fire(true);
+ goal_builder.add_turret(turret_offset);
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
+ }
+ superstructure_plant_.set_flipper_arm_left(
+ constants::Values::kFlipperArmRange().upper);
+ superstructure_plant_.set_flipper_arm_right(
+ constants::Values::kFlipperArmRange().upper);
+ RunFor(dt() * 2);
+
+ // Now that we were asked to fire and the flippers are open,
+ // we should be shooting the ball and holding the flippers open.
+ // The turret should still be at its goal, and we should still be wiggling the
+ // transfer rollers to keep the ball in the back intake
+ ASSERT_TRUE(superstructure_output_fetcher_.Fetch());
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_front(), 0.0);
+ EXPECT_EQ(superstructure_output_fetcher_->roller_voltage_back(), 0.0);
+ EXPECT_TRUE(superstructure_output_fetcher_->transfer_roller_voltage_back() !=
+ 0.0 &&
+ superstructure_output_fetcher_->transfer_roller_voltage_back() <=
+ constants::Values::kTransferRollerWiggleVoltage() &&
+ superstructure_output_fetcher_->transfer_roller_voltage_back() >=
+ -constants::Values::kTransferRollerWiggleVoltage());
+ EXPECT_EQ(superstructure_output_fetcher_->transfer_roller_voltage_front(),
+ -superstructure_output_fetcher_->transfer_roller_voltage_back());
+ EXPECT_EQ(superstructure_status_fetcher_->state(),
+ SuperstructureState::SHOOTING);
+ EXPECT_EQ(superstructure_status_fetcher_->intake_state(),
+ IntakeState::INTAKE_BACK_BALL);
+ EXPECT_TRUE(superstructure_status_fetcher_->flippers_open());
+ EXPECT_EQ(superstructure_output_fetcher_->flipper_arms_voltage(),
+ constants::Values::kFlipperHoldVoltage());
+ EXPECT_NEAR(superstructure_status_fetcher_->turret()->position(), kTurretGoal,
+ 0.001);
+ EXPECT_EQ(superstructure_status_fetcher_->shot_count(), 0);
+
+ superstructure_plant_.set_flipper_arm_left(
+ constants::Values::kFlipperArmRange().upper);
+ superstructure_plant_.set_flipper_arm_right(
+ constants::Values::kFlipperArmRange().upper);
+ superstructure_plant_.set_intake_beambreak_back(false);
+ RunFor(std::chrono::seconds(2));
+
+ // After a bit, we should have completed the shot and be idle.
+ // Since the beambreak was triggered a bit ago, it should still think a ball
+ // is there
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_status_fetcher_->shot_count(), 1);
+ EXPECT_EQ(superstructure_status_fetcher_->state(), SuperstructureState::IDLE);
+ EXPECT_EQ(superstructure_status_fetcher_->intake_state(),
+ IntakeState::INTAKE_BACK_BALL);
+
+ // Since the intake beambreak hasn't triggered in a while, it should realize
+ // the ball was lost
+ RunFor(std::chrono::seconds(1));
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_status_fetcher_->shot_count(), 1);
+ EXPECT_EQ(superstructure_status_fetcher_->state(), SuperstructureState::IDLE);
+ EXPECT_EQ(superstructure_status_fetcher_->intake_state(),
+ IntakeState::NO_BALL);
+}
+
+TEST_F(SuperstructureTest, TestTurretWrapsWhenLoading) {
+ SetEnabled(true);
+ WaitUntilZeroed();
+
+ constexpr double kTurretGoal = -4.0;
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+ flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
+ turret_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *builder.fbb(), kTurretGoal);
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+ goal_builder.add_turret(turret_offset);
+ builder.CheckOk(builder.Send(goal_builder.Finish()));
+ }
+ RunFor(std::chrono::seconds(5));
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_status_fetcher_->state(), SuperstructureState::IDLE);
+ EXPECT_EQ(superstructure_status_fetcher_->intake_state(),
+ IntakeState::NO_BALL);
+ EXPECT_NEAR(superstructure_status_fetcher_->turret()->position(), kTurretGoal,
+ 0.001);
+
+ superstructure_plant_.set_intake_beambreak_back(true);
+ RunFor(dt() * 2);
+
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_status_fetcher_->state(),
+ SuperstructureState::TRANSFERRING);
+ EXPECT_EQ(superstructure_status_fetcher_->intake_state(),
+ IntakeState::INTAKE_BACK_BALL);
+
+ RunFor(std::chrono::seconds(3));
+
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_NEAR(superstructure_status_fetcher_->turret()->position(),
+ -constants::Values::kTurretBackIntakePos(), 0.001);
+ // it chooses -pi because -pi is closer to -4 than positive pi
}
// Make sure that the front and back intakes are never switched
@@ -776,9 +1097,11 @@
TEST_F(SuperstructureTest, ShootCatapult) {
SetEnabled(true);
superstructure_plant_.intake_front()->InitializePosition(
- constants::Values::kIntakeRange().middle());
+ constants::Values::kIntakeRange().lower);
superstructure_plant_.intake_back()->InitializePosition(
- constants::Values::kIntakeRange().middle());
+ constants::Values::kIntakeRange().lower);
+ superstructure_plant_.turret()->InitializePosition(
+ constants::Values::kTurretFrontIntakePos());
WaitUntilZeroed();
@@ -794,7 +1117,6 @@
CatapultGoal::Builder catapult_goal_builder =
builder.MakeBuilder<CatapultGoal>();
- catapult_goal_builder.add_fire(false);
catapult_goal_builder.add_shot_position(0.3);
catapult_goal_builder.add_shot_velocity(15.0);
catapult_goal_builder.add_return_position(catapult_return_position_offset);
@@ -802,6 +1124,7 @@
catapult_goal_builder.Finish();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+ goal_builder.add_fire(false);
goal_builder.add_catapult(catapult_goal_offset);
ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
}
@@ -817,6 +1140,10 @@
auto builder = superstructure_goal_sender_.MakeBuilder();
flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
+ turret_goal_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *builder.fbb(), constants::Values::kTurretFrontIntakePos());
+
+ flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
catapult_return_position_offset =
CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
*builder.fbb(), constants::Values::kCatapultRange().lower,
@@ -825,7 +1152,6 @@
CatapultGoal::Builder catapult_goal_builder =
builder.MakeBuilder<CatapultGoal>();
- catapult_goal_builder.add_fire(true);
catapult_goal_builder.add_shot_position(0.5);
catapult_goal_builder.add_shot_velocity(20.0);
catapult_goal_builder.add_return_position(catapult_return_position_offset);
@@ -834,11 +1160,28 @@
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+ goal_builder.add_fire(true);
goal_builder.add_catapult(catapult_goal_offset);
+ goal_builder.add_turret(turret_goal_offset);
ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
}
- RunFor(chrono::milliseconds(100));
+ // Make the superstructure statemachine progress to SHOOTING
+ superstructure_plant_.set_intake_beambreak_front(true);
+ superstructure_plant_.set_turret_beambreak(true);
+ superstructure_plant_.set_flipper_arm_left(
+ constants::Values::kFlipperArmRange().upper);
+ superstructure_plant_.set_flipper_arm_right(
+ constants::Values::kFlipperArmRange().upper);
+
+ RunFor(dt() * 4);
+
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_status_fetcher_->state(),
+ SuperstructureState::LOADING);
+ superstructure_plant_.set_turret_beambreak(false);
+
+ RunFor(chrono::milliseconds(200));
ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
EXPECT_TRUE(superstructure_status_fetcher_->mpc_active());
@@ -846,12 +1189,105 @@
EXPECT_GT(superstructure_status_fetcher_->catapult()->position(),
constants::Values::kCatapultRange().lower + 0.1);
+ EXPECT_EQ(superstructure_status_fetcher_->state(),
+ SuperstructureState::SHOOTING);
+ superstructure_plant_.set_intake_beambreak_front(false);
+
RunFor(chrono::milliseconds(1950));
ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
EXPECT_NEAR(superstructure_status_fetcher_->catapult()->position(),
constants::Values::kCatapultRange().lower, 1e-3);
EXPECT_EQ(superstructure_status_fetcher_->shot_count(), 1);
+ EXPECT_EQ(superstructure_status_fetcher_->state(), SuperstructureState::IDLE);
+}
+
+// Test that we are able to signal that the ball was preloaded
+TEST_F(SuperstructureTest, Preloaded) {
+ SetEnabled(true);
+ WaitUntilZeroed();
+
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+ goal_builder.add_preloaded(true);
+ ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
+ }
+
+ RunFor(dt());
+
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+ EXPECT_EQ(superstructure_status_fetcher_->state(),
+ SuperstructureState::LOADED);
+}
+
+// Tests that the turret switches to auto-aiming when we set auto_aim to
+// true.
+TEST_F(SuperstructureTest, TurretAutoAim) {
+ SetEnabled(true);
+ WaitUntilZeroed();
+
+ // Set ourselves up 5m from the target--the turret goal should be 90 deg (we
+ // need to shoot out the right of the robot, and we shoot out of the back of
+ // the turret).
+ SendDrivetrainStatus(0.0, {0.0, 5.0}, 0.0);
+
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+
+ goal_builder.add_auto_aim(true);
+
+ ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
+ }
+
+ // Give it time to stabilize.
+ RunFor(chrono::seconds(2));
+
+ superstructure_status_fetcher_.Fetch();
+ EXPECT_NEAR(M_PI_2, superstructure_status_fetcher_->turret()->position(),
+ 5e-4);
+ EXPECT_FLOAT_EQ(M_PI_2,
+ superstructure_status_fetcher_->aimer()->turret_position());
+ EXPECT_FLOAT_EQ(0,
+ superstructure_status_fetcher_->aimer()->turret_velocity());
+}
+
+TEST_F(SuperstructureTest, InterpolationTableTest) {
+ SetEnabled(true);
+ WaitUntilZeroed();
+
+ constexpr double kDistance = 3.0;
+
+ SendDrivetrainStatus(0.0, {0.0, kDistance}, 0.0);
+
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+
+ goal_builder.add_auto_aim(true);
+
+ ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
+ }
+
+ // Give it time to stabilize.
+ RunFor(chrono::seconds(2));
+
+ ASSERT_TRUE(superstructure_status_fetcher_.Fetch());
+
+ EXPECT_NEAR(superstructure_status_fetcher_->aimer()->target_distance(),
+ kDistance, 0.01);
+
+ constants::Values::ShotParams shot_params;
+ EXPECT_TRUE(
+ values_->shot_interpolation_table.GetInRange(kDistance, &shot_params));
+
+ EXPECT_EQ(superstructure_status_fetcher_->shot_velocity(),
+ shot_params.shot_velocity);
+ EXPECT_EQ(superstructure_status_fetcher_->shot_position(),
+ shot_params.shot_angle);
}
} // namespace testing
diff --git a/y2022/control_loops/superstructure/superstructure_output.fbs b/y2022/control_loops/superstructure/superstructure_output.fbs
index a673361..af6c292 100644
--- a/y2022/control_loops/superstructure/superstructure_output.fbs
+++ b/y2022/control_loops/superstructure/superstructure_output.fbs
@@ -23,10 +23,11 @@
intake_voltage_back:double (id: 5);
// Intake roller voltages
+ // positive is pulling into the robot
roller_voltage_front:double (id: 6);
roller_voltage_back:double (id: 7);
- // One transfer motor for both sides
- transfer_roller_voltage:double (id: 8);
+ transfer_roller_voltage_front:double (id: 8);
+ transfer_roller_voltage_back:double (id: 9);
}
root_type Output;
diff --git a/y2022/control_loops/superstructure/superstructure_plotter.ts b/y2022/control_loops/superstructure/superstructure_plotter.ts
index 6581758..f8c3a7c 100644
--- a/y2022/control_loops/superstructure/superstructure_plotter.ts
+++ b/y2022/control_loops/superstructure/superstructure_plotter.ts
@@ -6,7 +6,7 @@
import Connection = proxy.Connection;
const TIME = AosPlotter.TIME;
-const DEFAULT_WIDTH = AosPlotter.DEFAULT_WIDTH;
+const DEFAULT_WIDTH = AosPlotter.DEFAULT_WIDTH * 2;
const DEFAULT_HEIGHT = AosPlotter.DEFAULT_HEIGHT * 3;
export function plotSuperstructure(conn: Connection, element: Element): void {
@@ -20,4 +20,65 @@
const position = aosPlotter.addMessageSource(
'/superstructure', 'y2022.control_loops.superstructure.Position');
const robotState = aosPlotter.addMessageSource('/aos', 'aos.RobotState');
+
+ const positionPlot =
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ positionPlot.plot.getAxisLabels().setTitle('States');
+ positionPlot.plot.getAxisLabels().setXLabel(TIME);
+ positionPlot.plot.getAxisLabels().setYLabel('wonky state units');
+ positionPlot.plot.setDefaultYRange([-1.0, 2.0]);
+
+ positionPlot.addMessageLine(position, ['turret_beambreak'])
+ .setColor(RED)
+ .setPointSize(4.0);
+ positionPlot.addMessageLine(status, ['state'])
+ .setColor(CYAN)
+ .setPointSize(1.0);
+ positionPlot.addMessageLine(status, ['flippers_open'])
+ .setColor(WHITE)
+ .setPointSize(1.0);
+ positionPlot.addMessageLine(status, ['reseating_in_catapult'])
+ .setColor(BLUE)
+ .setPointSize(1.0);
+ positionPlot.addMessageLine(status, ['fire'])
+ .setColor(CYAN)
+ .setPointSize(1.0);
+
+
+ const intakePlot =
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ intakePlot.plot.getAxisLabels().setTitle('Intake');
+ intakePlot.plot.getAxisLabels().setXLabel(TIME);
+ intakePlot.plot.getAxisLabels().setYLabel('wonky state units');
+ intakePlot.plot.setDefaultYRange([-1.0, 2.0]);
+ intakePlot.addMessageLine(status, ['intake_state'])
+ .setColor(RED)
+ .setPointSize(1.0);
+ intakePlot.addMessageLine(position, ['intake_beambreak_front'])
+ .setColor(GREEN)
+ .setPointSize(4.0);
+ intakePlot.addMessageLine(position, ['intake_beambreak_back'])
+ .setColor(PINK)
+ .setPointSize(1.0);
+
+
+ const otherPlot =
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ otherPlot.plot.getAxisLabels().setTitle('Position');
+ otherPlot.plot.getAxisLabels().setXLabel(TIME);
+ otherPlot.plot.getAxisLabels().setYLabel('rad');
+ otherPlot.plot.setDefaultYRange([-1.0, 2.0]);
+
+ otherPlot.addMessageLine(status, ['catapult', 'position'])
+ .setColor(PINK)
+ .setPointSize(4.0);
+ otherPlot.addMessageLine(position, ['flipper_arm_left', 'encoder'])
+ .setColor(BLUE)
+ .setPointSize(4.0);
+ otherPlot.addMessageLine(position, ['flipper_arm_right', 'encoder'])
+ .setColor(CYAN)
+ .setPointSize(4.0);
+ otherPlot.addMessageLine(output, ['flipper_arms_voltage'])
+ .setColor(BROWN)
+ .setPointSize(4.0);
}
diff --git a/y2022/control_loops/superstructure/superstructure_position.fbs b/y2022/control_loops/superstructure/superstructure_position.fbs
index 46dd547..ba47662 100644
--- a/y2022/control_loops/superstructure/superstructure_position.fbs
+++ b/y2022/control_loops/superstructure/superstructure_position.fbs
@@ -4,14 +4,14 @@
table Position {
climber:frc971.RelativePosition (id: 0);
- // Zero for the intake position value is up, and positive is
- // down.
+ // Zero for the intake position value is horizontal, and positive is
+ // up.
intake_front:frc971.PotAndAbsolutePosition (id: 1);
intake_back:frc971.PotAndAbsolutePosition (id: 2);
- // Zero is forwards; positive = counter-clockwise.
+ // Zero is to the front (away from the RIO); positive = counter-clockwise.
turret:frc971.PotAndAbsolutePosition (id: 3);
- // Zero is straight and positive is open
+ // Zero is closed and positive is open
flipper_arm_left:frc971.RelativePosition (id: 4);
flipper_arm_right:frc971.RelativePosition (id: 5);
diff --git a/y2022/control_loops/superstructure/superstructure_status.fbs b/y2022/control_loops/superstructure/superstructure_status.fbs
index 4487f1d..d802f08 100644
--- a/y2022/control_loops/superstructure/superstructure_status.fbs
+++ b/y2022/control_loops/superstructure/superstructure_status.fbs
@@ -3,12 +3,59 @@
namespace y2022.control_loops.superstructure;
+// Contains which intake has a ball
+enum IntakeState : ubyte {
+ NO_BALL,
+ INTAKE_FRONT_BALL,
+ INTAKE_BACK_BALL,
+}
+
+// State of the superstructure state machine
+enum SuperstructureState : ubyte {
+ // Before a ball is intaked, when neither intake beambreak is triggered
+ IDLE = 0,
+ // Transferring ball with transfer rollers. Moves turret to loading position.
+ TRANSFERRING = 1,
+ // Loading the ball into the catapult
+ LOADING = 2,
+ // The ball is loaded into the catapult
+ LOADED = 3,
+ // Waiting for the turret to be at shooting goal and then telling the
+ // catapult to fire.
+ SHOOTING = 4,
+}
+
+table AimerStatus {
+ // The current goal angle for the turret auto-tracking, in radians.
+ turret_position:double (id: 0);
+ // The current goal velocity for the turret, in radians / sec.
+ turret_velocity:double (id: 1);
+ // The current distance to the target, in meters.
+ target_distance:double (id: 2);
+ // The current "shot distance." When shooting on the fly, this may be
+ // different from the static distance to the target.
+ shot_distance:double (id: 3);
+}
+
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);
+ // The state of the superstructure
+
+ state:SuperstructureState (id: 10);
+ // Intaking state
+ intake_state:IntakeState (id: 11);
+ // Whether the flippers are open for shooting
+ flippers_open:bool (id: 12);
+ // Whether the flippers failed to open and we are retrying
+ reseating_in_catapult:bool (id: 13);
+ // Whether the catapult was told to fire,
+ // meaning that the turret and flippers are ready for firing
+ // and we were asked to fire. Different from fire flag in goal.
+ fire:bool (id: 14);
// Subsystem statuses
climber:frc971.control_loops.RelativeEncoderProfiledJointStatus (id: 2);
@@ -23,9 +70,13 @@
solve_time:double (id: 7);
mpc_active:bool (id: 8);
+ shot_position:double (id: 16);
+ shot_velocity:double (id: 17);
// The number of shots we have taken.
shot_count:int32 (id: 9);
+
+ aimer:AimerStatus (id: 15);
}
root_type Status;
diff --git a/y2022/control_loops/superstructure/turret/BUILD b/y2022/control_loops/superstructure/turret/BUILD
index c2948d7..2f7ad14 100644
--- a/y2022/control_loops/superstructure/turret/BUILD
+++ b/y2022/control_loops/superstructure/turret/BUILD
@@ -32,3 +32,21 @@
"//frc971/control_loops:state_feedback_loop",
],
)
+
+cc_library(
+ name = "aiming",
+ srcs = ["aiming.cc"],
+ hdrs = ["aiming.h"],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ "//aos:flatbuffers",
+ "//frc971/control_loops:control_loops_fbs",
+ "//frc971/control_loops:pose",
+ "//frc971/control_loops:profiled_subsystem_fbs",
+ "//frc971/control_loops/aiming",
+ "//frc971/control_loops/drivetrain:drivetrain_status_fbs",
+ "//y2022:constants",
+ "//y2022/control_loops/drivetrain:drivetrain_base",
+ "//y2022/control_loops/superstructure:superstructure_status_fbs",
+ ],
+)
diff --git a/y2022/control_loops/superstructure/turret/aiming.cc b/y2022/control_loops/superstructure/turret/aiming.cc
new file mode 100644
index 0000000..2a600d8
--- /dev/null
+++ b/y2022/control_loops/superstructure/turret/aiming.cc
@@ -0,0 +1,87 @@
+#include "y2022/control_loops/superstructure/turret/aiming.h"
+
+#include "y2022/constants.h"
+#include "y2022/control_loops/drivetrain/drivetrain_base.h"
+
+namespace y2022 {
+namespace control_loops {
+namespace superstructure {
+namespace turret {
+
+using frc971::control_loops::Pose;
+using frc971::control_loops::aiming::ShotConfig;
+using frc971::control_loops::aiming::RobotState;
+
+namespace {
+// Average speed-over-ground of the ball on its way to the target. Our current
+// model assumes constant ball velocity regardless of shot distance.
+constexpr double kBallSpeedOverGround = 12.0; // m/s
+
+// If the turret is at zero, then it will be at this angle at which the shot
+// will leave the robot. I.e., if the turret is at zero, then the shot will go
+// straight out the back of the robot.
+constexpr double kTurretZeroOffset = M_PI;
+
+constexpr double kMaxProfiledVelocity = 10.0;
+constexpr double kMaxProfiledAccel = 20.0;
+
+flatbuffers::DetachedBuffer MakePrefilledGoal() {
+ flatbuffers::FlatBufferBuilder fbb;
+ fbb.ForceDefaults(true);
+ frc971::ProfileParameters::Builder profile_builder(fbb);
+ profile_builder.add_max_velocity(kMaxProfiledVelocity);
+ profile_builder.add_max_acceleration(kMaxProfiledAccel);
+ const flatbuffers::Offset<frc971::ProfileParameters> profile_offset =
+ profile_builder.Finish();
+ Aimer::Goal::Builder builder(fbb);
+ builder.add_unsafe_goal(0);
+ builder.add_goal_velocity(0);
+ builder.add_ignore_profile(false);
+ builder.add_profile_params(profile_offset);
+ fbb.Finish(builder.Finish());
+ return fbb.Release();
+}
+} // namespace
+
+Aimer::Aimer() : goal_(MakePrefilledGoal()) {}
+
+void Aimer::Update(const Status *status, ShotMode shot_mode) {
+ const Pose robot_pose({status->x(), status->y(), 0}, status->theta());
+ const Pose goal({0.0, 0.0, 0.0}, 0.0);
+
+ const Eigen::Vector2d linear_angular =
+ drivetrain::GetDrivetrainConfig().Tlr_to_la() *
+ Eigen::Vector2d(status->estimated_left_velocity(),
+ status->estimated_right_velocity());
+ const double xdot = linear_angular(0) * std::cos(status->theta());
+ const double ydot = linear_angular(0) * std::sin(status->theta());
+
+ current_goal_ =
+ frc971::control_loops::aiming::AimerGoal(
+ ShotConfig{goal, shot_mode, constants::Values::kTurretRange(),
+ kBallSpeedOverGround,
+ /*wrap_mode=*/0.0, kTurretZeroOffset},
+ RobotState{robot_pose,
+ {xdot, ydot},
+ linear_angular(1),
+ goal_.message().unsafe_goal()});
+
+ goal_.mutable_message()->mutate_unsafe_goal(current_goal_.position);
+ goal_.mutable_message()->mutate_goal_velocity(
+ std::clamp(current_goal_.velocity, -2.0, 2.0));
+}
+
+flatbuffers::Offset<AimerStatus> Aimer::PopulateStatus(
+ flatbuffers::FlatBufferBuilder *fbb) const {
+ AimerStatus::Builder builder(*fbb);
+ builder.add_turret_position(current_goal_.position);
+ builder.add_turret_velocity(current_goal_.velocity);
+ builder.add_target_distance(current_goal_.target_distance);
+ builder.add_shot_distance(DistanceToGoal());
+ return builder.Finish();
+}
+
+} // namespace turret
+} // namespace superstructure
+} // namespace control_loops
+} // namespace y2022
diff --git a/y2022/control_loops/superstructure/turret/aiming.h b/y2022/control_loops/superstructure/turret/aiming.h
new file mode 100644
index 0000000..9494103
--- /dev/null
+++ b/y2022/control_loops/superstructure/turret/aiming.h
@@ -0,0 +1,40 @@
+#ifndef Y2022_CONTROL_LOOPS_SUPERSTRUCTURE_TURRET_AIMING_H_
+#define Y2022_CONTROL_LOOPS_SUPERSTRUCTURE_TURRET_AIMING_H_
+
+#include "aos/flatbuffers.h"
+#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
+#include "frc971/control_loops/pose.h"
+#include "frc971/control_loops/profiled_subsystem_generated.h"
+#include "frc971/control_loops/aiming/aiming.h"
+#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
+
+namespace y2022::control_loops::superstructure::turret {
+
+// This class manages taking in drivetrain status messages and generating turret
+// goals so that it gets aimed at the goal.
+class Aimer {
+ public:
+ typedef frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal
+ Goal;
+ typedef frc971::control_loops::drivetrain::Status Status;
+ typedef frc971::control_loops::aiming::ShotMode ShotMode;
+
+ Aimer();
+
+ void Update(const Status *status, ShotMode shot_mode);
+
+ const Goal *TurretGoal() const { return &goal_.message(); }
+
+ // Returns the distance to the goal, in meters.
+ double DistanceToGoal() const { return current_goal_.virtual_shot_distance; }
+
+ flatbuffers::Offset<AimerStatus> PopulateStatus(
+ flatbuffers::FlatBufferBuilder *fbb) const;
+
+ private:
+ aos::FlatbufferDetachedBuffer<Goal> goal_;
+ frc971::control_loops::aiming::TurretGoal current_goal_;
+};
+
+} // namespace y2022::control_loops::superstructure::turret
+#endif // Y2020_CONTROL_LOOPS_SUPERSTRUCTURE_TURRET_AIMING_H_
diff --git a/y2022/control_loops/superstructure/turret_plotter.ts b/y2022/control_loops/superstructure/turret_plotter.ts
index 10fc10e..6753880 100644
--- a/y2022/control_loops/superstructure/turret_plotter.ts
+++ b/y2022/control_loops/superstructure/turret_plotter.ts
@@ -29,6 +29,12 @@
positionPlot.addMessageLine(status, ['turret', 'goal_position']).setColor(RED).setPointSize(4.0);
positionPlot.addMessageLine(status, ['turret', 'goal_velocity']).setColor(ORANGE).setPointSize(4.0);
positionPlot.addMessageLine(status, ['turret', 'estimator_state', 'position']).setColor(CYAN).setPointSize(1.0);
+ positionPlot.addMessageLine(status, ['aimer', 'turret_velocity'])
+ .setColor(WHITE)
+ .setPointSize(1.0);
+ positionPlot.addMessageLine(status, ['aimer', 'turret_position'])
+ .setColor(BROWN)
+ .setPointSize(1.0);
const voltagePlot =
aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
diff --git a/y2022/joystick_reader.cc b/y2022/joystick_reader.cc
index a39c130..8423f47 100644
--- a/y2022/joystick_reader.cc
+++ b/y2022/joystick_reader.cc
@@ -10,15 +10,21 @@
#include "aos/network/team_number.h"
#include "aos/util/log_interval.h"
#include "frc971/autonomous/base_autonomous_actor.h"
+#include "frc971/control_loops/drivetrain/localizer_generated.h"
#include "frc971/control_loops/profiled_subsystem_generated.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/zeroing/wrap.h"
+#include "y2022/constants.h"
#include "y2022/control_loops/drivetrain/drivetrain_base.h"
#include "y2022/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
+#include "y2022/setpoint_generated.h"
+using frc971::CreateProfileParameters;
+using frc971::control_loops::CreateStaticZeroingSingleDOFProfiledSubsystemGoal;
using frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
using frc971::input::driver_station::ButtonLocation;
using frc971::input::driver_station::ControlBit;
@@ -29,11 +35,37 @@
namespace input {
namespace joysticks {
-const ButtonLocation kCatapultPos(3, 3);
-const ButtonLocation kFire(3, 1);
-
namespace superstructure = y2022::control_loops::superstructure;
+#if 0
+const ButtonLocation kCatapultPos(4, 3);
+const ButtonLocation kFire(3, 4);
+const ButtonLocation kTurret(4, 15);
+const ButtonLocation kAutoAim(4, 2);
+
+const ButtonLocation kIntakeFrontOut(4, 10);
+const ButtonLocation kIntakeBackOut(4, 9);
+const ButtonLocation kSpit(3, 3);
+
+const ButtonLocation kRedLocalizerReset(3, 13);
+const ButtonLocation kBlueLocalizerReset(3, 14);
+const ButtonLocation kLocalizerReset(3, 8);
+#else
+
+const ButtonLocation kCatapultPos(4, 3);
+const ButtonLocation kFire(4, 1);
+const ButtonLocation kTurret(4, 15);
+const ButtonLocation kAutoAim(4, 2);
+
+const ButtonLocation kIntakeFrontOut(4, 10);
+const ButtonLocation kIntakeBackOut(4, 9);
+const ButtonLocation kSpit(3, 3);
+
+const ButtonLocation kRedLocalizerReset(4, 14);
+const ButtonLocation kBlueLocalizerReset(4, 13);
+const ButtonLocation kLocalizerReset(3, 8);
+#endif
+
class Reader : public ::frc971::input::ActionJoystickInput {
public:
Reader(::aos::EventLoop *event_loop)
@@ -43,9 +75,76 @@
::frc971::input::DrivetrainInputReader::InputType::kPistol, {}),
superstructure_goal_sender_(
event_loop->MakeSender<superstructure::Goal>("/superstructure")),
+ localizer_control_sender_(
+ event_loop->MakeSender<
+ ::frc971::control_loops::drivetrain::LocalizerControl>(
+ "/drivetrain")),
superstructure_status_fetcher_(
- event_loop->MakeFetcher<superstructure::Status>(
- "/superstructure")) {}
+ event_loop->MakeFetcher<superstructure::Status>("/superstructure")),
+ setpoint_fetcher_(
+ event_loop->MakeFetcher<Setpoint>("/superstructure")) {}
+
+ // Localizer reset positions are with front of robot pressed up against driver
+ // station in the middle of the field side-to-side.
+ void BlueResetLocalizer() {
+ auto builder = localizer_control_sender_.MakeBuilder();
+
+ frc971::control_loops::drivetrain::LocalizerControl::Builder
+ localizer_control_builder = builder.MakeBuilder<
+ frc971::control_loops::drivetrain::LocalizerControl>();
+ localizer_control_builder.add_x(-7.9);
+ localizer_control_builder.add_y(0.0);
+ localizer_control_builder.add_theta_uncertainty(10.0);
+ localizer_control_builder.add_theta(M_PI);
+ localizer_control_builder.add_keep_current_theta(false);
+ if (builder.Send(localizer_control_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
+ AOS_LOG(ERROR, "Failed to reset blue localizer.\n");
+ }
+ }
+
+ void RedResetLocalizer() {
+ auto builder = localizer_control_sender_.MakeBuilder();
+
+ frc971::control_loops::drivetrain::LocalizerControl::Builder
+ localizer_control_builder = builder.MakeBuilder<
+ frc971::control_loops::drivetrain::LocalizerControl>();
+ localizer_control_builder.add_x(7.9);
+ localizer_control_builder.add_y(0.0);
+ localizer_control_builder.add_theta_uncertainty(10.0);
+ localizer_control_builder.add_theta(0.0);
+ localizer_control_builder.add_keep_current_theta(false);
+ if (builder.Send(localizer_control_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
+ AOS_LOG(ERROR, "Failed to reset red localizer.\n");
+ }
+ }
+
+ void ResetLocalizer() {
+ const frc971::control_loops::drivetrain::Status *drivetrain_status =
+ this->drivetrain_status();
+ if (drivetrain_status == nullptr) {
+ return;
+ }
+ // Get the current position
+ // Snap to heading.
+ auto builder = localizer_control_sender_.MakeBuilder();
+
+ // TODO<Henry> Put our starting location here.
+ frc971::control_loops::drivetrain::LocalizerControl::Builder
+ localizer_control_builder = builder.MakeBuilder<
+ frc971::control_loops::drivetrain::LocalizerControl>();
+ localizer_control_builder.add_x(drivetrain_status->x());
+ localizer_control_builder.add_y(drivetrain_status->y());
+ const double new_theta =
+ frc971::zeroing::Wrap(drivetrain_status->theta(), 0, M_PI);
+ localizer_control_builder.add_theta(new_theta);
+ localizer_control_builder.add_theta_uncertainty(10.0);
+ if (builder.Send(localizer_control_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
+ AOS_LOG(ERROR, "Failed to reset localizer.\n");
+ }
+ }
void AutoEnded() override { AOS_LOG(INFO, "Auto ended.\n"); }
@@ -57,43 +156,168 @@
return;
}
- aos::Sender<superstructure::Goal>::Builder builder =
- superstructure_goal_sender_.MakeBuilder();
+ setpoint_fetcher_.Fetch();
- flatbuffers::Offset<frc971::ProfileParameters> catapult_profile =
- frc971::CreateProfileParameters(*builder.fbb(), 5.0, 30.0);
+ // Default to the intakes in
+ double intake_front_pos = 1.47;
+ double intake_back_pos = 1.47;
+ double transfer_roller_front_speed = 0.0;
+ double transfer_roller_back_speed = 0.0;
- StaticZeroingSingleDOFProfiledSubsystemGoal::Builder
- catapult_return_builder =
- builder.MakeBuilder<StaticZeroingSingleDOFProfiledSubsystemGoal>();
- catapult_return_builder.add_unsafe_goal(
- data.IsPressed(kCatapultPos) ? 0.3 : -0.85);
- catapult_return_builder.add_profile_params(catapult_profile);
- flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
- catapult_return_offset = catapult_return_builder.Finish();
+ double roller_front_speed = 0.0;
+ double roller_back_speed = 0.0;
- superstructure::CatapultGoal::Builder catapult_builder =
- builder.MakeBuilder<superstructure::CatapultGoal>();
- catapult_builder.add_return_position(catapult_return_offset);
- catapult_builder.add_fire(data.IsPressed(kFire));
- catapult_builder.add_shot_position(0.3);
- catapult_builder.add_shot_velocity(15.0);
- flatbuffers::Offset<superstructure::CatapultGoal> catapult_offset =
- catapult_builder.Finish();
+ double turret_pos = 0.0;
- superstructure::Goal::Builder goal_builder =
- builder.MakeBuilder<superstructure::Goal>();
- goal_builder.add_catapult(catapult_offset);
+ double catapult_pos = 0.03;
+ double catapult_speed = 18.0;
+ double catapult_return_pos = 0.0;
+ bool fire = false;
- if (builder.Send(goal_builder.Finish()) != aos::RawSender::Error::kOk) {
- AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
+ if (data.PosEdge(kLocalizerReset)) {
+ ResetLocalizer();
+ }
+
+ if (data.PosEdge(kRedLocalizerReset)) {
+ RedResetLocalizer();
+ }
+ if (data.PosEdge(kBlueLocalizerReset)) {
+ BlueResetLocalizer();
+ }
+
+ if (data.IsPressed(kTurret)) {
+ if (setpoint_fetcher_.get()) {
+ turret_pos = setpoint_fetcher_->turret();
+ } else {
+ turret_pos = -1.5;
+ }
+ } else {
+ turret_pos = 0.0;
+ }
+
+ if (setpoint_fetcher_.get()) {
+ catapult_pos = setpoint_fetcher_->catapult_position();
+ catapult_speed = setpoint_fetcher_->catapult_velocity();
+ }
+
+ // Keep the catapult return position at the shot one if kCatapultPos is
+ // pressed
+ if (data.IsPressed(kCatapultPos)) {
+ catapult_return_pos = 0.3;
+ } else {
+ catapult_return_pos = -0.908;
+ }
+
+ constexpr double kRollerSpeed = 8.0;
+ constexpr double kTransferRollerSpeed = 12.0;
+ constexpr double kIntakePosition = -0.02;
+ constexpr size_t kIntakeCounterIterations = 25;
+
+ // Extend the intakes and spin the rollers
+ if (data.IsPressed(kIntakeFrontOut)) {
+ intake_front_pos = kIntakePosition;
+ transfer_roller_front_speed = kTransferRollerSpeed;
+ transfer_roller_back_speed = -kTransferRollerSpeed;
+
+ intake_front_counter_ = kIntakeCounterIterations;
+ } else if (data.IsPressed(kIntakeBackOut)) {
+ intake_back_pos = kIntakePosition;
+ transfer_roller_back_speed = kTransferRollerSpeed;
+ transfer_roller_front_speed = -kTransferRollerSpeed;
+
+ intake_back_counter_ = kIntakeCounterIterations;
+ } else if (data.IsPressed(kSpit)) {
+ transfer_roller_front_speed = -kTransferRollerSpeed;
+ transfer_roller_back_speed = -kTransferRollerSpeed;
+
+ intake_front_counter_ = 0;
+ intake_back_counter_ = 0;
+ }
+
+ // Keep spinning the rollers a bit after they let go
+ if (intake_front_counter_ > 0) {
+ intake_front_counter_--;
+ roller_front_speed = kRollerSpeed;
+ }
+ if (intake_back_counter_ > 0) {
+ intake_back_counter_--;
+ roller_back_speed = kRollerSpeed;
+ }
+
+ if (data.IsPressed(kFire)) {
+ fire = true;
+ }
+
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+
+ flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
+ intake_front_offset =
+ CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *builder.fbb(), intake_front_pos,
+ CreateProfileParameters(*builder.fbb(), 8.0, 40.0));
+ flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
+ intake_back_offset =
+ CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *builder.fbb(), intake_back_pos,
+ CreateProfileParameters(*builder.fbb(), 8.0, 40.0));
+
+ flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
+ turret_offset = CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *builder.fbb(), turret_pos,
+ CreateProfileParameters(*builder.fbb(), 12.0, 20.0));
+
+ flatbuffers::Offset<StaticZeroingSingleDOFProfiledSubsystemGoal>
+ catapult_return_offset =
+ CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *builder.fbb(), catapult_return_pos,
+ frc971::CreateProfileParameters(*builder.fbb(), 9.0, 50.0));
+
+ superstructure::CatapultGoal::Builder catapult_builder =
+ builder.MakeBuilder<superstructure::CatapultGoal>();
+ catapult_builder.add_return_position(catapult_return_offset);
+ catapult_builder.add_shot_position(catapult_pos);
+ catapult_builder.add_shot_velocity(catapult_speed);
+ flatbuffers::Offset<superstructure::CatapultGoal> catapult_offset =
+ catapult_builder.Finish();
+
+ superstructure::Goal::Builder superstructure_goal_builder =
+ builder.MakeBuilder<superstructure::Goal>();
+
+ superstructure_goal_builder.add_intake_front(intake_front_offset);
+ superstructure_goal_builder.add_intake_back(intake_back_offset);
+ superstructure_goal_builder.add_turret(turret_offset);
+ superstructure_goal_builder.add_catapult(catapult_offset);
+ superstructure_goal_builder.add_fire(fire);
+
+ superstructure_goal_builder.add_roller_speed_front(roller_front_speed);
+ superstructure_goal_builder.add_roller_speed_back(roller_back_speed);
+ superstructure_goal_builder.add_transfer_roller_speed_front(
+ transfer_roller_front_speed);
+ superstructure_goal_builder.add_transfer_roller_speed_back(
+ transfer_roller_back_speed);
+ superstructure_goal_builder.add_auto_aim(
+ data.IsPressed(kAutoAim));
+
+ if (builder.Send(superstructure_goal_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
+ AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
+ }
}
}
private:
::aos::Sender<superstructure::Goal> superstructure_goal_sender_;
+ ::aos::Sender<frc971::control_loops::drivetrain::LocalizerControl>
+ localizer_control_sender_;
+
::aos::Fetcher<superstructure::Status> superstructure_status_fetcher_;
+
+ ::aos::Fetcher<Setpoint> setpoint_fetcher_;
+
+ size_t intake_front_counter_ = 0;
+ size_t intake_back_counter_ = 0;
};
} // namespace joysticks
diff --git a/y2022/localizer/BUILD b/y2022/localizer/BUILD
index e13159f..1a57caf 100644
--- a/y2022/localizer/BUILD
+++ b/y2022/localizer/BUILD
@@ -1,4 +1,4 @@
-load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
+load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library", "flatbuffer_ts_library")
load("//aos:flatbuffers.bzl", "cc_static_flatbuffer")
load("@npm//@bazel/typescript:index.bzl", "ts_library")
@@ -25,6 +25,13 @@
visibility = ["//visibility:public"],
)
+flatbuffer_ts_library(
+ name = "localizer_output_ts_fbs",
+ srcs = ["localizer_output.fbs"],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+)
+
flatbuffer_cc_library(
name = "localizer_status_fbs",
srcs = [
@@ -39,6 +46,30 @@
visibility = ["//visibility:public"],
)
+flatbuffer_cc_library(
+ name = "localizer_visualization_fbs",
+ srcs = ["localizer_visualization.fbs"],
+ gen_reflections = 1,
+ includes = [
+ ":localizer_status_fbs_includes",
+ "//frc971/control_loops:control_loops_fbs_includes",
+ "//frc971/control_loops/drivetrain:drivetrain_status_fbs_includes",
+ ],
+ visibility = ["//visibility:public"],
+)
+
+flatbuffer_ts_library(
+ name = "localizer_visualization_ts_fbs",
+ srcs = ["localizer_visualization.fbs"],
+ includes = [
+ ":localizer_status_fbs_includes",
+ "//frc971/control_loops:control_loops_fbs_includes",
+ "//frc971/control_loops/drivetrain:drivetrain_status_fbs_includes",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+)
+
cc_static_flatbuffer(
name = "localizer_schema",
function = "frc971::controls::LocalizerStatusSchema",
@@ -54,8 +85,11 @@
deps = [
":localizer_output_fbs",
":localizer_status_fbs",
+ ":localizer_visualization_fbs",
"//aos/containers:ring_buffer",
+ "//aos/containers:sized_array",
"//aos/events:event_loop",
+ "//aos/network:message_bridge_server_fbs",
"//aos/time",
"//frc971/control_loops:c2d",
"//frc971/control_loops:control_loops_fbs",
@@ -67,8 +101,10 @@
"//frc971/wpilib:imu_fbs",
"//frc971/zeroing:imu_zeroer",
"//frc971/zeroing:wrap",
- "//y2020/vision/sift:sift_fbs",
"//y2022:constants",
+ "//y2022/control_loops/superstructure:superstructure_status_fbs",
+ "//y2022/vision:calibration_fbs",
+ "//y2022/vision:target_estimate_fbs",
"@org_tuxfamily_eigen//:eigen",
],
)
@@ -91,12 +127,14 @@
data = [
"//y2022:aos_config",
],
- shard_count = 10,
+ shard_count = 13,
deps = [
":localizer",
"//aos/events:simulated_event_loop",
+ "//aos/events/logging:log_writer",
"//aos/testing:googletest",
"//frc971/control_loops/drivetrain:drivetrain_test_lib",
+ "//y2022/control_loops/drivetrain:drivetrain_base",
],
)
diff --git a/y2022/localizer/imu.cc b/y2022/localizer/imu.cc
index fed9ceb..2310e99 100644
--- a/y2022/localizer/imu.cc
+++ b/y2022/localizer/imu.cc
@@ -124,9 +124,9 @@
// extra data from the pico
imu_builder.add_pico_timestamp_us(pico_timestamp);
imu_builder.add_left_encoder(
- constants::Values::DrivetrainEncoderToMeters(encoder1_count));
+ -constants::Values::DrivetrainEncoderToMeters(encoder2_count));
imu_builder.add_right_encoder(
- constants::Values::DrivetrainEncoderToMeters(encoder2_count));
+ constants::Values::DrivetrainEncoderToMeters(encoder1_count));
imu_builder.add_previous_reading_diag_stat(diag_stat_offset);
}
diff --git a/y2022/localizer/localizer.cc b/y2022/localizer/localizer.cc
index 8d4f908..1aa2458 100644
--- a/y2022/localizer/localizer.cc
+++ b/y2022/localizer/localizer.cc
@@ -1,5 +1,6 @@
#include "y2022/localizer/localizer.h"
+#include "aos/json_to_flatbuffer.h"
#include "frc971/control_loops/c2d.h"
#include "frc971/wpilib/imu_batch_generated.h"
#include "y2022/constants.h"
@@ -10,6 +11,14 @@
constexpr double kG = 9.80665;
constexpr std::chrono::microseconds kNominalDt(500);
+// Field position of the target (the 2022 target is conveniently in the middle
+// of the field....).
+constexpr double kVisionTargetX = 0.0;
+constexpr double kVisionTargetY = 0.0;
+
+// Minimum confidence to require to use a target match.
+constexpr double kMinTargetEstimateConfidence = 0.75;
+
template <int N>
Eigen::Matrix<double, N, 1> MakeState(std::vector<double> values) {
CHECK_EQ(static_cast<size_t>(N), values.size());
@@ -29,8 +38,10 @@
.plant()
.coefficients()),
down_estimator_(dt_config) {
- CHECK_EQ(branches_.capacity(), static_cast<size_t>(std::chrono::seconds(1) /
- kNominalDt / kBranchPeriod));
+ statistics_.rejection_counts.fill(0);
+ CHECK_EQ(branches_.capacity(),
+ static_cast<size_t>(std::chrono::seconds(1) / kNominalDt /
+ kBranchPeriod));
if (dt_config_.is_simulated) {
down_estimator_.assume_perfect_gravity();
}
@@ -77,10 +88,22 @@
B_continuous_accel_(kTheta, kThetaRate) = 1.0;
Q_continuous_model_.setZero();
- Q_continuous_model_.diagonal() << 1e-4, 1e-4, 1e-4, 1e-2, 1e-0, 1e-0, 1e-2,
+ Q_continuous_model_.diagonal() << 1e-2, 1e-2, 1e-8, 1e-2, 1e-0, 1e-0, 1e-2,
1e-0, 1e-0;
+ Q_continuous_accel_.setZero();
+ Q_continuous_accel_.diagonal() << 1e-2, 1e-2, 1e-20, 1e-4, 1e-4;
+
P_model_ = Q_continuous_model_ * aos::time::DurationInSeconds(kNominalDt);
+
+ // We can precalculate the discretizations of the accel model because it is
+ // actually LTI.
+
+ DiscretizeQAFast(Q_continuous_accel_, A_continuous_accel_, kNominalDt,
+ &Q_discrete_accel_, &A_discrete_accel_);
+ P_accel_ = Q_discrete_accel_;
+
+ led_outputs_.fill(LedOutput::ON);
}
Eigen::Matrix<double, ModelBasedLocalizer::kNModelStates,
@@ -150,7 +173,7 @@
const ModelBasedLocalizer::ModelState &state) const {
const double robot_speed =
(state(kLeftVelocity) + state(kRightVelocity)) / 2.0;
- const double lat_speed = (AModel(state) * state)(kTheta) * long_offset_;
+ const double lat_speed = (AModel(state) * state)(kTheta)*long_offset_;
const double velocity_x = std::cos(state(kTheta)) * robot_speed -
std::sin(state(kTheta)) * lat_speed;
const double velocity_y = std::sin(state(kTheta)) * robot_speed +
@@ -281,6 +304,8 @@
&A_discrete);
P_model_ = A_discrete * P_model_ * A_discrete.transpose() + Q_discrete;
+ P_accel_ = A_discrete_accel_ * P_accel_ * A_discrete_accel_.transpose() +
+ Q_discrete_accel_;
Eigen::Matrix<double, kNModelOutputs, kNModelStates> H;
Eigen::Matrix<double, kNModelOutputs, kNModelOutputs> R;
@@ -300,8 +325,6 @@
if (branches_.empty()) {
VLOG(2) << "Initializing";
- current_state_.model_state.setZero();
- current_state_.accel_state.setZero();
current_state_.model_state(kLeftEncoder) = encoders(0);
current_state_.model_state(kRightEncoder) = encoders(1);
current_state_.branch_time = t;
@@ -404,6 +427,8 @@
++branch_counter_;
if (branch_counter_ % kBranchPeriod == 0) {
branches_.Push(new_branch);
+ old_positions_.Push(OldPosition{t, xytheta(), latest_turret_position_,
+ latest_turret_velocity_});
branch_counter_ = 0;
}
@@ -416,7 +441,7 @@
VLOG(2) << "Model state " << current_state_.model_state.transpose();
VLOG(2) << "Accel state " << current_state_.accel_state.transpose();
VLOG(2) << "Accel state for model "
- << AccelStateForModelState(current_state_.model_state).transpose();
+ << AccelStateForModelState(current_state_.model_state).transpose();
VLOG(2) << "Input acce " << accel.transpose();
VLOG(2) << "Input gyro " << gyro.transpose();
VLOG(2) << "Input voltage " << voltage.transpose();
@@ -426,10 +451,256 @@
CHECK(std::isfinite(last_residual_));
}
+const ModelBasedLocalizer::OldPosition ModelBasedLocalizer::GetStateForTime(
+ aos::monotonic_clock::time_point time) {
+ if (old_positions_.empty()) {
+ return OldPosition{};
+ }
+
+ aos::monotonic_clock::duration lowest_time_error =
+ aos::monotonic_clock::duration::max();
+ const OldPosition *best_match = nullptr;
+ for (const OldPosition &sample : old_positions_) {
+ const aos::monotonic_clock::duration time_error =
+ std::chrono::abs(sample.sample_time - time);
+ if (time_error < lowest_time_error) {
+ lowest_time_error = time_error;
+ best_match = &sample;
+ }
+ }
+ return *best_match;
+}
+
+namespace {
+// Converts a flatbuffer TransformationMatrix to an Eigen matrix. Technically,
+// this should be able to do a single memcpy, but the extra verbosity here seems
+// appropriate.
+Eigen::Matrix<double, 4, 4> FlatbufferToTransformationMatrix(
+ const frc971::vision::calibration::TransformationMatrix &flatbuffer) {
+ CHECK_EQ(16u, CHECK_NOTNULL(flatbuffer.data())->size());
+ Eigen::Matrix<double, 4, 4> result;
+ result.setIdentity();
+ for (int row = 0; row < 4; ++row) {
+ for (int col = 0; col < 4; ++col) {
+ result(row, col) = (*flatbuffer.data())[row * 4 + col];
+ }
+ }
+ return result;
+}
+
+// Node names of the pis to listen for cameras from.
+constexpr std::array<std::string_view, ModelBasedLocalizer::kNumPis> kPisToUse{
+ "pi1", "pi2", "pi3", "pi4"};
+} // namespace
+
+const Eigen::Matrix<double, 4, 4> ModelBasedLocalizer::CameraTransform(
+ const OldPosition &state,
+ const frc971::vision::calibration::CameraCalibration *calibration,
+ std::optional<RejectionReason> *rejection_reason) const {
+ CHECK_NOTNULL(rejection_reason);
+ CHECK_NOTNULL(calibration);
+ // Per the CameraCalibration specification, we can actually determine whether
+ // the camera is the turret camera just from the presence of the
+ // turret_extrinsics member.
+ const bool is_turret = calibration->has_turret_extrinsics();
+ // Ignore readings when the turret is spinning too fast, on the assumption
+ // that the odds of screwing up the time compensation are higher.
+ // Note that the current number here is chosen pretty arbitrarily--1 rad / sec
+ // seems reasonable, but may be unnecessarily low or high.
+ constexpr double kMaxTurretVelocity = 1.0;
+ if (is_turret && std::abs(state.turret_velocity) > kMaxTurretVelocity &&
+ !rejection_reason->has_value()) {
+ *rejection_reason = RejectionReason::TURRET_TOO_FAST;
+ }
+ CHECK(calibration->has_fixed_extrinsics());
+ const Eigen::Matrix<double, 4, 4> fixed_extrinsics =
+ FlatbufferToTransformationMatrix(*calibration->fixed_extrinsics());
+
+ // Calculate the pose of the camera relative to the robot origin.
+ Eigen::Matrix<double, 4, 4> H_robot_camera = fixed_extrinsics;
+ if (is_turret) {
+ H_robot_camera =
+ H_robot_camera *
+ frc971::control_loops::TransformationMatrixForYaw<double>(
+ state.turret_position) *
+ FlatbufferToTransformationMatrix(*calibration->turret_extrinsics());
+ }
+ return H_robot_camera;
+}
+
+const std::optional<Eigen::Vector2d>
+ModelBasedLocalizer::CameraMeasuredRobotPosition(
+ const OldPosition &state, const y2022::vision::TargetEstimate *target,
+ std::optional<RejectionReason> *rejection_reason,
+ Eigen::Matrix<double, 4, 4> *H_field_camera_measured) const {
+ if (!target->has_camera_calibration()) {
+ *rejection_reason = RejectionReason::NO_CALIBRATION;
+ return std::nullopt;
+ }
+ const Eigen::Matrix<double, 4, 4> H_robot_camera =
+ CameraTransform(state, target->camera_calibration(), rejection_reason);
+ const control_loops::Pose robot_pose(
+ {state.xytheta(0), state.xytheta(1), 0.0}, state.xytheta(2));
+ const Eigen::Matrix<double, 4, 4> H_field_robot =
+ robot_pose.AsTransformationMatrix();
+ // Current estimated pose of the camera in the global frame.
+ // Note that this is all really just an elaborate way of extracting the
+ // current estimated camera yaw, and nothing else.
+ const Eigen::Matrix<double, 4, 4> H_field_camera =
+ H_field_robot * H_robot_camera;
+ // Grab the implied yaw of the camera (the +Z axis is coming out of the front
+ // of the cameras).
+ const Eigen::Vector3d rotated_camera_z =
+ H_field_camera.block<3, 3>(0, 0) * Eigen::Vector3d(0, 0, 1);
+ const double camera_yaw =
+ std::atan2(rotated_camera_z.y(), rotated_camera_z.x());
+ // All right, now we need to use the heading and distance from the
+ // TargetEstimate, plus the yaw embedded in the camera_pose, to determine what
+ // the implied X/Y position of the robot is. To do this, we calculate the
+ // heading/distance from the target to the robot. The distance is easy, since
+ // that's the same as the distance from the robot to the target. The heading
+ // isn't too hard, but is obnoxious to think about, since the heading from the
+ // target to the robot is distinct from the heading from the robot to the
+ // target.
+
+ // Just to walk through examples to confirm that the below calculation is
+ // correct:
+ // * If yaw = 0, and angle_to_target = 0, we are at 180 deg relative to the
+ // target.
+ // * If yaw = 90 deg, and angle_to_target = 0, we are at -90 deg relative to
+ // the target.
+ // * If yaw = 0, and angle_to_target = 90 deg, we are at -90 deg relative to
+ // the target.
+ const double heading_from_target =
+ aos::math::NormalizeAngle(M_PI + camera_yaw + target->angle_to_target());
+ const double distance_from_target = target->distance();
+ // Extract the implied camera position on the field.
+ *H_field_camera_measured = H_field_camera;
+ // TODO(james): Are we going to need to evict the roll/pitch components of the
+ // camera extrinsics this year as well?
+ (*H_field_camera_measured)(0, 3) =
+ distance_from_target * std::cos(heading_from_target) + kVisionTargetX;
+ (*H_field_camera_measured)(1, 3) =
+ distance_from_target * std::sin(heading_from_target) + kVisionTargetY;
+ const Eigen::Matrix<double, 4, 4> H_field_robot_measured =
+ *H_field_camera_measured * H_robot_camera.inverse();
+ return H_field_robot_measured.block<2, 1>(0, 3);
+}
+
+void ModelBasedLocalizer::HandleImageMatch(
+ aos::monotonic_clock::time_point sample_time,
+ const y2022::vision::TargetEstimate *target, int camera_index) {
+ std::optional<RejectionReason> rejection_reason;
+
+ if (target->confidence() < kMinTargetEstimateConfidence) {
+ rejection_reason = RejectionReason::LOW_CONFIDENCE;
+ TallyRejection(rejection_reason.value());
+ return;
+ }
+
+ const OldPosition &state = GetStateForTime(sample_time);
+ Eigen::Matrix<double, 4, 4> H_field_camera_measured;
+ const std::optional<Eigen::Vector2d> measured_robot_position =
+ CameraMeasuredRobotPosition(state, target, &rejection_reason,
+ &H_field_camera_measured);
+ // Technically, rejection_reason should always be set if
+ // measured_robot_position is nullopt, but in the future we may have more
+ // recoverable rejection reasons that we wish to allow to propagate further
+ // into the process.
+ if (!measured_robot_position || rejection_reason.has_value()) {
+ CHECK(rejection_reason.has_value());
+ TallyRejection(rejection_reason.value());
+ return;
+ }
+
+ // Next, go through and do the actual Kalman corrections for the x/y
+ // measurement, for both the accel state and the model-based state.
+ const Eigen::Matrix<double, kNModelStates, kNModelStates> A_continuous_model =
+ AModel(current_state_.model_state);
+
+ Eigen::Matrix<double, kNModelStates, kNModelStates> A_discrete_model;
+ Eigen::Matrix<double, kNModelStates, kNModelStates> Q_discrete_model;
+
+ DiscretizeQAFast(Q_continuous_model_, A_continuous_model, kNominalDt,
+ &Q_discrete_model, &A_discrete_model);
+
+ Eigen::Matrix<double, 2, kNModelStates> H_model;
+ H_model.setZero();
+ Eigen::Matrix<double, 2, kNAccelStates> H_accel;
+ H_accel.setZero();
+ Eigen::Matrix<double, 2, 2> R;
+ R.setZero();
+ H_model(0, kX) = 1.0;
+ H_model(1, kY) = 1.0;
+ H_accel(0, kX) = 1.0;
+ H_accel(1, kY) = 1.0;
+ R.diagonal() << 1e-2, 1e-2;
+
+ const Eigen::Matrix<double, kNModelStates, 2> K_model =
+ P_model_ * H_model.transpose() *
+ (H_model * P_model_ * H_model.transpose() + R).inverse();
+ const Eigen::Matrix<double, kNAccelStates, 2> K_accel =
+ P_accel_ * H_accel.transpose() *
+ (H_accel * P_accel_ * H_accel.transpose() + R).inverse();
+ P_model_ = (Eigen::Matrix<double, kNModelStates, kNModelStates>::Identity() -
+ K_model * H_model) *
+ P_model_;
+ P_accel_ = (Eigen::Matrix<double, kNAccelStates, kNAccelStates>::Identity() -
+ K_accel * H_accel) *
+ P_accel_;
+ // And now we have to correct *everything* on all the branches:
+ for (CombinedState &state : branches_) {
+ state.model_state += K_model * (measured_robot_position.value() -
+ H_model * state.model_state);
+ state.accel_state += K_accel * (measured_robot_position.value() -
+ H_accel * state.accel_state);
+ }
+ current_state_.model_state +=
+ K_model *
+ (measured_robot_position.value() - H_model * current_state_.model_state);
+ current_state_.accel_state +=
+ K_accel *
+ (measured_robot_position.value() - H_accel * current_state_.accel_state);
+
+ statistics_.total_accepted++;
+ statistics_.total_candidates++;
+
+ const Eigen::Vector3d camera_z_in_field =
+ H_field_camera_measured.block<3, 3>(0, 0) * Eigen::Vector3d::UnitZ();
+ const double camera_yaw =
+ std::atan2(camera_z_in_field.y(), camera_z_in_field.x());
+
+ // TODO(milind): actually control this
+ led_outputs_[camera_index] = LedOutput::ON;
+
+ TargetEstimateDebugT debug;
+ debug.camera = static_cast<uint8_t>(camera_index);
+ debug.camera_x = H_field_camera_measured(0, 3);
+ debug.camera_y = H_field_camera_measured(1, 3);
+ debug.camera_theta = camera_yaw;
+ debug.implied_robot_x = measured_robot_position.value().x();
+ debug.implied_robot_y = measured_robot_position.value().y();
+ debug.implied_robot_theta = xytheta()(2);
+ debug.implied_turret_goal =
+ aos::math::NormalizeAngle(camera_yaw + target->angle_to_target());
+ debug.accepted = true;
+ debug.image_age_sec = aos::time::DurationInSeconds(t_ - sample_time);
+ CHECK_LT(image_debugs_.size(), kDebugBufferSize);
+ image_debugs_.push_back(debug);
+}
+
+void ModelBasedLocalizer::HandleTurret(
+ aos::monotonic_clock::time_point sample_time, double turret_position,
+ double turret_velocity) {
+ last_turret_update_ = sample_time;
+ latest_turret_position_ = turret_position;
+ latest_turret_velocity_ = turret_velocity;
+}
+
void ModelBasedLocalizer::HandleReset(aos::monotonic_clock::time_point now,
const Eigen::Vector3d &xytheta) {
branches_.Reset();
- t_ = now;
+ t_ = now;
using_model_ = true;
current_state_.model_state << xytheta(0), xytheta(1), xytheta(2),
current_state_.model_state(kLeftEncoder), 0.0, 0.0,
@@ -468,15 +739,30 @@
return model_state_builder.Finish();
}
+flatbuffers::Offset<CumulativeStatistics>
+ModelBasedLocalizer::PopulateStatistics(flatbuffers::FlatBufferBuilder *fbb) {
+ const auto rejections_offset = fbb->CreateVector(
+ statistics_.rejection_counts.data(), statistics_.rejection_counts.size());
+
+ CumulativeStatistics::Builder stats_builder(*fbb);
+ stats_builder.add_total_accepted(statistics_.total_accepted);
+ stats_builder.add_total_candidates(statistics_.total_candidates);
+ stats_builder.add_rejection_reason_count(rejections_offset);
+ return stats_builder.Finish();
+}
+
flatbuffers::Offset<ModelBasedStatus> ModelBasedLocalizer::PopulateStatus(
flatbuffers::FlatBufferBuilder *fbb) {
+ const flatbuffers::Offset<CumulativeStatistics> stats_offset =
+ PopulateStatistics(fbb);
+
const flatbuffers::Offset<control_loops::drivetrain::DownEstimatorState>
down_estimator_offset = down_estimator_.PopulateStatus(fbb, t_);
const CombinedState &state = current_state_;
const flatbuffers::Offset<ModelBasedState> model_state_offset =
- BuildModelState(fbb, state.model_state);
+ BuildModelState(fbb, state.model_state);
const flatbuffers::Offset<AccelBasedState> accel_state_offset =
BuildAccelState(fbb, state.accel_state);
@@ -508,15 +794,69 @@
builder.add_implied_accel_y(abs_accel_(1));
builder.add_implied_accel_z(abs_accel_(2));
builder.add_clock_resets(clock_resets_);
+ builder.add_statistics(stats_offset);
return builder.Finish();
}
+flatbuffers::Offset<LocalizerVisualization>
+ModelBasedLocalizer::PopulateVisualization(
+ flatbuffers::FlatBufferBuilder *fbb) {
+ const flatbuffers::Offset<CumulativeStatistics> stats_offset =
+ PopulateStatistics(fbb);
+
+ aos::SizedArray<flatbuffers::Offset<TargetEstimateDebug>, kDebugBufferSize>
+ debug_offsets;
+
+ for (const TargetEstimateDebugT &debug : image_debugs_) {
+ debug_offsets.push_back(PackTargetEstimateDebug(debug, fbb));
+ }
+
+ image_debugs_.clear();
+
+ const flatbuffers::Offset<
+ flatbuffers::Vector<flatbuffers::Offset<TargetEstimateDebug>>>
+ debug_offset =
+ fbb->CreateVector(debug_offsets.data(), debug_offsets.size());
+
+ LocalizerVisualization::Builder builder(*fbb);
+ builder.add_statistics(stats_offset);
+ builder.add_targets(debug_offset);
+ return builder.Finish();
+}
+
+void ModelBasedLocalizer::TallyRejection(const RejectionReason reason) {
+ statistics_.total_candidates++;
+ statistics_.rejection_counts[static_cast<size_t>(reason)]++;
+ TargetEstimateDebugT debug;
+ debug.accepted = false;
+ debug.rejection_reason = reason;
+ CHECK_LT(image_debugs_.size(), kDebugBufferSize);
+ image_debugs_.push_back(debug);
+}
+
+flatbuffers::Offset<TargetEstimateDebug>
+ModelBasedLocalizer::PackTargetEstimateDebug(
+ const TargetEstimateDebugT &debug, flatbuffers::FlatBufferBuilder *fbb) {
+ if (!debug.accepted) {
+ TargetEstimateDebug::Builder builder(*fbb);
+ builder.add_accepted(debug.accepted);
+ builder.add_rejection_reason(debug.rejection_reason);
+ return builder.Finish();
+ } else {
+ flatbuffers::Offset<TargetEstimateDebug> offset =
+ TargetEstimateDebug::Pack(*fbb, &debug);
+ flatbuffers::GetMutableTemporaryPointer(*fbb, offset)
+ ->clear_rejection_reason();
+ return offset;
+ }
+}
+
namespace {
// Period at which the encoder readings from the IMU board wrap.
static double DrivetrainWrapPeriod() {
return y2022::constants::Values::DrivetrainEncoderToMeters(1 << 16);
}
-}
+} // namespace
EventLoopLocalizer::EventLoopLocalizer(
aos::EventLoop *event_loop,
@@ -525,9 +865,18 @@
model_based_(dt_config),
status_sender_(event_loop_->MakeSender<LocalizerStatus>("/localizer")),
output_sender_(event_loop_->MakeSender<LocalizerOutput>("/localizer")),
+ visualization_sender_(
+ event_loop_->MakeSender<LocalizerVisualization>("/localizer")),
output_fetcher_(
event_loop_->MakeFetcher<frc971::control_loops::drivetrain::Output>(
"/drivetrain")),
+ clock_offset_fetcher_(
+ event_loop_->MakeFetcher<aos::message_bridge::ServerStatistics>(
+ "/aos")),
+ superstructure_fetcher_(
+ event_loop_
+ ->MakeFetcher<y2022::control_loops::superstructure::Status>(
+ "/superstructure")),
left_encoder_(-DrivetrainWrapPeriod() / 2.0, DrivetrainWrapPeriod()),
right_encoder_(-DrivetrainWrapPeriod() / 2.0, DrivetrainWrapPeriod()) {
event_loop_->MakeWatcher(
@@ -538,8 +887,72 @@
? model_based_.xytheta()(2)
: control.theta();
model_based_.HandleReset(event_loop_->monotonic_now(),
- {control.x(), control.y(), theta});
+ {control.x(), control.y(), theta});
});
+ aos::TimerHandler *superstructure_timer = event_loop_->AddTimer([this]() {
+ if (superstructure_fetcher_.Fetch()) {
+ const y2022::control_loops::superstructure::Status &status =
+ *superstructure_fetcher_.get();
+ if (!status.has_turret()) {
+ return;
+ }
+ CHECK(status.has_turret());
+ model_based_.HandleTurret(
+ superstructure_fetcher_.context().monotonic_event_time,
+ status.turret()->position(), status.turret()->velocity());
+ }
+ });
+ event_loop_->OnRun([this, superstructure_timer]() {
+ superstructure_timer->Setup(event_loop_->monotonic_now(),
+ std::chrono::milliseconds(20));
+ });
+
+ for (size_t camera_index = 0; camera_index < kPisToUse.size();
+ ++camera_index) {
+ CHECK_LT(camera_index, target_estimate_fetchers_.size());
+ target_estimate_fetchers_[camera_index] =
+ event_loop_->MakeFetcher<y2022::vision::TargetEstimate>(
+ absl::StrCat("/", kPisToUse[camera_index], "/camera"));
+ }
+ aos::TimerHandler *estimate_timer = event_loop_->AddTimer([this]() {
+ for (size_t camera_index = 0; camera_index < kPisToUse.size();
+ ++camera_index) {
+ if (model_based_.NumQueuedImageDebugs() ==
+ ModelBasedLocalizer::kDebugBufferSize ||
+ (last_visualization_send_ + kMinVisualizationPeriod <
+ event_loop_->monotonic_now())) {
+ auto builder = visualization_sender_.MakeBuilder();
+ visualization_sender_.CheckOk(
+ builder.Send(model_based_.PopulateVisualization(builder.fbb())));
+ }
+ if (target_estimate_fetchers_[camera_index].Fetch()) {
+ const std::optional<aos::monotonic_clock::duration> monotonic_offset =
+ ClockOffset(kPisToUse[camera_index]);
+ if (!monotonic_offset.has_value()) {
+ continue;
+ }
+ // TODO(james): Get timestamp from message contents.
+ aos::monotonic_clock::time_point capture_time(
+ target_estimate_fetchers_[camera_index]
+ .context()
+ .monotonic_remote_time -
+ monotonic_offset.value());
+ if (capture_time > target_estimate_fetchers_[camera_index]
+ .context()
+ .monotonic_event_time) {
+ model_based_.TallyRejection(RejectionReason::IMAGE_FROM_FUTURE);
+ continue;
+ }
+ model_based_.HandleImageMatch(
+ capture_time, target_estimate_fetchers_[camera_index].get(),
+ camera_index);
+ }
+ }
+ });
+ event_loop_->OnRun([this, estimate_timer]() {
+ estimate_timer->Setup(event_loop_->monotonic_now(),
+ std::chrono::milliseconds(100));
+ });
event_loop_->MakeWatcher(
"/localizer", [this](const frc971::IMUValuesBatch &values) {
CHECK(values.has_readings());
@@ -572,8 +985,8 @@
std::chrono::milliseconds(10) <
event_loop_->context().monotonic_event_time);
model_based_.HandleImu(
- sample_timestamp,
- zeroer_.ZeroedGyro(), zeroer_.ZeroedAccel(), encoders,
+ sample_timestamp, zeroer_.ZeroedGyro(), zeroer_.ZeroedAccel(),
+ encoders,
disabled ? Eigen::Vector2d::Zero()
: Eigen::Vector2d{output_fetcher_->left_voltage(),
output_fetcher_->right_voltage()});
@@ -603,6 +1016,11 @@
if (last_output_send_ + std::chrono::milliseconds(5) <
event_loop_->context().monotonic_event_time) {
auto builder = output_sender_.MakeBuilder();
+
+ const auto led_outputs_offset =
+ builder.fbb()->CreateVector(model_based_.led_outputs().data(),
+ model_based_.led_outputs().size());
+
LocalizerOutput::Builder output_builder =
builder.MakeBuilder<LocalizerOutput>();
// TODO(james): Should we bother to try to estimate time offsets for
@@ -612,6 +1030,7 @@
output_builder.add_x(model_based_.xytheta()(0));
output_builder.add_y(model_based_.xytheta()(1));
output_builder.add_theta(model_based_.xytheta()(2));
+ output_builder.add_zeroed(zeroer_.Zeroed());
const Eigen::Quaterniond &orientation = model_based_.orientation();
Quaternion quaternion;
quaternion.mutate_x(orientation.x());
@@ -619,6 +1038,7 @@
quaternion.mutate_z(orientation.z());
quaternion.mutate_w(orientation.w());
output_builder.add_orientation(&quaternion);
+ output_builder.add_led_outputs(led_outputs_offset);
builder.CheckOk(builder.Send(output_builder.Finish()));
last_output_send_ = event_loop_->monotonic_now();
}
@@ -626,4 +1046,30 @@
});
}
+std::optional<aos::monotonic_clock::duration> EventLoopLocalizer::ClockOffset(
+ std::string_view pi) {
+ std::optional<aos::monotonic_clock::duration> monotonic_offset;
+ clock_offset_fetcher_.Fetch();
+ if (clock_offset_fetcher_.get() != nullptr) {
+ for (const auto connection : *clock_offset_fetcher_->connections()) {
+ if (connection->has_node() && connection->node()->has_name() &&
+ connection->node()->name()->string_view() == pi) {
+ if (connection->has_monotonic_offset()) {
+ monotonic_offset =
+ std::chrono::nanoseconds(connection->monotonic_offset());
+ } else {
+ // If we don't have a monotonic offset, that means we aren't
+ // connected.
+ model_based_.TallyRejection(
+ RejectionReason::MESSAGE_BRIDGE_DISCONNECTED);
+ return std::nullopt;
+ }
+ break;
+ }
+ }
+ }
+ CHECK(monotonic_offset.has_value());
+ return monotonic_offset;
+}
+
} // namespace frc971::controls
diff --git a/y2022/localizer/localizer.h b/y2022/localizer/localizer.h
index d7b6a23..e9a61e1 100644
--- a/y2022/localizer/localizer.h
+++ b/y2022/localizer/localizer.h
@@ -3,18 +3,21 @@
#include "Eigen/Dense"
#include "Eigen/Geometry"
-
-#include "aos/events/event_loop.h"
#include "aos/containers/ring_buffer.h"
+#include "aos/containers/sized_array.h"
+#include "aos/events/event_loop.h"
+#include "aos/network/message_bridge_server_generated.h"
#include "aos/time/time.h"
-#include "y2020/vision/sift/sift_generated.h"
-#include "y2022/localizer/localizer_status_generated.h"
-#include "y2022/localizer/localizer_output_generated.h"
-#include "frc971/control_loops/drivetrain/improved_down_estimator.h"
#include "frc971/control_loops/drivetrain/drivetrain_output_generated.h"
+#include "frc971/control_loops/drivetrain/improved_down_estimator.h"
#include "frc971/control_loops/drivetrain/localizer_generated.h"
#include "frc971/zeroing/imu_zeroer.h"
#include "frc971/zeroing/wrap.h"
+#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
+#include "y2022/localizer/localizer_output_generated.h"
+#include "y2022/localizer/localizer_status_generated.h"
+#include "y2022/localizer/localizer_visualization_generated.h"
+#include "y2022/vision/target_estimate_generated.h"
namespace frc971::controls {
@@ -60,6 +63,8 @@
// * Tune for ADIS16505/real robot.
class ModelBasedLocalizer {
public:
+ static constexpr size_t kNumPis = 4;
+
static constexpr size_t kX = 0;
static constexpr size_t kY = 1;
static constexpr size_t kTheta = 2;
@@ -92,7 +97,9 @@
// Branching period, in cycles.
// Needs 10 to even stay alive, and still at ~96% CPU.
// ~20 gives ~55-60% CPU.
- static constexpr int kBranchPeriod = 20;
+ static constexpr int kBranchPeriod = 100;
+
+ static constexpr size_t kDebugBufferSize = 10;
typedef Eigen::Matrix<double, kNModelStates, 1> ModelState;
typedef Eigen::Matrix<double, kNAccelStates, 1> AccelState;
@@ -104,10 +111,11 @@
void HandleImu(aos::monotonic_clock::time_point t,
const Eigen::Vector3d &gyro, const Eigen::Vector3d &accel,
const Eigen::Vector2d encoders, const Eigen::Vector2d voltage);
- void HandleImageMatch(aos::monotonic_clock::time_point,
- const vision::sift::ImageMatchResult *) {
- LOG(FATAL) << "Unimplemented.";
- }
+ void HandleTurret(aos::monotonic_clock::time_point sample_time,
+ double turret_position, double turret_velocity);
+ void HandleImageMatch(aos::monotonic_clock::time_point sample_time,
+ const y2022::vision::TargetEstimate *target,
+ int camera_index);
void HandleReset(aos::monotonic_clock::time_point,
const Eigen::Vector3d &xytheta);
@@ -128,12 +136,32 @@
void set_longitudinal_offset(double offset) { long_offset_ = offset; }
+ void TallyRejection(const RejectionReason reason);
+
+ flatbuffers::Offset<LocalizerVisualization> PopulateVisualization(
+ flatbuffers::FlatBufferBuilder *fbb);
+
+ size_t NumQueuedImageDebugs() const { return image_debugs_.size(); }
+
+ std::array<LedOutput, kNumPis> led_outputs() const { return led_outputs_; }
+
private:
struct CombinedState {
- AccelState accel_state;
- ModelState model_state;
- aos::monotonic_clock::time_point branch_time;
- double accumulated_divergence;
+ AccelState accel_state = AccelState::Zero();
+ ModelState model_state = ModelState::Zero();
+ aos::monotonic_clock::time_point branch_time =
+ aos::monotonic_clock::min_time;
+ double accumulated_divergence = 0.0;
+ };
+
+ // Struct to store state data needed to perform a camera correction, since
+ // camera corrections require looking back in time.
+ struct OldPosition {
+ aos::monotonic_clock::time_point sample_time =
+ aos::monotonic_clock::min_time;
+ Eigen::Vector3d xytheta = Eigen::Vector3d::Zero();
+ double turret_position = 0.0;
+ double turret_velocity = 0.0;
};
static flatbuffers::Offset<AccelBasedState> BuildAccelState(
@@ -169,22 +197,53 @@
const AccelInput &accel_input, const ModelInput &model_input,
aos::monotonic_clock::duration dt);
+ const OldPosition GetStateForTime(aos::monotonic_clock::time_point time);
+
+ // Returns the transformation to get from the camera frame to the robot frame
+ // for the specified state.
+ const Eigen::Matrix<double, 4, 4> CameraTransform(
+ const OldPosition &state,
+ const frc971::vision::calibration::CameraCalibration *calibration,
+ std::optional<RejectionReason> *rejection_reason) const;
+
+ // Returns the robot x/y position implied by the specified camera data and
+ // estimated state from that time.
+ // H_field_camera is passed in so that it can be used as a debugging output.
+ const std::optional<Eigen::Vector2d> CameraMeasuredRobotPosition(
+ const OldPosition &state, const y2022::vision::TargetEstimate *target,
+ std::optional<RejectionReason> *rejection_reason,
+ Eigen::Matrix<double, 4, 4> *H_field_camera_measured) const;
+
+ flatbuffers::Offset<TargetEstimateDebug> PackTargetEstimateDebug(
+ const TargetEstimateDebugT &debug, flatbuffers::FlatBufferBuilder *fbb);
+
+ flatbuffers::Offset<CumulativeStatistics> PopulateStatistics(
+ flatbuffers::FlatBufferBuilder *fbb);
+
const control_loops::drivetrain::DrivetrainConfig<double> dt_config_;
const StateFeedbackHybridPlantCoefficients<2, 2, 2, double>
velocity_drivetrain_coefficients_;
Eigen::Matrix<double, kNModelStates, kNModelStates> A_continuous_model_;
Eigen::Matrix<double, kNAccelStates, kNAccelStates> A_continuous_accel_;
+ Eigen::Matrix<double, kNAccelStates, kNAccelStates> A_discrete_accel_;
Eigen::Matrix<double, kNModelStates, kNModelInputs> B_continuous_model_;
Eigen::Matrix<double, kNAccelStates, kNAccelInputs> B_continuous_accel_;
Eigen::Matrix<double, kNModelStates, kNModelStates> Q_continuous_model_;
Eigen::Matrix<double, kNModelStates, kNModelStates> P_model_;
+
+ Eigen::Matrix<double, kNAccelStates, kNAccelStates> Q_continuous_accel_;
+ Eigen::Matrix<double, kNAccelStates, kNAccelStates> Q_discrete_accel_;
+
+ Eigen::Matrix<double, kNAccelStates, kNAccelStates> P_accel_;
+
+ control_loops::drivetrain::DrivetrainUkf down_estimator_;
+
// When we are following the model, we will, on each iteration:
// 1) Perform a model-based update of a single state.
// 2) Add a hypothetical non-model-based entry based on the current state.
// 3) Evict too-old non-model-based entries.
- control_loops::drivetrain::DrivetrainUkf down_estimator_;
// Buffer of old branches these are all created by initializing a new
// model-based state based on the current state, and then initializing a new
@@ -195,6 +254,10 @@
aos::RingBuffer<CombinedState, 2000 / kBranchPeriod> branches_;
int branch_counter_ = 0;
+ // Buffer of old x/y/theta positions. This is used so that we can have a
+ // reference for exactly where we thought a camera was when it took an image.
+ aos::RingBuffer<OldPosition, 500 / kBranchPeriod> old_positions_;
+
CombinedState current_state_;
aos::monotonic_clock::time_point t_ = aos::monotonic_clock::min_time;
bool using_model_;
@@ -215,11 +278,39 @@
int clock_resets_ = 0;
+ std::optional<aos::monotonic_clock::time_point> last_turret_update_;
+ double latest_turret_position_ = 0.0;
+ double latest_turret_velocity_ = 0.0;
+
+ // Stuff to track faults.
+ static constexpr size_t kNumRejectionReasons =
+ static_cast<int>(RejectionReason::MAX) -
+ static_cast<int>(RejectionReason::MIN) + 1;
+
+ struct Statistics {
+ int total_accepted = 0;
+ int total_candidates = 0;
+ static_assert(0 == static_cast<int>(RejectionReason::MIN));
+ static_assert(
+ kNumRejectionReasons ==
+ sizeof(
+ std::invoke_result<decltype(EnumValuesRejectionReason)>::type) /
+ sizeof(RejectionReason),
+ "RejectionReason has non-contiguous error values.");
+ std::array<int, kNumRejectionReasons> rejection_counts;
+ };
+ Statistics statistics_;
+
+ aos::SizedArray<TargetEstimateDebugT, kDebugBufferSize> image_debugs_;
+ std::array<LedOutput, kNumPis> led_outputs_;
+
friend class testing::LocalizerTest;
};
class EventLoopLocalizer {
public:
+ static constexpr std::chrono::milliseconds kMinVisualizationPeriod{100};
+
EventLoopLocalizer(
aos::EventLoop *event_loop,
const control_loops::drivetrain::DrivetrainConfig<double> &dt_config);
@@ -227,14 +318,25 @@
ModelBasedLocalizer *localizer() { return &model_based_; }
private:
+ std::optional<aos::monotonic_clock::duration> ClockOffset(
+ std::string_view pi);
aos::EventLoop *event_loop_;
ModelBasedLocalizer model_based_;
aos::Sender<LocalizerStatus> status_sender_;
aos::Sender<LocalizerOutput> output_sender_;
+ aos::Sender<LocalizerVisualization> visualization_sender_;
aos::Fetcher<frc971::control_loops::drivetrain::Output> output_fetcher_;
+ aos::Fetcher<aos::message_bridge::ServerStatistics> clock_offset_fetcher_;
+ std::array<aos::Fetcher<y2022::vision::TargetEstimate>,
+ ModelBasedLocalizer::kNumPis>
+ target_estimate_fetchers_;
+ aos::Fetcher<y2022::control_loops::superstructure::Status>
+ superstructure_fetcher_;
zeroing::ImuZeroer zeroer_;
aos::monotonic_clock::time_point last_output_send_ =
aos::monotonic_clock::min_time;
+ aos::monotonic_clock::time_point last_visualization_send_ =
+ aos::monotonic_clock::min_time;
std::optional<aos::monotonic_clock::time_point> last_pico_timestamp_;
aos::monotonic_clock::duration pico_offset_error_;
// t = pico_offset_ + pico_timestamp.
diff --git a/y2022/localizer/localizer_output.fbs b/y2022/localizer/localizer_output.fbs
index 03abf19..ec3302a 100644
--- a/y2022/localizer/localizer_output.fbs
+++ b/y2022/localizer/localizer_output.fbs
@@ -10,6 +10,12 @@
z:double (id: 3);
}
+// Used to tell different LEDs to be on or off
+enum LedOutput : byte {
+ ON,
+ OFF
+}
+
table LocalizerOutput {
// Timestamp (on the source node) that this sample corresponds with. This
// may be older than the sent time to account for delays in sensor readings.
@@ -21,6 +27,13 @@
theta:double (id: 3);
// Current estimate of the robot's 3-D rotation.
orientation:Quaternion (id: 4);
+ // Whether we have zeroed the IMU (may go false if we observe a fault with the
+ // IMU).
+ zeroed:bool (id: 5);
+
+ // Whether each led should be on.
+ // Indices correspond to pi number.
+ led_outputs:[LedOutput] (id: 6);
}
root_type LocalizerOutput;
diff --git a/y2022/localizer/localizer_status.fbs b/y2022/localizer/localizer_status.fbs
index 80cee0b..ae96b63 100644
--- a/y2022/localizer/localizer_status.fbs
+++ b/y2022/localizer/localizer_status.fbs
@@ -2,6 +2,21 @@
namespace frc971.controls;
+enum RejectionReason : byte {
+ IMAGE_FROM_FUTURE = 0,
+ NO_CALIBRATION = 1,
+ TURRET_TOO_FAST = 2,
+ MESSAGE_BRIDGE_DISCONNECTED = 3,
+ LOW_CONFIDENCE = 4,
+}
+
+table CumulativeStatistics {
+ total_accepted:int (id: 0);
+ total_candidates:int (id: 1);
+ // Indexed by integer value of RejectionReason enum.
+ rejection_reason_count:[int] (id: 2);
+}
+
// Stores the state associated with the acceleration-based modelling.
table AccelBasedState {
// x/y position, in meters.
@@ -74,6 +89,7 @@
// Number of times we have missed an IMU reading. Should never increase except
// *maybe* during startup.
clock_resets:int (id: 17);
+ statistics:CumulativeStatistics (id: 18);
}
table LocalizerStatus {
diff --git a/y2022/localizer/localizer_test.cc b/y2022/localizer/localizer_test.cc
index 1997b80..6e9cd1e 100644
--- a/y2022/localizer/localizer_test.cc
+++ b/y2022/localizer/localizer_test.cc
@@ -1,14 +1,31 @@
#include "y2022/localizer/localizer.h"
+#include "aos/events/logging/log_writer.h"
#include "aos/events/simulated_event_loop.h"
-#include "gtest/gtest.h"
#include "frc971/control_loops/drivetrain/drivetrain_test_lib.h"
+#include "frc971/control_loops/pose.h"
+#include "gtest/gtest.h"
+#include "y2022/control_loops/drivetrain/drivetrain_base.h"
+#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
+#include "y2022/vision/target_estimate_generated.h"
+
+DEFINE_string(output_folder, "",
+ "If set, logs all channels to the provided logfile.");
namespace frc971::controls::testing {
typedef ModelBasedLocalizer::ModelState ModelState;
typedef ModelBasedLocalizer::AccelState AccelState;
typedef ModelBasedLocalizer::ModelInput ModelInput;
typedef ModelBasedLocalizer::AccelInput AccelInput;
+
+using frc971::control_loops::Pose;
+using frc971::control_loops::drivetrain::DrivetrainConfig;
+using frc971::control_loops::drivetrain::LocalizerControl;
+using frc971::vision::calibration::CameraCalibrationT;
+using frc971::vision::calibration::TransformationMatrixT;
+using y2022::vision::TargetEstimate;
+using y2022::vision::TargetEstimateT;
+
namespace {
constexpr size_t kX = ModelBasedLocalizer::kX;
constexpr size_t kY = ModelBasedLocalizer::kY;
@@ -26,14 +43,51 @@
constexpr size_t kRightVoltageError = ModelBasedLocalizer::kRightVoltageError;
constexpr size_t kLeftVoltage = ModelBasedLocalizer::kLeftVoltage;
constexpr size_t kRightVoltage = ModelBasedLocalizer::kRightVoltage;
+
+Eigen::Matrix<double, 4, 4> TurretRobotTransformation() {
+ Eigen::Matrix<double, 4, 4> H;
+ H.setIdentity();
+ H.block<3, 1>(0, 3) << 1, 1.1, 0.9;
+ return H;
}
+// Provides the location of the camera on the turret.
+Eigen::Matrix<double, 4, 4> CameraTurretTransformation() {
+ Eigen::Matrix<double, 4, 4> H;
+ H.setIdentity();
+ H.block<3, 1>(0, 3) << 0.1, 0, 0;
+ H.block<3, 3>(0, 0) << 0, 0, 1, -1, 0, 0, 0, -1, 0;
+
+ // Introduce a bit of pitch to make sure that we're exercising all the code.
+ H.block<3, 3>(0, 0) =
+ Eigen::AngleAxis<double>(0.1, Eigen::Vector3d::UnitY()) *
+ H.block<3, 3>(0, 0);
+ return H;
+}
+
+// Copies an Eigen matrix into a row-major vector of the data.
+std::vector<float> MatrixToVector(const Eigen::Matrix<double, 4, 4> &H) {
+ std::vector<float> data;
+ for (int row = 0; row < 4; ++row) {
+ for (int col = 0; col < 4; ++col) {
+ data.push_back(H(row, col));
+ }
+ }
+ return data;
+}
+
+DrivetrainConfig<double> GetTest2022DrivetrainConfig() {
+ DrivetrainConfig<double> config =
+ y2022::control_loops::drivetrain::GetDrivetrainConfig();
+ config.is_simulated = true;
+ return config;
+}
+} // namespace
+
class LocalizerTest : public ::testing::Test {
protected:
LocalizerTest()
- : dt_config_(
- control_loops::drivetrain::testing::GetTestDrivetrainConfig()),
- localizer_(dt_config_) {
+ : dt_config_(GetTest2022DrivetrainConfig()), localizer_(dt_config_) {
localizer_.set_longitudinal_offset(0.0);
}
ModelState CallDiffModel(const ModelState &state, const ModelInput &U) {
@@ -46,7 +100,6 @@
const control_loops::drivetrain::DrivetrainConfig<double> dt_config_;
ModelBasedLocalizer localizer_;
-
};
TEST_F(LocalizerTest, AccelIntegrationTest) {
@@ -177,7 +230,8 @@
const Eigen::Vector2d encoders{0.0, 0.0};
const Eigen::Vector2d voltages{0.0, 0.0};
Eigen::Vector3d accel{5.0, 2.0, 9.80665};
- Eigen::Vector3d accel_gs = accel / 9.80665;
+ Eigen::Vector3d accel_gs =
+ dt_config_.imu_transform.inverse() * accel / 9.80665;
while (t < start) {
// Spin to fill up the buffer.
localizer_.HandleImu(t, gyro, Eigen::Vector3d::UnitZ(), encoders, voltages);
@@ -215,7 +269,7 @@
// and then leave them constant, which should make it look like we are going
// around in a circle.
accel = Eigen::Vector3d{-accel(1), accel(0), 9.80665};
- accel_gs = accel / 9.80665;
+ accel_gs = dt_config_.imu_transform.inverse() * accel / 9.80665;
// v^2 / r = a
// w * r = v
// v^2 / v * w = a
@@ -292,6 +346,8 @@
aos::configuration::GetNode(&configuration_.message(), "roborio")),
imu_node_(
aos::configuration::GetNode(&configuration_.message(), "imu")),
+ camera_node_(
+ aos::configuration::GetNode(&configuration_.message(), "pi1")),
dt_config_(
control_loops::drivetrain::testing::GetTestDrivetrainConfig()),
localizer_event_loop_(
@@ -308,37 +364,187 @@
event_loop_factory_.MakeEventLoop("test", roborio_node_)),
imu_test_event_loop_(
event_loop_factory_.MakeEventLoop("test", imu_node_)),
+ camera_test_event_loop_(
+ event_loop_factory_.MakeEventLoop("test", camera_node_)),
logger_test_event_loop_(
event_loop_factory_.GetNodeEventLoopFactory("logger")
->MakeEventLoop("test")),
output_sender_(
roborio_test_event_loop_->MakeSender<Output>("/drivetrain")),
+ turret_sender_(
+ roborio_test_event_loop_
+ ->MakeSender<y2022::control_loops::superstructure::Status>(
+ "/superstructure")),
+ target_sender_(
+ camera_test_event_loop_->MakeSender<y2022::vision::TargetEstimate>(
+ "/camera")),
+ control_sender_(roborio_test_event_loop_->MakeSender<LocalizerControl>(
+ "/drivetrain")),
output_fetcher_(roborio_test_event_loop_->MakeFetcher<LocalizerOutput>(
"/localizer")),
status_fetcher_(
imu_test_event_loop_->MakeFetcher<LocalizerStatus>("/localizer")) {
localizer_.localizer()->set_longitudinal_offset(0.0);
- aos::TimerHandler *timer = roborio_test_event_loop_->AddTimer([this]() {
- auto builder = output_sender_.MakeBuilder();
- auto output_builder = builder.MakeBuilder<Output>();
- output_builder.add_left_voltage(output_voltages_(0));
- output_builder.add_right_voltage(output_voltages_(1));
- builder.CheckOk(builder.Send(output_builder.Finish()));
- });
- roborio_test_event_loop_->OnRun([timer, this]() {
- timer->Setup(roborio_test_event_loop_->monotonic_now(),
- std::chrono::milliseconds(5));
- });
+ {
+ aos::TimerHandler *timer = roborio_test_event_loop_->AddTimer([this]() {
+ {
+ auto builder = output_sender_.MakeBuilder();
+ auto output_builder = builder.MakeBuilder<Output>();
+ output_builder.add_left_voltage(output_voltages_(0));
+ output_builder.add_right_voltage(output_voltages_(1));
+ builder.CheckOk(builder.Send(output_builder.Finish()));
+ }
+ {
+ auto builder = turret_sender_.MakeBuilder();
+ auto turret_estimator_builder =
+ builder
+ .MakeBuilder<frc971::PotAndAbsoluteEncoderEstimatorState>();
+ turret_estimator_builder.add_position(turret_position_);
+ const flatbuffers::Offset<frc971::PotAndAbsoluteEncoderEstimatorState>
+ turret_estimator_offset = turret_estimator_builder.Finish();
+ auto turret_builder =
+ builder
+ .MakeBuilder<frc971::control_loops::
+ PotAndAbsoluteEncoderProfiledJointStatus>();
+ turret_builder.add_position(turret_position_);
+ turret_builder.add_velocity(turret_velocity_);
+ turret_builder.add_zeroed(true);
+ turret_builder.add_estimator_state(turret_estimator_offset);
+ const auto turret_offset = turret_builder.Finish();
+ auto status_builder =
+ builder
+ .MakeBuilder<y2022::control_loops::superstructure::Status>();
+ status_builder.add_turret(turret_offset);
+ builder.CheckOk(builder.Send(status_builder.Finish()));
+ }
+ });
+ roborio_test_event_loop_->OnRun([timer, this]() {
+ timer->Setup(roborio_test_event_loop_->monotonic_now(),
+ std::chrono::milliseconds(5));
+ });
+ }
+ {
+ aos::TimerHandler *timer = camera_test_event_loop_->AddTimer([this]() {
+ if (!send_targets_) {
+ return;
+ }
+ const frc971::control_loops::Pose robot_pose(
+ {drivetrain_plant_.GetPosition().x(),
+ drivetrain_plant_.GetPosition().y(), 0.0},
+ drivetrain_plant_.state()(2, 0));
+ const Eigen::Matrix<double, 4, 4> H_turret_camera =
+ frc971::control_loops::TransformationMatrixForYaw(
+ turret_position_) *
+ CameraTurretTransformation();
+
+ const Eigen::Matrix<double, 4, 4> H_field_camera =
+ robot_pose.AsTransformationMatrix() * TurretRobotTransformation() *
+ H_turret_camera;
+ const Eigen::Matrix<double, 4, 4> target_transform =
+ Eigen::Matrix<double, 4, 4>::Identity();
+ const Eigen::Matrix<double, 4, 4> H_camera_target =
+ H_field_camera.inverse() * target_transform;
+ const Eigen::Matrix<double, 4, 4> H_target_camera =
+ H_camera_target.inverse();
+
+ std::unique_ptr<y2022::vision::TargetEstimateT> estimate(
+ new y2022::vision::TargetEstimateT());
+ estimate->distance = H_target_camera.block<2, 1>(0, 3).norm();
+ estimate->angle_to_target =
+ std::atan2(-H_camera_target(0, 3), H_camera_target(2, 3));
+ estimate->camera_calibration.reset(new CameraCalibrationT());
+ {
+ estimate->camera_calibration->fixed_extrinsics.reset(
+ new TransformationMatrixT());
+ TransformationMatrixT *H_robot_turret =
+ estimate->camera_calibration->fixed_extrinsics.get();
+ H_robot_turret->data = MatrixToVector(TurretRobotTransformation());
+ }
+
+ estimate->camera_calibration->turret_extrinsics.reset(
+ new TransformationMatrixT());
+ estimate->camera_calibration->turret_extrinsics->data =
+ MatrixToVector(CameraTurretTransformation());
+
+ estimate->confidence = 1.0;
+
+ auto builder = target_sender_.MakeBuilder();
+ builder.CheckOk(
+ builder.Send(TargetEstimate::Pack(*builder.fbb(), estimate.get())));
+ });
+ camera_test_event_loop_->OnRun([timer, this]() {
+ timer->Setup(camera_test_event_loop_->monotonic_now(),
+ std::chrono::milliseconds(50));
+ });
+ }
+
+ localizer_control_send_timer_ =
+ roborio_test_event_loop_->AddTimer([this]() {
+ auto builder = control_sender_.MakeBuilder();
+ auto control_builder = builder.MakeBuilder<LocalizerControl>();
+ control_builder.add_x(localizer_control_x_);
+ control_builder.add_y(localizer_control_y_);
+ control_builder.add_theta(localizer_control_theta_);
+ control_builder.add_theta_uncertainty(0.01);
+ control_builder.add_keep_current_theta(false);
+ builder.CheckOk(builder.Send(control_builder.Finish()));
+ });
+
// Get things zeroed.
event_loop_factory_.RunFor(std::chrono::seconds(10));
CHECK(status_fetcher_.Fetch());
CHECK(status_fetcher_->zeroed());
+
+ if (!FLAGS_output_folder.empty()) {
+ logger_event_loop_ =
+ event_loop_factory_.MakeEventLoop("logger", imu_node_);
+ logger_ = std::make_unique<aos::logger::Logger>(logger_event_loop_.get());
+ logger_->StartLoggingOnRun(FLAGS_output_folder);
+ }
+ }
+
+ void SendLocalizerControl(double x, double y, double theta) {
+ localizer_control_x_ = x;
+ localizer_control_y_ = y;
+ localizer_control_theta_ = theta;
+ localizer_control_send_timer_->Setup(
+ roborio_test_event_loop_->monotonic_now());
+ }
+ ::testing::AssertionResult IsNear(double expected, double actual,
+ double epsilon) {
+ if (std::abs(expected - actual) < epsilon) {
+ return ::testing::AssertionSuccess();
+ } else {
+ return ::testing::AssertionFailure()
+ << "Expected " << expected << " but got " << actual
+ << " with a max difference of " << epsilon
+ << " and an actual difference of " << std::abs(expected - actual);
+ }
+ }
+ ::testing::AssertionResult VerifyEstimatorAccurate(double eps) {
+ const Eigen::Matrix<double, 5, 1> true_state = drivetrain_plant_.state();
+ ::testing::AssertionResult result(true);
+ status_fetcher_.Fetch();
+ if (!(result = IsNear(status_fetcher_->model_based()->x(), true_state(0),
+ eps))) {
+ return result;
+ }
+ if (!(result = IsNear(status_fetcher_->model_based()->y(), true_state(1),
+ eps))) {
+ return result;
+ }
+ if (!(result = IsNear(status_fetcher_->model_based()->theta(),
+ true_state(2), eps))) {
+ return result;
+ }
+ return result;
}
aos::FlatbufferDetachedBuffer<aos::Configuration> configuration_;
aos::SimulatedEventLoopFactory event_loop_factory_;
const aos::Node *const roborio_node_;
const aos::Node *const imu_node_;
+ const aos::Node *const camera_node_;
const control_loops::drivetrain::DrivetrainConfig<double> dt_config_;
std::unique_ptr<aos::EventLoop> localizer_event_loop_;
EventLoopLocalizer localizer_;
@@ -349,13 +555,30 @@
std::unique_ptr<aos::EventLoop> roborio_test_event_loop_;
std::unique_ptr<aos::EventLoop> imu_test_event_loop_;
+ std::unique_ptr<aos::EventLoop> camera_test_event_loop_;
std::unique_ptr<aos::EventLoop> logger_test_event_loop_;
aos::Sender<Output> output_sender_;
+ aos::Sender<y2022::control_loops::superstructure::Status> turret_sender_;
+ aos::Sender<y2022::vision::TargetEstimate> target_sender_;
+ aos::Sender<LocalizerControl> control_sender_;
aos::Fetcher<LocalizerOutput> output_fetcher_;
aos::Fetcher<LocalizerStatus> status_fetcher_;
Eigen::Vector2d output_voltages_ = Eigen::Vector2d::Zero();
+
+ aos::TimerHandler *localizer_control_send_timer_;
+
+ bool send_targets_ = false;
+ double turret_position_ = 0.0;
+ double turret_velocity_ = 0.0;
+
+ double localizer_control_x_ = 0.0;
+ double localizer_control_y_ = 0.0;
+ double localizer_control_theta_ = 0.0;
+
+ std::unique_ptr<aos::EventLoop> logger_event_loop_;
+ std::unique_ptr<aos::logger::Logger> logger_;
};
TEST_F(EventLoopLocalizerTest, Nominal) {
@@ -519,10 +742,145 @@
ASSERT_FALSE(status_fetcher_->model_based()->using_model());
ASSERT_LT(0.1, status_fetcher_->model_based()->residual())
<< aos::FlatbufferToJson(status_fetcher_.get(), {.multi_line = true});
- ASSERT_NEAR(drivetrain_plant_.state()(0),
- status_fetcher_->model_based()->x(), 1.0);
- ASSERT_NEAR(drivetrain_plant_.state()(1),
- status_fetcher_->model_based()->y(), 1e-6);
+ ASSERT_NEAR(drivetrain_plant_.state()(0), status_fetcher_->model_based()->x(),
+ 1.0);
+ ASSERT_NEAR(drivetrain_plant_.state()(1), status_fetcher_->model_based()->y(),
+ 1e-6);
}
-} // namespace frc91::controls::testing
+// Tests that image corrections in the nominal case (no errors) causes no
+// issues.
+TEST_F(EventLoopLocalizerTest, NominalImageCorrections) {
+ output_voltages_ << 3.0, 2.0;
+ drivetrain_plant_.set_accel_sin_magnitude(0.01);
+ send_targets_ = true;
+
+ event_loop_factory_.RunFor(std::chrono::seconds(4));
+ CHECK(status_fetcher_.Fetch());
+ ASSERT_TRUE(status_fetcher_->model_based()->using_model());
+ EXPECT_TRUE(VerifyEstimatorAccurate(1e-1));
+ ASSERT_TRUE(status_fetcher_->model_based()->has_statistics());
+ ASSERT_LT(10,
+ status_fetcher_->model_based()->statistics()->total_candidates());
+ ASSERT_EQ(status_fetcher_->model_based()->statistics()->total_candidates(),
+ status_fetcher_->model_based()->statistics()->total_accepted());
+}
+
+// Tests that image corrections when there is an error at the start results
+// in us actually getting corrected over time.
+TEST_F(EventLoopLocalizerTest, ImageCorrections) {
+ output_voltages_ << 0.0, 0.0;
+ drivetrain_plant_.mutable_state()->x() = 2.0;
+ drivetrain_plant_.mutable_state()->y() = 2.0;
+ SendLocalizerControl(5.0, 3.0, 0.0);
+ event_loop_factory_.RunFor(std::chrono::seconds(4));
+ CHECK(output_fetcher_.Fetch());
+ ASSERT_NEAR(5.0, output_fetcher_->x(), 1e-5);
+ ASSERT_NEAR(3.0, output_fetcher_->y(), 1e-5);
+ ASSERT_NEAR(0.0, output_fetcher_->theta(), 1e-5);
+
+ send_targets_ = true;
+
+ event_loop_factory_.RunFor(std::chrono::seconds(4));
+ CHECK(status_fetcher_.Fetch());
+ ASSERT_TRUE(status_fetcher_->model_based()->using_model());
+ EXPECT_TRUE(VerifyEstimatorAccurate(1e-1));
+ ASSERT_TRUE(status_fetcher_->model_based()->has_statistics());
+ ASSERT_LT(10,
+ status_fetcher_->model_based()->statistics()->total_candidates());
+ ASSERT_EQ(status_fetcher_->model_based()->statistics()->total_candidates(),
+ status_fetcher_->model_based()->statistics()->total_accepted());
+}
+
+// Tests that image corrections are ignored when the turret moves too fast.
+TEST_F(EventLoopLocalizerTest, ImageCorrectionsTurretTooFast) {
+ output_voltages_ << 0.0, 0.0;
+ drivetrain_plant_.mutable_state()->x() = 2.0;
+ drivetrain_plant_.mutable_state()->y() = 2.0;
+ SendLocalizerControl(5.0, 3.0, 0.0);
+ turret_velocity_ = 10.0;
+ event_loop_factory_.RunFor(std::chrono::seconds(4));
+ CHECK(output_fetcher_.Fetch());
+ ASSERT_NEAR(5.0, output_fetcher_->x(), 1e-5);
+ ASSERT_NEAR(3.0, output_fetcher_->y(), 1e-5);
+ ASSERT_NEAR(0.0, output_fetcher_->theta(), 1e-5);
+
+ send_targets_ = true;
+
+ event_loop_factory_.RunFor(std::chrono::seconds(4));
+ CHECK(status_fetcher_.Fetch());
+ CHECK(output_fetcher_.Fetch());
+ ASSERT_NEAR(5.0, output_fetcher_->x(), 1e-5);
+ ASSERT_NEAR(3.0, output_fetcher_->y(), 1e-5);
+ ASSERT_NEAR(0.0, output_fetcher_->theta(), 1e-5);
+ ASSERT_TRUE(status_fetcher_->model_based()->has_statistics());
+ ASSERT_LT(10,
+ status_fetcher_->model_based()->statistics()->total_candidates());
+ ASSERT_EQ(0, status_fetcher_->model_based()->statistics()->total_accepted());
+ ASSERT_EQ(status_fetcher_->model_based()->statistics()->total_candidates(),
+ status_fetcher_->model_based()
+ ->statistics()
+ ->rejection_reason_count()
+ ->Get(static_cast<int>(RejectionReason::TURRET_TOO_FAST)));
+ // We expect one more rejection to occur due to the time it takes all the
+ // information to propagate.
+ const int rejected_count =
+ status_fetcher_->model_based()->statistics()->total_candidates() + 1;
+ // Check that when we go back to being still we do successfully converge.
+ turret_velocity_ = 0.0;
+ turret_position_ = 1.0;
+ event_loop_factory_.RunFor(std::chrono::seconds(4));
+ CHECK(status_fetcher_.Fetch());
+ ASSERT_TRUE(status_fetcher_->model_based()->using_model());
+ EXPECT_TRUE(VerifyEstimatorAccurate(1e-1));
+ ASSERT_TRUE(status_fetcher_->model_based()->has_statistics());
+ ASSERT_EQ(status_fetcher_->model_based()->statistics()->total_candidates(),
+ rejected_count +
+ status_fetcher_->model_based()->statistics()->total_accepted());
+}
+
+// Tests that image corrections when we are in accel mode works.
+TEST_F(EventLoopLocalizerTest, ImageCorrectionsInAccel) {
+ output_voltages_ << 0.0, 0.0;
+ drivetrain_plant_.set_left_voltage_offset(200.0);
+ drivetrain_plant_.set_right_voltage_offset(200.0);
+ drivetrain_plant_.set_accel_sin_magnitude(0.01);
+ drivetrain_plant_.mutable_state()->x() = 2.0;
+ drivetrain_plant_.mutable_state()->y() = 2.0;
+ SendLocalizerControl(6.0, 3.0, 0.0);
+ event_loop_factory_.RunFor(std::chrono::seconds(1));
+ CHECK(output_fetcher_.Fetch());
+ CHECK(status_fetcher_.Fetch());
+ ASSERT_FALSE(status_fetcher_->model_based()->using_model());
+ EXPECT_FALSE(VerifyEstimatorAccurate(3.0));
+
+ send_targets_ = true;
+
+ event_loop_factory_.RunFor(std::chrono::seconds(4));
+ CHECK(status_fetcher_.Fetch());
+ ASSERT_FALSE(status_fetcher_->model_based()->using_model());
+ EXPECT_TRUE(VerifyEstimatorAccurate(3.0));
+ // y should be noticeably more accurate than x, since we are just driving
+ // straight.
+ ASSERT_NEAR(drivetrain_plant_.state()(1), status_fetcher_->model_based()->y(),
+ 0.1);
+ ASSERT_TRUE(status_fetcher_->model_based()->has_statistics());
+ ASSERT_LT(10,
+ status_fetcher_->model_based()->statistics()->total_candidates());
+ ASSERT_EQ(status_fetcher_->model_based()->statistics()->total_candidates(),
+ status_fetcher_->model_based()->statistics()->total_accepted());
+}
+
+TEST_F(EventLoopLocalizerTest, LedOutputs) {
+ send_targets_ = true;
+
+ event_loop_factory_.RunFor(std::chrono::milliseconds(10));
+ CHECK(output_fetcher_.Fetch());
+ EXPECT_EQ(output_fetcher_->led_outputs()->size(),
+ ModelBasedLocalizer::kNumPis);
+ for (LedOutput led_output : *output_fetcher_->led_outputs()) {
+ EXPECT_EQ(led_output, LedOutput::ON);
+ }
+}
+
+} // namespace frc971::controls::testing
diff --git a/y2022/localizer/localizer_visualization.fbs b/y2022/localizer/localizer_visualization.fbs
new file mode 100644
index 0000000..6cca9e8
--- /dev/null
+++ b/y2022/localizer/localizer_visualization.fbs
@@ -0,0 +1,26 @@
+include "y2022/localizer/localizer_status.fbs";
+
+namespace frc971.controls;
+
+table TargetEstimateDebug {
+ camera:uint8 (id: 0);
+ camera_x:double (id: 1);
+ camera_y:double (id: 2);
+ camera_theta:double (id: 3);
+ implied_robot_x:double (id: 4);
+ implied_robot_y:double (id: 5);
+ implied_robot_theta:double (id: 6);
+ implied_turret_goal:double (id: 7);
+ accepted:bool (id: 8);
+ rejection_reason:RejectionReason (id: 9);
+ // Image age (more human-readable than trying to interpret raw nanosecond
+ // values).
+ image_age_sec:double (id: 10);
+}
+
+table LocalizerVisualization {
+ targets:[TargetEstimateDebug] (id: 0);
+ statistics:CumulativeStatistics (id: 1);
+}
+
+root_type LocalizerVisualization;
diff --git a/y2022/log_web_proxy.sh b/y2022/log_web_proxy.sh
new file mode 100755
index 0000000..cb945ab
--- /dev/null
+++ b/y2022/log_web_proxy.sh
@@ -0,0 +1 @@
+./aos/network/log_web_proxy_main --data_dir=y2022/www $@
diff --git a/y2022/setpoint.fbs b/y2022/setpoint.fbs
new file mode 100644
index 0000000..f8dc458
--- /dev/null
+++ b/y2022/setpoint.fbs
@@ -0,0 +1,14 @@
+namespace y2022.input.joysticks;
+
+// Table for dynamically setting shooter goals
+table Setpoint {
+ // Catapult shot release angle
+ catapult_position:double (id: 0);
+ // Catapult shot velocity
+ catapult_velocity:double (id: 1);
+
+ // Turret angle
+ turret:double (id: 2);
+}
+
+root_type Setpoint;
diff --git a/y2022/setpoint_setter.cc b/y2022/setpoint_setter.cc
new file mode 100644
index 0000000..b588636
--- /dev/null
+++ b/y2022/setpoint_setter.cc
@@ -0,0 +1,35 @@
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "gflags/gflags.h"
+#include "glog/logging.h"
+#include "y2022/setpoint_generated.h"
+
+DEFINE_double(catapult_position, 0.03, "Catapult shot position");
+DEFINE_double(catapult_velocity, 18.0, "Catapult shot velocity");
+DEFINE_double(turret, 0.0, "Turret setpoint");
+
+DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
+
+using y2022::input::joysticks::Setpoint;
+
+int main(int argc, char **argv) {
+ aos::InitGoogle(&argc, &argv);
+
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig(FLAGS_config);
+
+ aos::ShmEventLoop event_loop(&config.message());
+
+ auto setpoint_sender = event_loop.MakeSender<Setpoint>("/superstructure");
+
+ aos::Sender<Setpoint>::Builder builder = setpoint_sender.MakeBuilder();
+
+ Setpoint::Builder setpoint_builder = builder.MakeBuilder<Setpoint>();
+
+ setpoint_builder.add_catapult_position(FLAGS_catapult_position);
+ setpoint_builder.add_catapult_velocity(FLAGS_catapult_velocity);
+ setpoint_builder.add_turret(FLAGS_turret);
+ builder.CheckOk(builder.Send(setpoint_builder.Finish()));
+
+ return 0;
+}
diff --git a/y2022/vision/BUILD b/y2022/vision/BUILD
index 599b4ed..e9543cf 100644
--- a/y2022/vision/BUILD
+++ b/y2022/vision/BUILD
@@ -1,4 +1,5 @@
load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library", "flatbuffer_py_library")
+load("@npm//@bazel/typescript:index.bzl", "ts_library")
flatbuffer_cc_library(
name = "calibration_fbs",
@@ -23,6 +24,18 @@
visibility = ["//visibility:public"],
)
+ts_library(
+ name = "vision_plotter",
+ srcs = ["vision_plotter.ts"],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//aos/network/www:aos_plotter",
+ "//aos/network/www:colors",
+ "//aos/network/www:proxy",
+ ],
+)
+
py_library(
name = "camera_definition",
srcs = [
@@ -97,6 +110,7 @@
":blob_detector_lib",
":calibration_data",
":calibration_fbs",
+ ":geometry_lib",
":target_estimate_fbs",
":target_estimator_lib",
"//aos:flatbuffer_merge",
@@ -106,6 +120,7 @@
"//frc971/vision:v4l2_reader",
"//frc971/vision:vision_fbs",
"//third_party:opencv",
+ "//y2022/localizer:localizer_output_fbs",
],
)
@@ -124,6 +139,31 @@
)
cc_library(
+ name = "geometry_lib",
+ hdrs = [
+ "geometry.h",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//y2022:__subpackages__"],
+ deps = [
+ "//aos/util:math",
+ "//third_party:opencv",
+ "@com_github_google_glog//:glog",
+ ],
+)
+
+cc_test(
+ name = "geometry_test",
+ srcs = [
+ "geometry_test.cc",
+ ],
+ deps = [
+ ":geometry_lib",
+ "//aos/testing:googletest",
+ ],
+)
+
+cc_library(
name = "blob_detector_lib",
srcs = [
"blob_detector.cc",
@@ -134,6 +174,7 @@
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//y2022:__subpackages__"],
deps = [
+ ":geometry_lib",
"//aos/network:team_number",
"//aos/time",
"//third_party:opencv",
@@ -151,12 +192,14 @@
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//y2022:__subpackages__"],
deps = [
+ ":blob_detector_lib",
":calibration_fbs",
":target_estimate_fbs",
"//aos/logging",
"//aos/time",
"//frc971/control_loops:quaternion_utils",
"//third_party:opencv",
+ "//y2022:constants",
"@com_google_absl//absl/strings:str_format",
"@com_google_ceres_solver//:ceres",
"@org_tuxfamily_eigen//:eigen",
@@ -186,6 +229,7 @@
visibility = ["//y2022:__subpackages__"],
deps = [
":blob_detector_lib",
+ ":calibration_data",
":target_estimator_lib",
"//aos:init",
"//aos/events:shm_event_loop",
@@ -193,3 +237,31 @@
"//third_party:opencv",
],
)
+
+cc_binary(
+ name = "extrinsics_calibration",
+ srcs = [
+ "extrinsics_calibration.cc",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//y2022:__subpackages__"],
+ deps = [
+ "//aos:init",
+ "//aos/events/logging:log_reader",
+ "//frc971/control_loops:profiled_subsystem_fbs",
+ "//frc971/vision:extrinsics_calibration",
+ "//y2022/control_loops/superstructure:superstructure_status_fbs",
+ ],
+)
+
+cc_binary(
+ name = "image_decimator",
+ srcs = ["image_decimator.cc"],
+ visibility = ["//y2022:__subpackages__"],
+ deps = [
+ "//aos:flatbuffers",
+ "//aos:init",
+ "//aos/events:shm_event_loop",
+ "//frc971/vision:vision_fbs",
+ ],
+)
diff --git a/y2022/vision/blob_detector.cc b/y2022/vision/blob_detector.cc
index 2c68a27..873cf43 100644
--- a/y2022/vision/blob_detector.cc
+++ b/y2022/vision/blob_detector.cc
@@ -7,11 +7,13 @@
#include "aos/network/team_number.h"
#include "aos/time/time.h"
#include "opencv2/features2d.hpp"
+#include "opencv2/highgui/highgui.hpp"
#include "opencv2/imgproc.hpp"
+#include "y2022/vision/geometry.h"
DEFINE_uint64(red_delta, 100,
"Required difference between green pixels vs. red");
-DEFINE_uint64(blue_delta, 50,
+DEFINE_uint64(blue_delta, 1,
"Required difference between green pixels vs. blue");
DEFINE_bool(use_outdoors, false,
@@ -50,6 +52,14 @@
}
}
+ // Fill in the contours on the binarized image so that we don't detect
+ // multiple blobs in one
+ const auto blobs = FindBlobs(binarized_image);
+ for (auto it = blobs.begin(); it < blobs.end(); it++) {
+ cv::drawContours(binarized_image, blobs, it - blobs.begin(),
+ cv::Scalar(255), cv::FILLED);
+ }
+
return binarized_image;
}
@@ -66,123 +76,37 @@
std::vector<BlobDetector::BlobStats> BlobDetector::ComputeStats(
const std::vector<std::vector<cv::Point>> &blobs) {
+ cv::Mat img = cv::Mat::zeros(640, 480, CV_8UC3);
+
std::vector<BlobDetector::BlobStats> blob_stats;
for (auto blob : blobs) {
- auto blob_size = cv::boundingRect(blob).size();
+ // Opencv doesn't have height and width ordered correctly.
+ // The rotated size will only be used after blobs have been filtered, so it
+ // is ok to assume that width is the larger side
+ const cv::Size rotated_rect_size_unordered = cv::minAreaRect(blob).size;
+ const cv::Size rotated_rect_size = {
+ std::max(rotated_rect_size_unordered.width,
+ rotated_rect_size_unordered.height),
+ std::min(rotated_rect_size_unordered.width,
+ rotated_rect_size_unordered.height)};
+ const cv::Size bounding_box_size = cv::boundingRect(blob).size();
+
cv::Moments moments = cv::moments(blob);
const auto centroid =
cv::Point(moments.m10 / moments.m00, moments.m01 / moments.m00);
const double aspect_ratio =
- static_cast<double>(blob_size.width) / blob_size.height;
+ static_cast<double>(bounding_box_size.width) / bounding_box_size.height;
const double area = moments.m00;
const size_t num_points = blob.size();
blob_stats.emplace_back(
- BlobStats{centroid, aspect_ratio, area, num_points});
+ BlobStats{centroid, rotated_rect_size, aspect_ratio, area, num_points});
}
+
return blob_stats;
}
-namespace {
-
-// Linear equation in the form ax + by = c
-struct Line {
- public:
- double a, b, c;
-
- std::optional<cv::Point2d> Intersection(const Line &l) const {
- // Use Cramer's rule to solve for the intersection
- const double denominator = Determinant(a, b, l.a, l.b);
- const double numerator_x = Determinant(c, b, l.c, l.b);
- const double numerator_y = Determinant(a, c, l.a, l.c);
-
- std::optional<cv::Point2d> intersection = std::nullopt;
- // Return nullopt if the denominator is 0, meaning the same slopes
- if (denominator != 0) {
- intersection =
- cv::Point2d(numerator_x / denominator, numerator_y / denominator);
- }
-
- return intersection;
- }
-
- private: // Determinant of [[a, b], [c, d]]
- static double Determinant(double a, double b, double c, double d) {
- return (a * d) - (b * c);
- }
-};
-
-struct Circle {
- public:
- cv::Point2d center;
- double radius;
-
- static std::optional<Circle> Fit(std::vector<cv::Point2d> centroids) {
- CHECK_EQ(centroids.size(), 3ul);
- // For the 3 points, we have 3 equations in the form
- // (x - h)^2 + (y - k)^2 = r^2
- // Manipulate them to solve for the center and radius
- // (x1 - h)^2 + (y1 - k)^2 = r^2 ->
- // x1^2 + h^2 - 2x1h + y1^2 + k^2 - 2y1k = r^2
- // Also, (x2 - h)^2 + (y2 - k)^2 = r^2
- // Subtracting these two, we get
- // x1^2 - x2^2 - 2h(x1 - x2) + y1^2 - y2^2 - 2k(y1 - y2) = 0 ->
- // h(x1 - x2) + k(y1 - y2) = (-x1^2 + x2^2 - y1^2 + y2^2) / -2
- // Doing the same with equations 1 and 3, we get the second linear equation
- // h(x1 - x3) + k(y1 - y3) = (-x1^2 + x3^2 - y1^2 + y3^2) / -2
- // Now, we can solve for their intersection and find the center
- const auto l =
- Line{centroids[0].x - centroids[1].x, centroids[0].y - centroids[1].y,
- (-std::pow(centroids[0].x, 2) + std::pow(centroids[1].x, 2) -
- std::pow(centroids[0].y, 2) + std::pow(centroids[1].y, 2)) /
- -2.0};
- const auto m =
- Line{centroids[0].x - centroids[2].x, centroids[0].y - centroids[2].y,
- (-std::pow(centroids[0].x, 2) + std::pow(centroids[2].x, 2) -
- std::pow(centroids[0].y, 2) + std::pow(centroids[2].y, 2)) /
- -2.0};
- const auto center = l.Intersection(m);
-
- std::optional<Circle> circle = std::nullopt;
- if (center) {
- // Now find the radius
- const double radius = cv::norm(centroids[0] - *center);
- circle = Circle{*center, radius};
- }
- return circle;
- }
-
- double DistanceTo(cv::Point2d p) const {
- const auto p_prime = TranslateToOrigin(p);
- // Now, the distance is simply the difference between distance from the
- // origin to p' and the radius.
- return std::abs(cv::norm(p_prime) - radius);
- }
-
- double AngleOf(cv::Point2d p) const {
- auto p_prime = TranslateToOrigin(p);
- // Flip the y because y values go downwards.
- p_prime.y *= -1;
- return std::atan2(p_prime.y, p_prime.x);
- }
-
- // TODO(milind): handle wrapping around 2pi
- bool InAngleRange(cv::Point2d p, double theta_min, double theta_max) const {
- const double theta = AngleOf(p);
- return (theta >= theta_min && theta <= theta_max);
- }
-
- private:
- // Translate the point on the circle
- // as if the circle's center is the origin (0,0)
- cv::Point2d TranslateToOrigin(cv::Point2d p) const {
- return cv::Point2d(p.x - center.x, p.y - center.y);
- }
-};
-
-} // namespace
-
void BlobDetector::FilterBlobs(BlobResult *blob_result) {
std::vector<std::vector<cv::Point>> filtered_blobs;
std::vector<BlobStats> filtered_stats;
@@ -216,8 +140,8 @@
constexpr double kMinBlobAngle = 50.0 * kDegToRad;
constexpr double kMaxBlobAngle = M_PI - kMinBlobAngle;
std::vector<std::vector<cv::Point>> blob_circle;
+ std::vector<BlobStats> blob_circle_stats;
Circle circle;
- std::vector<cv::Point2d> centroids;
// If we see more than this number of blobs after filtering based on
// color/size, the circle fit may detect noise so just return no blobs.
@@ -240,11 +164,11 @@
std::vector<std::vector<cv::Point>> current_blobs{
filtered_blobs[j], filtered_blobs[k], filtered_blobs[l]};
- std::vector<cv::Point2d> current_centroids{filtered_stats[j].centroid,
- filtered_stats[k].centroid,
- filtered_stats[l].centroid};
+ std::vector<BlobStats> current_stats{filtered_stats[j], filtered_stats[k],
+ filtered_stats[l]};
const std::optional<Circle> current_circle =
- Circle::Fit(current_centroids);
+ Circle::Fit({current_stats[0].centroid, current_stats[1].centroid,
+ current_stats[2].centroid});
// Make sure that a circle could be created from the points
if (!current_circle) {
@@ -253,11 +177,11 @@
// Only try to fit points to this circle if all of these are between
// certain angles.
- if (current_circle->InAngleRange(current_centroids[0], kMinBlobAngle,
+ if (current_circle->InAngleRange(current_stats[0].centroid, kMinBlobAngle,
kMaxBlobAngle) &&
- current_circle->InAngleRange(current_centroids[1], kMinBlobAngle,
+ current_circle->InAngleRange(current_stats[1].centroid, kMinBlobAngle,
kMaxBlobAngle) &&
- current_circle->InAngleRange(current_centroids[2], kMinBlobAngle,
+ current_circle->InAngleRange(current_stats[2].centroid, kMinBlobAngle,
kMaxBlobAngle)) {
for (size_t m = 0; m < filtered_blobs.size(); m++) {
// Add this blob to the list if it is close to the circle, is on the
@@ -268,44 +192,31 @@
(current_circle->DistanceTo(filtered_stats[m].centroid) <
kCircleDistanceThreshold)) {
current_blobs.emplace_back(filtered_blobs[m]);
- current_centroids.emplace_back(filtered_stats[m].centroid);
+ current_stats.emplace_back(filtered_stats[m]);
}
}
if (current_blobs.size() > blob_circle.size()) {
blob_circle = current_blobs;
+ blob_circle_stats = current_stats;
circle = *current_circle;
- centroids = current_centroids;
}
}
}
}
cv::Point avg_centroid(-1, -1);
- if (centroids.size() > 0) {
- for (auto centroid : centroids) {
- avg_centroid.x += centroid.x;
- avg_centroid.y += centroid.y;
+ if (blob_circle.size() > 0) {
+ for (const auto &stats : blob_circle_stats) {
+ avg_centroid.x += stats.centroid.x;
+ avg_centroid.y += stats.centroid.y;
}
- avg_centroid.x /= centroids.size();
- avg_centroid.y /= centroids.size();
-
- for (auto centroid : centroids) {
- blob_result->filtered_centroids.emplace_back(
- static_cast<int>(centroid.x), static_cast<int>(centroid.y));
- }
-
- // Sort the filtered centroids to make them go from left to right
- std::sort(blob_result->filtered_centroids.begin(),
- blob_result->filtered_centroids.end(),
- [&circle](cv::Point p, cv::Point q) {
- // If the angle is greater, it is more left and should be
- // considered "less" for sorting
- return circle.AngleOf(p) > circle.AngleOf(q);
- });
+ avg_centroid.x /= blob_circle_stats.size();
+ avg_centroid.y /= blob_circle_stats.size();
}
blob_result->filtered_blobs = blob_circle;
+ blob_result->filtered_stats = blob_circle_stats;
blob_result->centroid = avg_centroid;
}
@@ -318,8 +229,14 @@
cv::Scalar(0, 0, 255), 0);
}
- cv::drawContours(view_image, blob_result.filtered_blobs, -1,
- cv::Scalar(0, 100, 0), cv::FILLED);
+ if (blob_result.filtered_blobs.size() > 0) {
+ cv::drawContours(view_image, blob_result.filtered_blobs, -1,
+ cv::Scalar(0, 100, 0), cv::FILLED);
+ }
+
+ for (const auto &blob : blob_result.filtered_blobs) {
+ cv::polylines(view_image, blob, true, cv::Scalar(0, 255, 0));
+ }
static constexpr double kCircleRadius = 2.0;
// Draw blob centroids
@@ -327,8 +244,8 @@
cv::circle(view_image, stats.centroid, kCircleRadius,
cv::Scalar(0, 215, 255), cv::FILLED);
}
- for (auto centroid : blob_result.filtered_centroids) {
- cv::circle(view_image, centroid, kCircleRadius, cv::Scalar(0, 255, 0),
+ for (auto stats : blob_result.filtered_stats) {
+ cv::circle(view_image, stats.centroid, kCircleRadius, cv::Scalar(0, 255, 0),
cv::FILLED);
}
@@ -345,7 +262,7 @@
blob_result->blob_stats = ComputeStats(blob_result->unfiltered_blobs);
FilterBlobs(blob_result);
auto end = aos::monotonic_clock::now();
- VLOG(2) << "Blob detection elapsed time: "
+ VLOG(1) << "Blob detection elapsed time: "
<< std::chrono::duration<double, std::milli>(end - start).count()
<< " ms";
}
diff --git a/y2022/vision/blob_detector.h b/y2022/vision/blob_detector.h
index d0a2b85..a60316a 100644
--- a/y2022/vision/blob_detector.h
+++ b/y2022/vision/blob_detector.h
@@ -11,6 +11,9 @@
public:
struct BlobStats {
cv::Point centroid;
+ // Size of the rotated rect fitting around the blob
+ cv::Size size;
+ // Aspect ratio of the non-rotated bounding box
double aspect_ratio;
double area;
size_t num_points;
@@ -20,8 +23,7 @@
cv::Mat binarized_image;
std::vector<std::vector<cv::Point>> filtered_blobs, unfiltered_blobs;
std::vector<BlobStats> blob_stats;
- // In sorted order from left to right on the circle
- std::vector<cv::Point> filtered_centroids;
+ std::vector<BlobStats> filtered_stats;
cv::Point centroid;
};
diff --git a/y2022/vision/camera_definition.py b/y2022/vision/camera_definition.py
index 21ae7f3..7ad2c0b 100644
--- a/y2022/vision/camera_definition.py
+++ b/y2022/vision/camera_definition.py
@@ -99,10 +99,8 @@
T = np.array([0.0, 0.0, 0.0])
if pi_number == "pi1":
- # This is the turret camera
- camera_pitch = -10.0 * np.pi / 180.0
- is_turret = True
- T = np.array([7.5 * 0.0254, -5.5 * 0.0254, 41.0 * 0.0254])
+ camera_pitch = -35.0 * np.pi / 180.0
+ T = np.array([0.0, 0.0, 37.0 * 0.0254])
elif pi_number == "pi2":
T = np.array([4.5 * 0.0254, 3.75 * 0.0254, 26.0 * 0.0254])
elif pi_number == "pi3":
diff --git a/y2022/vision/camera_reader.cc b/y2022/vision/camera_reader.cc
index 637ad0a..94b2d96 100644
--- a/y2022/vision/camera_reader.cc
+++ b/y2022/vision/camera_reader.cc
@@ -50,6 +50,8 @@
return builder->fbb()->CreateVectorOfStructs(points_fbs);
}
+constexpr size_t kMaxBlobsForDebug = 100;
+
// Converts a vector of cv::Point to PointT for the flatbuffer
flatbuffers::Offset<flatbuffers::Vector<flatbuffers::Offset<Blob>>>
CvBlobsToFbs(const std::vector<std::vector<cv::Point>> &blobs,
@@ -60,6 +62,9 @@
auto blob_builder = builder->MakeBuilder<Blob>();
blob_builder.add_points(points_offset);
blobs_fbs.emplace_back(blob_builder.Finish());
+ if (blobs_fbs.size() == kMaxBlobsForDebug) {
+ break;
+ }
}
return builder->fbb()->CreateVector(blobs_fbs.data(), blobs_fbs.size());
}
@@ -98,8 +103,8 @@
CvBlobsToFbs(blob_result.unfiltered_blobs, &builder);
const auto blob_stats_offset =
BlobStatsToFbs(blob_result.blob_stats, &builder);
- const auto filtered_centroids_offset =
- CvPointsToFbs(blob_result.filtered_centroids, &builder);
+ const auto filtered_stats_offset =
+ BlobStatsToFbs(blob_result.filtered_stats, &builder);
const Point centroid_fbs =
Point{blob_result.centroid.x, blob_result.centroid.y};
@@ -107,12 +112,12 @@
blob_result_builder.add_filtered_blobs(filtered_blobs_offset);
blob_result_builder.add_unfiltered_blobs(unfiltered_blobs_offset);
blob_result_builder.add_blob_stats(blob_stats_offset);
- blob_result_builder.add_filtered_centroids(filtered_centroids_offset);
+ blob_result_builder.add_filtered_stats(filtered_stats_offset);
blob_result_builder.add_centroid(¢roid_fbs);
blob_result_offset = blob_result_builder.Finish();
}
- target_estimator_.Solve(blob_result.filtered_centroids, std::nullopt);
+ target_estimator_.Solve(blob_result.filtered_stats, std::nullopt);
const auto camera_calibration_offset =
aos::RecursiveCopyFlatBuffer(camera_calibration_, builder.fbb());
@@ -206,6 +211,26 @@
reader_->SendLatestImage();
read_image_timer_->Setup(event_loop_->monotonic_now());
+
+ // Disable the LEDs based on localizer output
+ if (localizer_output_fetcher_.Fetch()) {
+ const auto node_name = event_loop_->node()->name()->string_view();
+ const size_t pi_number =
+ std::atol(node_name.substr(node_name.size() - 1).data());
+
+ CHECK(localizer_output_fetcher_->has_led_outputs() &&
+ localizer_output_fetcher_->led_outputs()->size() > pi_number);
+
+ const LedOutput led_output =
+ localizer_output_fetcher_->led_outputs()->Get(pi_number);
+
+ if (led_output != prev_led_output_) {
+ gpio_disable_control_.GPIOWrite(led_output == LedOutput::OFF ? kGPIOHigh
+ : kGPIOLow);
+
+ prev_led_output_ = led_output;
+ }
+ }
}
} // namespace vision
diff --git a/y2022/vision/camera_reader.h b/y2022/vision/camera_reader.h
index 3b1eca6..707e04e 100644
--- a/y2022/vision/camera_reader.h
+++ b/y2022/vision/camera_reader.h
@@ -13,6 +13,7 @@
#include "aos/network/team_number.h"
#include "frc971/vision/v4l2_reader.h"
#include "frc971/vision/vision_generated.h"
+#include "y2022/localizer/localizer_output_generated.h"
#include "y2022/vision/calibration_data.h"
#include "y2022/vision/calibration_generated.h"
#include "y2022/vision/gpio.h"
@@ -23,10 +24,9 @@
namespace vision {
using namespace frc971::vision;
+using frc971::controls::LedOutput;
// TODO<jim>: Probably need to break out LED control to separate process
-// TODO<jim>: Need to add sync with camera to strobe lights
-
class CameraReader {
public:
CameraReader(aos::ShmEventLoop *event_loop,
@@ -40,6 +40,9 @@
target_estimator_(CameraIntrinsics(), CameraExtrinsics()),
target_estimate_sender_(
event_loop->MakeSender<TargetEstimate>("/camera")),
+ localizer_output_fetcher_(
+ event_loop->MakeFetcher<frc971::controls::LocalizerOutput>(
+ "/localizer")),
read_image_timer_(event_loop->AddTimer([this]() { ReadImage(); })),
gpio_imu_pin_(GPIOControl(GPIO_PIN_SCLK_IMU, kGPIOIn)),
gpio_pwm_control_(GPIOPWMControl(GPIO_PIN_SCK_PWM, duty_cycle_)),
@@ -66,18 +69,20 @@
void ReadImage();
cv::Mat CameraIntrinsics() const {
- const cv::Mat result(3, 3, CV_32F,
- const_cast<void *>(static_cast<const void *>(
- camera_calibration_->intrinsics()->data())));
+ cv::Mat result(3, 3, CV_32F,
+ const_cast<void *>(static_cast<const void *>(
+ camera_calibration_->intrinsics()->data())));
+ result.convertTo(result, CV_64F);
CHECK_EQ(result.total(), camera_calibration_->intrinsics()->size());
return result;
}
cv::Mat CameraExtrinsics() const {
- const cv::Mat result(
+ cv::Mat result(
4, 4, CV_32F,
const_cast<void *>(static_cast<const void *>(
camera_calibration_->fixed_extrinsics()->data()->data())));
+ result.convertTo(result, CV_64F);
CHECK_EQ(result.total(),
camera_calibration_->fixed_extrinsics()->data()->size());
return result;
@@ -99,6 +104,9 @@
TargetEstimator target_estimator_;
aos::Sender<TargetEstimate> target_estimate_sender_;
+ LedOutput prev_led_output_ = LedOutput::ON;
+ aos::Fetcher<frc971::controls::LocalizerOutput> localizer_output_fetcher_;
+
// We schedule this immediately to read an image. Having it on a timer
// means other things can run on the event loop in between.
aos::TimerHandler *const read_image_timer_;
diff --git a/y2022/vision/camera_reader_main.cc b/y2022/vision/camera_reader_main.cc
index f91b07e..d5ba448 100644
--- a/y2022/vision/camera_reader_main.cc
+++ b/y2022/vision/camera_reader_main.cc
@@ -6,7 +6,7 @@
// bazel run //y2022/vision:camera_reader -- --config y2022/aos_config.json
// --override_hostname pi-7971-1 --ignore_timestamps true
DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
-DEFINE_double(duty_cycle, 0.25, "Duty cycle of the LEDs");
+DEFINE_double(duty_cycle, 0.5, "Duty cycle of the LEDs");
DEFINE_uint32(exposure, 5,
"Exposure time, in 100us increments; 0 implies auto exposure");
diff --git a/y2022/vision/extrinsics_calibration.cc b/y2022/vision/extrinsics_calibration.cc
new file mode 100644
index 0000000..49f2ca3
--- /dev/null
+++ b/y2022/vision/extrinsics_calibration.cc
@@ -0,0 +1,129 @@
+#include "frc971/vision/extrinsics_calibration.h"
+
+#include "Eigen/Dense"
+#include "Eigen/Geometry"
+#include "absl/strings/str_format.h"
+#include "aos/events/logging/log_reader.h"
+#include "aos/init.h"
+#include "aos/network/team_number.h"
+#include "aos/time/time.h"
+#include "aos/util/file.h"
+#include "frc971/control_loops/quaternion_utils.h"
+#include "frc971/vision/vision_generated.h"
+#include "frc971/wpilib/imu_batch_generated.h"
+#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
+#include "y2020/vision/sift/sift_generated.h"
+#include "y2020/vision/sift/sift_training_generated.h"
+#include "y2020/vision/tools/python_code/sift_training_data.h"
+
+DEFINE_string(pi, "pi-7971-2", "Pi name to calibrate.");
+DEFINE_bool(plot, false, "Whether to plot the resulting data.");
+
+namespace frc971 {
+namespace vision {
+namespace chrono = std::chrono;
+using aos::distributed_clock;
+using aos::monotonic_clock;
+
+// TODO(austin): Source of IMU data? Is it the same?
+// TODO(austin): Intrinsics data?
+
+void Main(int argc, char **argv) {
+ CalibrationData data;
+
+ {
+ // Now, accumulate all the data into the data object.
+ aos::logger::LogReader reader(
+ aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
+
+ aos::SimulatedEventLoopFactory factory(reader.configuration());
+ reader.Register(&factory);
+
+ CHECK(aos::configuration::MultiNode(reader.configuration()));
+
+ // Find the nodes we care about.
+ const aos::Node *const roborio_node =
+ aos::configuration::GetNode(factory.configuration(), "roborio");
+
+ std::optional<uint16_t> pi_number = aos::network::ParsePiNumber(FLAGS_pi);
+ CHECK(pi_number);
+ LOG(INFO) << "Pi " << *pi_number;
+ const aos::Node *const pi_node = aos::configuration::GetNode(
+ factory.configuration(), absl::StrCat("pi", *pi_number));
+
+ LOG(INFO) << "roboRIO " << aos::FlatbufferToJson(roborio_node);
+ LOG(INFO) << "Pi " << aos::FlatbufferToJson(pi_node);
+
+ std::unique_ptr<aos::EventLoop> roborio_event_loop =
+ factory.MakeEventLoop("calibration", roborio_node);
+ std::unique_ptr<aos::EventLoop> pi_event_loop =
+ factory.MakeEventLoop("calibration", pi_node);
+
+ // Now, hook Calibration up to everything.
+ Calibration extractor(&factory, pi_event_loop.get(),
+ roborio_event_loop.get(), FLAGS_pi, &data);
+
+ aos::NodeEventLoopFactory *roborio_factory =
+ factory.GetNodeEventLoopFactory(roborio_node->name()->string_view());
+ roborio_event_loop->MakeWatcher(
+ "/superstructure",
+ [roborio_factory, roborio_event_loop = roborio_event_loop.get(),
+ &data](const y2022::control_loops::superstructure::Status &status) {
+ data.AddTurret(
+ roborio_factory->ToDistributedClock(
+ roborio_event_loop->context().monotonic_event_time),
+ Eigen::Vector2d(status.turret()->position(),
+ status.turret()->velocity()));
+ });
+
+ factory.Run();
+
+ reader.Deregister();
+ }
+
+ LOG(INFO) << "Done with event_loop running";
+ // And now we have it, we can start processing it.
+
+ const Eigen::Quaternion<double> nominal_initial_orientation(
+ frc971::controls::ToQuaternionFromRotationVector(
+ Eigen::Vector3d(0.0, 0.0, M_PI)));
+ const Eigen::Quaternion<double> nominal_pivot_to_camera(
+ Eigen::AngleAxisd(-0.5 * M_PI, Eigen::Vector3d::UnitX()));
+ const Eigen::Quaternion<double> nominal_board_to_world(
+ Eigen::AngleAxisd(0.5 * M_PI, Eigen::Vector3d::UnitX()));
+
+ CalibrationParameters calibration_parameters;
+ calibration_parameters.initial_orientation = nominal_initial_orientation;
+ calibration_parameters.pivot_to_camera = nominal_pivot_to_camera;
+ calibration_parameters.board_to_world = nominal_board_to_world;
+
+ Solve(data, &calibration_parameters);
+ LOG(INFO) << "Nominal initial_orientation "
+ << nominal_initial_orientation.coeffs().transpose();
+ LOG(INFO) << "Nominal pivot_to_camera "
+ << nominal_pivot_to_camera.coeffs().transpose();
+
+ LOG(INFO) << "pivot_to_camera delta "
+ << frc971::controls::ToRotationVectorFromQuaternion(
+ calibration_parameters.pivot_to_camera *
+ nominal_pivot_to_camera.inverse())
+ .transpose();
+ LOG(INFO) << "board_to_world delta "
+ << frc971::controls::ToRotationVectorFromQuaternion(
+ calibration_parameters.board_to_world *
+ nominal_board_to_world.inverse())
+ .transpose();
+
+ if (FLAGS_plot) {
+ Plot(data, calibration_parameters);
+ }
+}
+
+} // namespace vision
+} // namespace frc971
+
+int main(int argc, char **argv) {
+ aos::InitGoogle(&argc, &argv);
+
+ frc971::vision::Main(argc, argv);
+}
diff --git a/y2022/vision/geometry.h b/y2022/vision/geometry.h
new file mode 100644
index 0000000..31e8629
--- /dev/null
+++ b/y2022/vision/geometry.h
@@ -0,0 +1,131 @@
+#include "aos/util/math.h"
+#include "glog/logging.h"
+#include "opencv2/core/types.hpp"
+
+namespace y2022::vision {
+
+// Linear equation in the form y = mx + b
+struct SlopeInterceptLine {
+ double m, b;
+
+ inline SlopeInterceptLine(cv::Point2d p, cv::Point2d q) {
+ if (p.x == q.x) {
+ CHECK_EQ(p.y, q.y) << "Can't fit line to infinite slope";
+
+ // If two identical points were passed in, give the slope 0,
+ // with it passing the point.
+ m = 0.0;
+ } else {
+ m = (p.y - q.y) / (p.x - q.x);
+ }
+ // y = mx + b -> b = y - mx
+ b = p.y - (m * p.x);
+ }
+
+ inline double operator()(double x) const { return (m * x) + b; }
+};
+
+// Linear equation in the form ax + by = c
+struct StdFormLine {
+ public:
+ double a, b, c;
+
+ inline std::optional<cv::Point2d> Intersection(const StdFormLine &l) const {
+ // Use Cramer's rule to solve for the intersection
+ const double denominator = Determinant(a, b, l.a, l.b);
+ const double numerator_x = Determinant(c, b, l.c, l.b);
+ const double numerator_y = Determinant(a, c, l.a, l.c);
+
+ std::optional<cv::Point2d> intersection = std::nullopt;
+ // Return nullopt if the denominator is 0, meaning the same slopes
+ if (denominator != 0) {
+ intersection =
+ cv::Point2d(numerator_x / denominator, numerator_y / denominator);
+ }
+
+ return intersection;
+ }
+
+ private: // Determinant of [[a, b], [c, d]]
+ static inline double Determinant(double a, double b, double c, double d) {
+ return (a * d) - (b * c);
+ }
+};
+
+struct Circle {
+ public:
+ cv::Point2d center;
+ double radius;
+
+ static inline std::optional<Circle> Fit(std::vector<cv::Point2d> points) {
+ CHECK_EQ(points.size(), 3ul);
+ // For the 3 points, we have 3 equations in the form
+ // (x - h)^2 + (y - k)^2 = r^2
+ // Manipulate them to solve for the center and radius
+ // (x1 - h)^2 + (y1 - k)^2 = r^2 ->
+ // x1^2 + h^2 - 2x1h + y1^2 + k^2 - 2y1k = r^2
+ // Also, (x2 - h)^2 + (y2 - k)^2 = r^2
+ // Subtracting these two, we get
+ // x1^2 - x2^2 - 2h(x1 - x2) + y1^2 - y2^2 - 2k(y1 - y2) = 0 ->
+ // h(x1 - x2) + k(y1 - y2) = (-x1^2 + x2^2 - y1^2 + y2^2) / -2
+ // Doing the same with equations 1 and 3, we get the second linear equation
+ // h(x1 - x3) + k(y1 - y3) = (-x1^2 + x3^2 - y1^2 + y3^2) / -2
+ // Now, we can solve for their intersection and find the center
+ const auto l =
+ StdFormLine{points[0].x - points[1].x, points[0].y - points[1].y,
+ (-std::pow(points[0].x, 2) + std::pow(points[1].x, 2) -
+ std::pow(points[0].y, 2) + std::pow(points[1].y, 2)) /
+ -2.0};
+ const auto m =
+ StdFormLine{points[0].x - points[2].x, points[0].y - points[2].y,
+ (-std::pow(points[0].x, 2) + std::pow(points[2].x, 2) -
+ std::pow(points[0].y, 2) + std::pow(points[2].y, 2)) /
+ -2.0};
+ const auto center = l.Intersection(m);
+
+ std::optional<Circle> circle = std::nullopt;
+ if (center) {
+ // Now find the radius
+ const double radius = cv::norm(points[0] - *center);
+ circle = Circle{*center, radius};
+ }
+ return circle;
+ }
+
+ inline double DistanceTo(cv::Point2d p) const {
+ const auto p_prime = TranslateToOrigin(p);
+ // Now, the distance is simply the difference between distance from the
+ // origin to p' and the radius.
+ return std::abs(cv::norm(p_prime) - radius);
+ }
+
+ inline double AngleOf(cv::Point2d p) const {
+ auto p_prime = TranslateToOrigin(p);
+ // Flip the y because y values go downwards.
+ p_prime.y *= -1;
+ return std::atan2(p_prime.y, p_prime.x);
+ }
+
+ // Expects all angles to be from 0 to 2pi
+ // TODO(milind): handle wrapping
+ static inline bool AngleInRange(double theta, double theta_min,
+ double theta_max) {
+ return (
+ (theta >= theta_min && theta <= theta_max) ||
+ (theta_min > theta_max && (theta >= theta_min || theta <= theta_max)));
+ }
+
+ inline bool InAngleRange(cv::Point2d p, double theta_min,
+ double theta_max) const {
+ return AngleInRange(AngleOf(p), theta_min, theta_max);
+ }
+
+ private:
+ // Translate the point on the circle
+ // as if the circle's center is the origin (0,0)
+ inline cv::Point2d TranslateToOrigin(cv::Point2d p) const {
+ return cv::Point2d(p.x - center.x, p.y - center.y);
+ }
+};
+
+} // namespace y2022::vision
diff --git a/y2022/vision/geometry_test.cc b/y2022/vision/geometry_test.cc
new file mode 100644
index 0000000..0a5a759
--- /dev/null
+++ b/y2022/vision/geometry_test.cc
@@ -0,0 +1,111 @@
+#include "y2022/vision/geometry.h"
+
+#include <cmath>
+
+#include "aos/util/math.h"
+#include "glog/logging.h"
+#include "gtest/gtest.h"
+
+namespace y2022::vision::testing {
+
+TEST(GeometryTest, SlopeInterceptLine) {
+ // Test a normal line
+ {
+ SlopeInterceptLine l({2.0, 3.0}, {4.0, 2.0});
+ EXPECT_DOUBLE_EQ(l.m, -0.5);
+ EXPECT_DOUBLE_EQ(l.b, 4.0);
+ EXPECT_DOUBLE_EQ(l(5), 1.5);
+ }
+ // Test a horizontal line
+ {
+ SlopeInterceptLine l({2.0, 3.0}, {4.0, 3.0});
+ EXPECT_DOUBLE_EQ(l.m, 0.0);
+ EXPECT_DOUBLE_EQ(l.b, 3.0);
+ EXPECT_DOUBLE_EQ(l(1000.0), 3.0);
+ }
+ // Test duplicate points
+ {
+ SlopeInterceptLine l({2.0, 3.0}, {2.0, 3.0});
+ EXPECT_DOUBLE_EQ(l.m, 0.0);
+ EXPECT_DOUBLE_EQ(l.b, 3.0);
+ EXPECT_DOUBLE_EQ(l(1000.0), 3.0);
+ }
+ // Test infinite slope
+ {
+ EXPECT_DEATH(SlopeInterceptLine({2.0, 3.0}, {2.0, 5.0}),
+ "(.*)infinite slope(.*)");
+ }
+}
+
+TEST(GeometryTest, StdFormLine) {
+ // Test the intersection of normal lines
+ {
+ StdFormLine l{3.0, 2.0, 2.3};
+ StdFormLine m{-2.0, 1.2, -0.3};
+ const cv::Point2d kIntersection = {42.0 / 95.0, 37.0 / 76.0};
+ EXPECT_EQ(*l.Intersection(m), kIntersection);
+ EXPECT_EQ(*m.Intersection(l), kIntersection);
+ }
+ // Test the intersection of parallel lines
+ {
+ StdFormLine l{-3.0, 2.0, -3.7};
+ StdFormLine m{-6.0, 4.0, 0.1};
+ EXPECT_EQ(l.Intersection(m), std::nullopt);
+ EXPECT_EQ(m.Intersection(l), std::nullopt);
+ }
+ // Test the intersection of duplicate lines
+ {
+ StdFormLine l{6.0, -8.0, 0.23};
+ StdFormLine m{6.0, -8.0, 0.23};
+ EXPECT_EQ(l.Intersection(m), std::nullopt);
+ EXPECT_EQ(m.Intersection(l), std::nullopt);
+ }
+}
+
+TEST(GeometryTest, Circle) {
+ // Test fitting a normal circle
+ {
+ auto c = Circle::Fit({{-6.0, 3.2}, {-3.0, 2.0}, {-9.3, 1.4}});
+ EXPECT_TRUE(c.has_value());
+ EXPECT_NEAR(c->center.x, -5.901, 1e-3);
+ EXPECT_NEAR(c->center.y, -0.905, 1e-3);
+ EXPECT_NEAR(c->radius, 4.106, 1e-3);
+
+ // Coordinate systems flipped because of image
+ const cv::Point2d kPoint = {c->center.x - c->radius * std::sqrt(3.0) / 2.0,
+ c->center.y - c->radius / 2.0};
+ EXPECT_NEAR(c->AngleOf(kPoint), 5.0 * M_PI / 6.0, 1e-5);
+ EXPECT_TRUE(c->InAngleRange(kPoint, 4.0 * M_PI / 6.0, M_PI));
+ EXPECT_FALSE(c->InAngleRange(kPoint, 0, 2.0 * M_PI / 6.0));
+ EXPECT_EQ(c->DistanceTo(kPoint), 0.0);
+
+ const cv::Point2d kZeroPoint = {c->center.x + c->radius, c->center.y};
+ EXPECT_NEAR(c->AngleOf(kZeroPoint), 0.0, 1e-5);
+ EXPECT_TRUE(c->InAngleRange(kZeroPoint, (2.0 * M_PI) - 0.1, 0.1));
+ EXPECT_EQ(c->DistanceTo(kZeroPoint), 0.0);
+
+ // Test the distance to another point
+ const cv::Point2d kDoubleDistPoint = {
+ c->center.x - (c->radius * 2.0) * std::sqrt(3.0) / 2.0,
+ c->center.y - (c->radius * 2.0) / 2.0};
+ EXPECT_DOUBLE_EQ(c->DistanceTo(kDoubleDistPoint), c->radius);
+
+ // Distance to center should be radius
+ EXPECT_DOUBLE_EQ(c->DistanceTo(c->center), c->radius);
+ }
+ // Test fitting an invalid circle (duplicate points)
+ {
+ auto c = Circle::Fit({{-6.0, 3.2}, {-3.0, 2.0}, {-6.0, 3.2}});
+ EXPECT_FALSE(c.has_value());
+ }
+ // Test if angles are in ranges
+ {
+ EXPECT_TRUE(Circle::AngleInRange(0.5, 0.4, 0.6));
+ EXPECT_TRUE(Circle::AngleInRange(0, (2.0 * M_PI) - 0.2, 0.2));
+ EXPECT_FALSE(
+ Circle::AngleInRange(0, (2.0 * M_PI) - 0.2, (2.0 * M_PI) - 0.1));
+ EXPECT_TRUE(Circle::AngleInRange(0.5, (2.0 * M_PI) - 0.1, 0.6));
+ }
+}
+
+} // namespace y2022::vision::testing
diff --git a/y2022/vision/image_decimator.cc b/y2022/vision/image_decimator.cc
new file mode 100644
index 0000000..5fda423
--- /dev/null
+++ b/y2022/vision/image_decimator.cc
@@ -0,0 +1,52 @@
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "aos/flatbuffers.h"
+#include "frc971/vision/vision_generated.h"
+
+DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
+
+namespace frc971::vision {
+// Reads images from /camera and resends them in /camera/decimated at a fixed
+// rate (1 Hz, in this case).
+class ImageDecimator {
+ public:
+ ImageDecimator(aos::EventLoop *event_loop)
+ : slow_image_sender_(
+ event_loop->MakeSender<CameraImage>("/camera/decimated")),
+ image_fetcher_(event_loop->MakeFetcher<CameraImage>("/camera")) {
+ aos::TimerHandler *timer =
+ event_loop->AddTimer(
+ [this]() {
+ if (image_fetcher_.Fetch()) {
+ const aos::FlatbufferSpan<CameraImage> image(
+ {reinterpret_cast<const uint8_t *>(
+ image_fetcher_.context().data),
+ image_fetcher_.context().size});
+ slow_image_sender_.CheckOk(slow_image_sender_.Send(image));
+ }
+ });
+ event_loop->OnRun([event_loop, timer]() {
+ timer->Setup(event_loop->monotonic_now(),
+ std::chrono::milliseconds(1000));
+ });
+ }
+
+ private:
+ aos::Sender<CameraImage> slow_image_sender_;
+ aos::Fetcher<CameraImage> image_fetcher_;
+};
+}
+
+int main(int argc, char *argv[]) {
+ aos::InitGoogle(&argc, &argv);
+
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig(FLAGS_config);
+
+ aos::ShmEventLoop event_loop(&config.message());
+ frc971::vision::ImageDecimator decimator(&event_loop);
+
+ event_loop.Run();
+
+ return 0;
+}
diff --git a/y2022/vision/target_estimate.fbs b/y2022/vision/target_estimate.fbs
index 42a012d..3ba10f03 100644
--- a/y2022/vision/target_estimate.fbs
+++ b/y2022/vision/target_estimate.fbs
@@ -7,6 +7,11 @@
y:int (id: 1);
}
+struct Size {
+ width:int (id: 0);
+ height:int (id: 1);
+}
+
table Blob {
points:[Point] (id: 0);
}
@@ -14,6 +19,7 @@
// Statistics for each blob used for filtering
table BlobStatsFbs {
centroid:Point (id: 0);
+ size:Size (id: 4);
aspect_ratio:double (id: 1);
area:double (id: 2);
num_points:uint64 (id: 3);
@@ -27,8 +33,8 @@
unfiltered_blobs:[Blob] (id: 1);
// Stats on the blobs
blob_stats:[BlobStatsFbs] (id: 2);
- // Centroids of filtered blobs
- filtered_centroids:[Point] (id: 4);
+ // Stats of filtered blobs
+ filtered_stats:[BlobStatsFbs] (id: 4);
// Average centroid of the filtered blobs
centroid:Point (id: 3);
}
@@ -52,7 +58,8 @@
angle_to_camera:double (id: 3);
// Rotation of the camera in the hub's reference frame
rotation_camera_hub:Rotation (id: 4);
- // Confidence in the estimate from 0 to 1, based on the final solver cost.
+ // Confidence in the estimate from 0 to 1,
+ // based on the final deviation between projected points and actual blobs.
// Good estimates currently have confidences of around 0.9 or greater.
confidence:double (id: 7);
diff --git a/y2022/vision/target_estimator.cc b/y2022/vision/target_estimator.cc
index 6773631..b495b23 100644
--- a/y2022/vision/target_estimator.cc
+++ b/y2022/vision/target_estimator.cc
@@ -4,13 +4,15 @@
#include "aos/time/time.h"
#include "ceres/ceres.h"
#include "frc971/control_loops/quaternion_utils.h"
+#include "geometry.h"
#include "opencv2/core/core.hpp"
#include "opencv2/core/eigen.hpp"
#include "opencv2/features2d.hpp"
#include "opencv2/highgui/highgui.hpp"
#include "opencv2/imgproc.hpp"
+#include "y2022/constants.h"
-DEFINE_bool(freeze_roll, true, "If true, don't solve for roll");
+DEFINE_bool(freeze_roll, false, "If true, don't solve for roll");
DEFINE_bool(freeze_pitch, false, "If true, don't solve for pitch");
DEFINE_bool(freeze_yaw, false, "If true, don't solve for yaw");
DEFINE_bool(freeze_camera_height, true,
@@ -25,9 +27,19 @@
namespace y2022::vision {
-std::vector<cv::Point3d> TargetEstimator::ComputeTapePoints() {
+namespace {
+
+constexpr size_t kNumPiecesOfTape = 16;
+// Width and height of a piece of reflective tape
+constexpr double kTapePieceWidth = 0.13;
+constexpr double kTapePieceHeight = 0.05;
+// Height of the center of the tape (m)
+constexpr double kTapeCenterHeight = 2.58 + (kTapePieceHeight / 2);
+// Horizontal distance from tape to center of hub (m)
+constexpr double kUpperHubRadius = 1.22 / 2;
+
+std::vector<cv::Point3d> ComputeTapePoints() {
std::vector<cv::Point3d> tape_points;
- tape_points.reserve(kNumPiecesOfTape);
constexpr size_t kNumVisiblePiecesOfTape = 5;
for (size_t i = 0; i < kNumVisiblePiecesOfTape; i++) {
@@ -38,25 +50,63 @@
// The polar angle is a multiple of the angle between tape centers
double theta = theta_index * ((2.0 * M_PI) / kNumPiecesOfTape);
tape_points.emplace_back(kUpperHubRadius * std::cos(theta),
- kUpperHubRadius * std::sin(theta), kTapeHeight);
+ kUpperHubRadius * std::sin(theta),
+ kTapeCenterHeight);
}
return tape_points;
}
+std::array<cv::Point3d, 4> ComputeMiddleTapePiecePoints() {
+ std::array<cv::Point3d, 4> tape_piece_points;
+
+ // Angle that each piece of tape occupies on the hub
+ constexpr double kTapePieceAngle =
+ (kTapePieceWidth / (2.0 * M_PI * kUpperHubRadius)) * (2.0 * M_PI);
+
+ constexpr double kThetaTapeLeft = -kTapePieceAngle / 2.0;
+ constexpr double kThetaTapeRight = kTapePieceAngle / 2.0;
+
+ constexpr double kTapeTopHeight =
+ kTapeCenterHeight + (kTapePieceHeight / 2.0);
+ constexpr double kTapeBottomHeight =
+ kTapeCenterHeight - (kTapePieceHeight / 2.0);
+
+ tape_piece_points[0] = {kUpperHubRadius * std::cos(kThetaTapeLeft),
+ kUpperHubRadius * std::sin(kThetaTapeLeft),
+ kTapeTopHeight};
+ tape_piece_points[1] = {kUpperHubRadius * std::cos(kThetaTapeRight),
+ kUpperHubRadius * std::sin(kThetaTapeRight),
+ kTapeTopHeight};
+
+ tape_piece_points[2] = {kUpperHubRadius * std::cos(kThetaTapeRight),
+ kUpperHubRadius * std::sin(kThetaTapeRight),
+ kTapeBottomHeight};
+ tape_piece_points[3] = {kUpperHubRadius * std::cos(kThetaTapeLeft),
+ kUpperHubRadius * std::sin(kThetaTapeLeft),
+ kTapeBottomHeight};
+
+ return tape_piece_points;
+}
+
+} // namespace
+
const std::vector<cv::Point3d> TargetEstimator::kTapePoints =
ComputeTapePoints();
+const std::array<cv::Point3d, 4> TargetEstimator::kMiddleTapePiecePoints =
+ ComputeMiddleTapePiecePoints();
TargetEstimator::TargetEstimator(cv::Mat intrinsics, cv::Mat extrinsics)
- : centroids_(),
+ : blob_stats_(),
image_(std::nullopt),
roll_(0.0),
pitch_(0.0),
yaw_(M_PI),
distance_(3.0),
angle_to_camera_(0.0),
- // TODO(milind): add IMU height
- camera_height_(extrinsics.at<double>(2, 3)) {
+ // Seed camera height
+ camera_height_(extrinsics.at<double>(2, 3) +
+ constants::Values::kImuHeight()) {
cv::cv2eigen(intrinsics, intrinsics_);
cv::cv2eigen(extrinsics, extrinsics_);
}
@@ -65,47 +115,94 @@
void SetBoundsOrFreeze(double *param, bool freeze, double min, double max,
ceres::Problem *problem) {
if (freeze) {
- problem->SetParameterization(
- param, new ceres::SubsetParameterization(1, std::vector<int>{0}));
+ problem->SetParameterBlockConstant(param);
} else {
problem->SetParameterLowerBound(param, 0, min);
problem->SetParameterUpperBound(param, 0, max);
}
}
+
+// With X, Y, Z being hub axes and x, y, z being camera axes,
+// x = -Y, y = -Z, z = X
+const Eigen::Matrix3d kHubToCameraAxes =
+ (Eigen::Matrix3d() << 0.0, -1.0, 0.0, 0.0, 0.0, -1.0, 1.0, 0.0, 0.0)
+ .finished();
+
} // namespace
-void TargetEstimator::Solve(const std::vector<cv::Point> ¢roids,
- std::optional<cv::Mat> image) {
+void TargetEstimator::Solve(
+ const std::vector<BlobDetector::BlobStats> &blob_stats,
+ std::optional<cv::Mat> image) {
auto start = aos::monotonic_clock::now();
- centroids_ = centroids;
+ blob_stats_ = blob_stats;
image_ = image;
+ // Do nothing if no blobs were detected
+ if (blob_stats_.size() == 0) {
+ confidence_ = 0.0;
+ return;
+ }
+
+ CHECK_GE(blob_stats_.size(), 3) << "Expected at least 3 blobs";
+
+ const auto circle =
+ Circle::Fit({blob_stats_[0].centroid, blob_stats_[1].centroid,
+ blob_stats_[2].centroid});
+ CHECK(circle.has_value());
+
+ // Find the middle blob, which is the one with the angle closest to the
+ // average
+ double theta_avg = 0.0;
+ for (const auto &stats : blob_stats_) {
+ theta_avg += circle->AngleOf(stats.centroid);
+ }
+ theta_avg /= blob_stats_.size();
+
+ double min_diff = std::numeric_limits<double>::infinity();
+ for (auto it = blob_stats_.begin(); it < blob_stats_.end(); it++) {
+ const double diff = std::abs(circle->AngleOf(it->centroid) - theta_avg);
+ if (diff < min_diff) {
+ min_diff = diff;
+ middle_blob_index_ = it - blob_stats_.begin();
+ }
+ }
+
ceres::Problem problem;
+ // x and y differences between projected centroids and blob centroids, as well
+ // as width and height differences between middle projected piece and the
+ // detected blob
+ const size_t num_residuals = (blob_stats_.size() * 2) + 2;
+
// Set up the only cost function (also known as residual). This uses
// auto-differentiation to obtain the derivative (jacobian).
ceres::CostFunction *cost_function =
new ceres::AutoDiffCostFunction<TargetEstimator, ceres::DYNAMIC, 1, 1, 1,
- 1, 1, 1>(this, centroids_.size() * 2,
+ 1, 1, 1>(this, num_residuals,
ceres::DO_NOT_TAKE_OWNERSHIP);
// TODO(milind): add loss function when we get more noisy data
problem.AddResidualBlock(cost_function, nullptr, &roll_, &pitch_, &yaw_,
&distance_, &angle_to_camera_, &camera_height_);
- // TODO(milind): seed values at localizer output, and constrain to be close to
- // that.
+ // Compute the estimated rotation of the camera using the robot rotation.
+ const Eigen::Vector3d ypr_extrinsics =
+ (Eigen::Affine3d(extrinsics_).rotation() * kHubToCameraAxes)
+ .eulerAngles(2, 1, 0);
+ // TODO(milind): seed with localizer output as well
+ const double roll_seed = ypr_extrinsics.z();
+ const double pitch_seed = ypr_extrinsics.y();
- // Constrain the rotation, otherwise there can be multiple solutions.
- // There shouldn't be too much roll or pitch
- constexpr double kMaxRoll = 0.1;
- SetBoundsOrFreeze(&roll_, FLAGS_freeze_roll, -kMaxRoll, kMaxRoll, &problem);
+ // Constrain the rotation to be around the localizer's, otherwise there can be
+ // multiple solutions. There shouldn't be too much roll or pitch
+ constexpr double kMaxRollDelta = 0.1;
+ SetBoundsOrFreeze(&roll_, FLAGS_freeze_roll, roll_seed - kMaxRollDelta,
+ roll_seed + kMaxRollDelta, &problem);
- constexpr double kPitch = -35.0 * M_PI / 180.0;
constexpr double kMaxPitchDelta = 0.15;
- SetBoundsOrFreeze(&pitch_, FLAGS_freeze_pitch, kPitch - kMaxPitchDelta,
- kPitch + kMaxPitchDelta, &problem);
+ SetBoundsOrFreeze(&pitch_, FLAGS_freeze_pitch, pitch_seed - kMaxPitchDelta,
+ pitch_seed + kMaxPitchDelta, &problem);
// Constrain the yaw to where the target would be visible
constexpr double kMaxYawDelta = M_PI / 4.0;
SetBoundsOrFreeze(&yaw_, FLAGS_freeze_yaw, M_PI - kMaxYawDelta,
@@ -136,28 +233,33 @@
ceres::Solve(options, &problem, &summary);
auto end = aos::monotonic_clock::now();
- LOG(INFO) << "Target estimation elapsed time: "
- << std::chrono::duration<double, std::milli>(end - start).count()
- << " ms";
+ VLOG(1) << "Target estimation elapsed time: "
+ << std::chrono::duration<double, std::milli>(end - start).count()
+ << " ms";
- // Use a sigmoid to convert the final cost into a confidence for the
- // localizer. Fit a sigmoid to the points of (0, 1) and two other reasonable
- // residual-confidence combinations using
- // https://www.desmos.com/calculator/jj7p8zk0w2
- constexpr double kSigmoidCapacity = 1.206;
- // Stretch the sigmoid out correctly.
- // Currently, good estimates have final costs of around 1 to 2 pixels.
- constexpr double kSigmoidScalar = 0.2061;
- constexpr double kSigmoidGrowthRate = -0.1342;
- if (centroids_.size() > 0) {
- confidence_ = kSigmoidCapacity /
- (1.0 + kSigmoidScalar * std::exp(-kSigmoidGrowthRate *
- summary.final_cost));
- } else {
- // If we detected no blobs, the confidence should be zero and not depending
- // on the final cost, which would be 0.
- confidence_ = 0.0;
+ // For computing the confidence, find the standard deviation in pixels
+ std::vector<double> residual(num_residuals);
+ (*this)(&roll_, &pitch_, &yaw_, &distance_, &angle_to_camera_,
+ &camera_height_, residual.data());
+ double std_dev = 0.0;
+ for (auto it = residual.begin(); it < residual.end() - 2; it++) {
+ std_dev += std::pow(*it, 2);
}
+ std_dev /= num_residuals - 2;
+ std_dev = std::sqrt(std_dev);
+
+ // Use a sigmoid to convert the deviation into a confidence for the
+ // localizer. Fit a sigmoid to the points of (0, 1) and two other
+ // reasonable deviation-confidence combinations using
+ // https://www.desmos.com/calculator/try0pgx1qw
+ constexpr double kSigmoidCapacity = 1.045;
+ // Stretch the sigmoid out correctly.
+ // Currently, good estimates have deviations of around 2 pixels.
+ constexpr double kSigmoidScalar = 0.04452;
+ constexpr double kSigmoidGrowthRate = -0.4021;
+ confidence_ =
+ kSigmoidCapacity /
+ (1.0 + kSigmoidScalar * std::exp(-kSigmoidGrowthRate * std_dev));
if (FLAGS_solver_output) {
LOG(INFO) << summary.FullReport();
@@ -169,6 +271,7 @@
LOG(INFO) << "angle to camera (polar): " << angle_to_camera_;
LOG(INFO) << "distance (polar): " << distance_;
LOG(INFO) << "camera height: " << camera_height_;
+ LOG(INFO) << "standard deviation (px): " << std_dev;
LOG(INFO) << "confidence: " << confidence_;
}
}
@@ -206,32 +309,26 @@
*distance * ceres::sin(*theta), *camera_height);
Affine3s H_camera_hub = Eigen::Translation<S, 3>(T_camera_hub) * R_camera_hub;
+ Affine3s H_hub_camera = H_camera_hub.inverse();
std::vector<cv::Point_<S>> tape_points_proj;
for (cv::Point3d tape_point_hub : kTapePoints) {
- Vector3s tape_point_hub_eigen(S(tape_point_hub.x), S(tape_point_hub.y),
- S(tape_point_hub.z));
-
- // With X, Y, Z being world axes and x, y, z being camera axes,
- // x = Y, y = Z, z = -X
- static const Eigen::Matrix3d kCameraAxisConversion =
- (Eigen::Matrix3d() << 0.0, 1.0, 0.0, 0.0, 0.0, 1.0, -1.0, 0.0, 0.0)
- .finished();
- // Project the 3d tape point onto the image using the transformation and
- // intrinsics
- Vector3s tape_point_proj =
- intrinsics_ * (kCameraAxisConversion *
- (H_camera_hub.inverse() * tape_point_hub_eigen));
-
- // Normalize the projected point
- tape_points_proj.emplace_back(tape_point_proj.x() / tape_point_proj.z(),
- tape_point_proj.y() / tape_point_proj.z());
- VLOG(1) << "Projected tape point: "
+ tape_points_proj.emplace_back(ProjectToImage(tape_point_hub, H_hub_camera));
+ VLOG(2) << "Projected tape point: "
<< ScalarPointToDouble(
tape_points_proj[tape_points_proj.size() - 1]);
}
- for (size_t i = 0; i < centroids_.size(); i++) {
+ // Find the rectangle bounding the projected piece of tape
+ std::array<cv::Point_<S>, 4> middle_tape_piece_points_proj;
+ for (auto tape_piece_it = kMiddleTapePiecePoints.begin();
+ tape_piece_it < kMiddleTapePiecePoints.end(); tape_piece_it++) {
+ middle_tape_piece_points_proj[tape_piece_it -
+ kMiddleTapePiecePoints.begin()] =
+ ProjectToImage(*tape_piece_it, H_hub_camera);
+ }
+
+ for (size_t i = 0; i < blob_stats_.size(); i++) {
const auto distance = DistanceFromTape(i, tape_points_proj);
// Set the residual to the (x, y) distance of the centroid from the
// nearest projected piece of tape
@@ -239,6 +336,31 @@
residual[(i * 2) + 1] = distance.y;
}
+ // Penalize based on the difference between the size of the projected piece of
+ // tape and that of the detected blobs. Use the squared size to avoid taking a
+ // norm, which ceres can't handle well
+ const S middle_tape_piece_width_squared =
+ ceres::pow(middle_tape_piece_points_proj[2].x -
+ middle_tape_piece_points_proj[3].x,
+ 2) +
+ ceres::pow(middle_tape_piece_points_proj[2].y -
+ middle_tape_piece_points_proj[3].y,
+ 2);
+ const S middle_tape_piece_height_squared =
+ ceres::pow(middle_tape_piece_points_proj[1].x -
+ middle_tape_piece_points_proj[2].x,
+ 2) +
+ ceres::pow(middle_tape_piece_points_proj[1].y -
+ middle_tape_piece_points_proj[2].y,
+ 2);
+
+ residual[blob_stats_.size() * 2] =
+ middle_tape_piece_width_squared -
+ std::pow(blob_stats_[middle_blob_index_].size.width, 2);
+ residual[(blob_stats_.size() * 2) + 1] =
+ middle_tape_piece_height_squared -
+ std::pow(blob_stats_[middle_blob_index_].size.height, 2);
+
if (image_.has_value()) {
// Draw the current stage of the solving
cv::Mat image = image_->clone();
@@ -258,6 +380,24 @@
return true;
}
+template <typename S>
+cv::Point_<S> TargetEstimator::ProjectToImage(
+ cv::Point3d tape_point_hub,
+ Eigen::Transform<S, 3, Eigen::Affine> &H_hub_camera) const {
+ using Vector3s = Eigen::Matrix<S, 3, 1>;
+
+ const Vector3s tape_point_hub_eigen =
+ Vector3s(S(tape_point_hub.x), S(tape_point_hub.y), S(tape_point_hub.z));
+ // Project the 3d tape point onto the image using the transformation and
+ // intrinsics
+ const Vector3s tape_point_proj =
+ intrinsics_ * (kHubToCameraAxes * (H_hub_camera * tape_point_hub_eigen));
+
+ // Normalize the projected point
+ return {tape_point_proj.x() / tape_point_proj.z(),
+ tape_point_proj.y() / tape_point_proj.z()};
+}
+
namespace {
template <typename S>
cv::Point_<S> Distance(cv::Point p, cv::Point_<S> q) {
@@ -273,35 +413,20 @@
template <typename S>
cv::Point_<S> TargetEstimator::DistanceFromTape(
- size_t centroid_index,
- const std::vector<cv::Point_<S>> &tape_points) const {
- // Figure out the middle index in the tape points
- size_t middle_index = centroids_.size() / 2;
- if (centroids_.size() % 2 == 0) {
- // There are two possible middles in this case. Figure out which one fits
- // the current better
- const auto tape_middle = tape_points[tape_points.size() / 2];
- const auto middle_distance_1 =
- Distance(centroids_[(centroids_.size() / 2) - 1], tape_middle);
- const auto middle_distance_2 =
- Distance(centroids_[centroids_.size() / 2], tape_middle);
- if (Less(middle_distance_1, middle_distance_2)) {
- middle_index--;
- }
- }
-
+ size_t blob_index, const std::vector<cv::Point_<S>> &tape_points) const {
auto distance = cv::Point_<S>(std::numeric_limits<S>::infinity(),
std::numeric_limits<S>::infinity());
- if (centroid_index == middle_index) {
- // Fix the middle centroid so the solver can't go too far off
- distance =
- Distance(centroids_[middle_index], tape_points[tape_points.size() / 2]);
+ if (blob_index == middle_blob_index_) {
+ // Fix the middle blob so the solver can't go too far off
+ distance = Distance(blob_stats_[middle_blob_index_].centroid,
+ tape_points[tape_points.size() / 2]);
} else {
- // Give the other centroids some freedom in case some are split into pieces
- for (auto tape_point : tape_points) {
+ // Give the other blob_stats some freedom in case some are split into pieces
+ for (auto it = tape_points.begin(); it < tape_points.end(); it++) {
const auto current_distance =
- Distance(centroids_[centroid_index], tape_point);
- if (Less(current_distance, distance)) {
+ Distance(blob_stats_[blob_index].centroid, *it);
+ if ((it != tape_points.begin() + (tape_points.size() / 2)) &&
+ Less(current_distance, distance)) {
distance = current_distance;
}
}
@@ -315,11 +440,11 @@
double angle_to_camera, double roll, double pitch,
double yaw, double confidence, cv::Mat view_image) {
constexpr int kTextX = 10;
- int text_y = 250;
- constexpr int kTextSpacing = 35;
+ int text_y = 0;
+ constexpr int kTextSpacing = 25;
const auto kTextColor = cv::Scalar(0, 255, 255);
- constexpr double kFontScale = 1.0;
+ constexpr double kFontScale = 0.6;
cv::putText(view_image, absl::StrFormat("Distance: %.3f", distance),
cv::Point(kTextX, text_y += kTextSpacing),
diff --git a/y2022/vision/target_estimator.h b/y2022/vision/target_estimator.h
index 5d338c4..b509a2e 100644
--- a/y2022/vision/target_estimator.h
+++ b/y2022/vision/target_estimator.h
@@ -7,22 +7,21 @@
#include "Eigen/Geometry"
#include "opencv2/core/types.hpp"
#include "opencv2/imgproc.hpp"
+#include "y2022/vision/blob_detector.h"
#include "y2022/vision/target_estimate_generated.h"
namespace y2022::vision {
-// Class to estimate the polar coordinates and rotation from the camera to the
+// Class to estimate the distance and rotation of the camera from the
// target.
class TargetEstimator {
public:
TargetEstimator(cv::Mat intrinsics, cv::Mat extrinsics);
// Runs the solver to estimate the target
- // centroids must be in sorted order from left to right on the circle.
- // TODO(milind): seems safer to sort them here.
// If image != std::nullopt, the solver's progress will be displayed
// graphically.
- void Solve(const std::vector<cv::Point> ¢roids,
+ void Solve(const std::vector<BlobDetector::BlobStats> &blob_stats,
std::optional<cv::Mat> image);
// Cost function for the solver.
@@ -54,22 +53,24 @@
void DrawEstimate(cv::Mat view_image) const;
private:
- // Height of the center of the tape (m)
- static constexpr double kTapeHeight = 2.58 + (0.05 / 2);
- // Horizontal distance from tape to center of hub (m)
- static constexpr double kUpperHubRadius = 1.22 / 2;
- static constexpr size_t kNumPiecesOfTape = 16;
-
// 3d points of the visible pieces of tape in the hub's frame
static const std::vector<cv::Point3d> kTapePoints;
- static std::vector<cv::Point3d> ComputeTapePoints();
+ // 3d outer points of the middle piece of tape in the hub's frame,
+ // clockwise around the rectangle
+ static const std::array<cv::Point3d, 4> kMiddleTapePiecePoints;
+
+ template <typename S>
+ cv::Point_<S> ProjectToImage(
+ cv::Point3d tape_point_hub,
+ Eigen::Transform<S, 3, Eigen::Affine> &H_hub_camera) const;
template <typename S>
cv::Point_<S> DistanceFromTape(
size_t centroid_index,
const std::vector<cv::Point_<S>> &tape_points) const;
- std::vector<cv::Point> centroids_;
+ std::vector<BlobDetector::BlobStats> blob_stats_;
+ size_t middle_blob_index_;
std::optional<cv::Mat> image_;
Eigen::Matrix3d intrinsics_;
diff --git a/y2022/vision/viewer.cc b/y2022/vision/viewer.cc
index e20f433..f847dbd 100644
--- a/y2022/vision/viewer.cc
+++ b/y2022/vision/viewer.cc
@@ -10,6 +10,7 @@
#include "aos/time/time.h"
#include "frc971/vision/vision_generated.h"
#include "y2022/vision/blob_detector.h"
+#include "y2022/vision/calibration_data.h"
#include "y2022/vision/target_estimate_generated.h"
#include "y2022/vision/target_estimator.h"
@@ -18,6 +19,11 @@
DEFINE_string(channel, "/camera", "Channel name for the image.");
DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
DEFINE_string(png_dir, "", "Path to a set of images to display.");
+DEFINE_string(calibration_node, "",
+ "If reading locally, use the calibration for this node");
+DEFINE_int32(
+ calibration_team_number, 971,
+ "If reading locally, use the calibration for a node with this team number");
DEFINE_uint64(skip, 0,
"Number of images to skip if doing local reading (png_dir set).");
DEFINE_bool(show_features, true, "Show the blobs.");
@@ -44,9 +50,12 @@
}
std::vector<std::vector<cv::Point>> FbsToCvBlobs(
- const flatbuffers::Vector<flatbuffers::Offset<Blob>> &blobs_fbs) {
+ const flatbuffers::Vector<flatbuffers::Offset<Blob>> *blobs_fbs) {
+ if (blobs_fbs == nullptr) {
+ return {};
+ }
std::vector<std::vector<cv::Point>> blobs;
- for (const auto blob : blobs_fbs) {
+ for (const auto blob : *blobs_fbs) {
blobs.emplace_back(FbsToCvPoints(*blob->points()));
}
return blobs;
@@ -58,8 +67,9 @@
std::vector<BlobDetector::BlobStats> blob_stats;
for (const auto stats_fbs : blob_stats_fbs) {
cv::Point centroid{stats_fbs->centroid()->x(), stats_fbs->centroid()->y()};
+ cv::Size size{stats_fbs->size()->width(), stats_fbs->size()->height()};
blob_stats.emplace_back(BlobDetector::BlobStats{
- centroid, stats_fbs->aspect_ratio(), stats_fbs->area(),
+ centroid, size, stats_fbs->aspect_ratio(), stats_fbs->area(),
static_cast<size_t>(stats_fbs->num_points())});
}
return blob_stats;
@@ -79,10 +89,10 @@
// Store the TargetEstimate data so we can match timestamp with image
target_est_map[target_timestamp] = BlobDetector::BlobResult{
cv::Mat(),
- FbsToCvBlobs(*target_est->blob_result()->filtered_blobs()),
- FbsToCvBlobs(*target_est->blob_result()->unfiltered_blobs()),
+ FbsToCvBlobs(target_est->blob_result()->filtered_blobs()),
+ FbsToCvBlobs(target_est->blob_result()->unfiltered_blobs()),
FbsToBlobStats(*target_est->blob_result()->blob_stats()),
- FbsToCvPoints(*target_est->blob_result()->filtered_centroids()),
+ FbsToBlobStats(*target_est->blob_result()->filtered_stats()),
cv::Point{target_est->blob_result()->centroid()->x(),
target_est->blob_result()->centroid()->y()}};
// Only keep last 10 matches
@@ -170,22 +180,39 @@
std::vector<cv::String> file_list;
cv::glob(FLAGS_png_dir + "/*.png", file_list, false);
- cv::Mat intrinsics = cv::Mat::zeros(cv::Size(3, 3), CV_64F);
- intrinsics.at<double>(0, 0) = 391.63916;
- intrinsics.at<double>(0, 1) = 0.0;
- intrinsics.at<double>(0, 2) = 312.691162;
- intrinsics.at<double>(1, 0) = 0.0;
- intrinsics.at<double>(1, 1) = 391.535889;
- intrinsics.at<double>(1, 2) = 267.138672;
- intrinsics.at<double>(2, 0) = 0.0;
- intrinsics.at<double>(2, 1) = 0.0;
- intrinsics.at<double>(2, 2) = 1.0;
- cv::Mat extrinsics = cv::Mat::zeros(cv::Size(4, 4), CV_64F);
- extrinsics.at<double>(2, 3) = 0.9398;
+ const aos::FlatbufferSpan<calibration::CalibrationData> calibration_data(
+ CalibrationData());
+
+ const calibration::CameraCalibration *calibration = nullptr;
+ for (const calibration::CameraCalibration *candidate :
+ *calibration_data.message().camera_calibrations()) {
+ if ((candidate->node_name()->string_view() == FLAGS_calibration_node) &&
+ (candidate->team_number() == FLAGS_calibration_team_number)) {
+ calibration = candidate;
+ break;
+ }
+ }
+
+ CHECK(calibration) << "No calibration data found for node \""
+ << FLAGS_calibration_node << "\" with team number "
+ << FLAGS_calibration_team_number;
+
+ auto intrinsics_float = cv::Mat(3, 3, CV_32F,
+ const_cast<void *>(static_cast<const void *>(
+ calibration->intrinsics()->data())));
+ cv::Mat intrinsics;
+ intrinsics_float.convertTo(intrinsics, CV_64F);
+
+ const auto extrinsics_float =
+ cv::Mat(4, 4, CV_32F,
+ const_cast<void *>(static_cast<const void *>(
+ calibration->fixed_extrinsics()->data()->data())));
+ cv::Mat extrinsics;
+ extrinsics_float.convertTo(extrinsics, CV_64F);
TargetEstimator estimator(intrinsics, extrinsics);
- for (auto it = file_list.begin() + FLAGS_skip; it != file_list.end(); it++) {
+ for (auto it = file_list.begin() + FLAGS_skip; it < file_list.end(); it++) {
LOG(INFO) << "Reading file " << *it;
cv::Mat image_mat = cv::imread(it->c_str());
BlobDetector::BlobResult blob_result;
@@ -204,7 +231,7 @@
<< ")";
if (blob_result.filtered_blobs.size() > 0) {
- estimator.Solve(blob_result.filtered_centroids,
+ estimator.Solve(blob_result.filtered_stats,
FLAGS_display_estimation ? std::make_optional(ret_image)
: std::nullopt);
estimator.DrawEstimate(ret_image);
diff --git a/y2022/vision/vision_plotter.ts b/y2022/vision/vision_plotter.ts
new file mode 100644
index 0000000..bc27170
--- /dev/null
+++ b/y2022/vision/vision_plotter.ts
@@ -0,0 +1,114 @@
+import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
+import * as proxy from 'org_frc971/aos/network/www/proxy';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
+
+import Connection = proxy.Connection;
+
+const TIME = AosPlotter.TIME;
+// magenta, yellow, cyan, orange
+const PI_COLORS = [[255, 0, 255], [255, 255, 0], [0, 255, 255], [255, 165, 0]];
+
+export function plotVision(conn: Connection, element: Element): void {
+ const aosPlotter = new AosPlotter(conn);
+
+ const targets = [];
+ for (const pi of ["pi1", "pi2", "pi3", "pi4"]) {
+ targets.push(aosPlotter.addMessageSource(
+ '/' + pi + '/camera', 'y2022.vision.TargetEstimate'));
+ }
+ const localizer = aosPlotter.addMessageSource(
+ '/localizer', 'frc971.controls.LocalizerVisualization');
+ const localizerOutput = aosPlotter.addMessageSource(
+ '/localizer', 'frc971.controls.LocalizerOutput');
+ const superstructureStatus = aosPlotter.addMessageSource(
+ '/superstructure', 'y2022.control_loops.superstructure.Status');
+
+ const rejectionPlot = aosPlotter.addPlot(element);
+ rejectionPlot.plot.getAxisLabels().setTitle("Rejection Reasons");
+ rejectionPlot.plot.getAxisLabels().setXLabel(TIME);
+ rejectionPlot.plot.getAxisLabels().setYLabel("[bool, enum]");
+
+ rejectionPlot.addMessageLine(localizer, ['targets[]', 'accepted'])
+ .setDrawLine(false)
+ .setColor(BLUE);
+ rejectionPlot.addMessageLine(localizer, ['targets[]', 'rejection_reason'])
+ .setDrawLine(false)
+ .setColor(RED);
+
+ const xPlot = aosPlotter.addPlot(element);
+ xPlot.plot.getAxisLabels().setTitle("X Position");
+ xPlot.plot.getAxisLabels().setXLabel(TIME);
+ xPlot.plot.getAxisLabels().setYLabel("[m]");
+
+ xPlot.addMessageLine(localizer, ['targets[]', 'implied_robot_x'])
+ .setDrawLine(false)
+ .setColor(RED);
+ xPlot.addMessageLine(localizerOutput, ['x'])
+ .setDrawLine(false)
+ .setColor(BLUE);
+
+ const yPlot = aosPlotter.addPlot(element);
+ yPlot.plot.getAxisLabels().setTitle("X Position");
+ yPlot.plot.getAxisLabels().setXLabel(TIME);
+ yPlot.plot.getAxisLabels().setYLabel("[m]");
+
+ yPlot.addMessageLine(localizer, ['targets[]', 'implied_robot_y'])
+ .setDrawLine(false)
+ .setColor(RED);
+ yPlot.addMessageLine(localizerOutput, ['y'])
+ .setDrawLine(false)
+ .setColor(BLUE);
+
+ const turretPlot = aosPlotter.addPlot(element);
+ turretPlot.plot.getAxisLabels().setTitle("Turret Position");
+ turretPlot.plot.getAxisLabels().setXLabel(TIME);
+ turretPlot.plot.getAxisLabels().setYLabel("[m]");
+
+ turretPlot.addMessageLine(localizer, ['targets[]', 'implied_turret_goal'])
+ .setDrawLine(false)
+ .setColor(RED);
+ turretPlot.addMessageLine(superstructureStatus, ['turret', 'position'])
+ .setPointSize(0.0)
+ .setColor(BLUE);
+ turretPlot
+ .addMessageLine(
+ superstructureStatus, ['aimer', 'turret_position'])
+ .setPointSize(0.0)
+ .setColor(GREEN);
+
+ const anglePlot = aosPlotter.addPlot(element);
+ anglePlot.plot.getAxisLabels().setTitle("TargetEstimate Angle");
+ anglePlot.plot.getAxisLabels().setXLabel(TIME);
+ anglePlot.plot.getAxisLabels().setYLabel("[rad]");
+
+ for (let ii = 0; ii < targets.length; ++ii) {
+ anglePlot.addMessageLine(targets[ii], ['angle_to_target'])
+ .setDrawLine(false)
+ .setColor(PI_COLORS[ii])
+ .setLabel('pi' + ii);
+ }
+
+ const distancePlot = aosPlotter.addPlot(element);
+ distancePlot.plot.getAxisLabels().setTitle("TargetEstimate Distance");
+ distancePlot.plot.getAxisLabels().setXLabel(TIME);
+ distancePlot.plot.getAxisLabels().setYLabel("[rad]");
+
+ for (let ii = 0; ii < targets.length; ++ii) {
+ distancePlot.addMessageLine(targets[ii], ['distance'])
+ .setDrawLine(false)
+ .setColor(PI_COLORS[ii])
+ .setLabel('pi' + ii);
+ }
+
+ const confidencePlot = aosPlotter.addPlot(element);
+ confidencePlot.plot.getAxisLabels().setTitle("TargetEstimate Confidence");
+ confidencePlot.plot.getAxisLabels().setXLabel(TIME);
+ confidencePlot.plot.getAxisLabels().setYLabel("[rad]");
+
+ for (let ii = 0; ii < targets.length; ++ii) {
+ confidencePlot.addMessageLine(targets[ii], ['confidence'])
+ .setDrawLine(false)
+ .setColor(PI_COLORS[ii])
+ .setLabel('pi' + ii);
+ }
+}
diff --git a/y2022/wpilib_interface.cc b/y2022/wpilib_interface.cc
index 00417f0..69883b4 100644
--- a/y2022/wpilib_interface.cc
+++ b/y2022/wpilib_interface.cc
@@ -186,7 +186,7 @@
CopyPosition(catapult_encoder_, &catapult,
Values::kCatapultEncoderCountsPerRevolution(),
Values::kCatapultEncoderRatio(), catapult_pot_translate,
- true, values_->catapult.potentiometer_offset);
+ false, values_->catapult.potentiometer_offset);
flatbuffers::Offset<frc971::PotAndAbsolutePosition> catapult_offset =
frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &catapult);
@@ -203,19 +203,19 @@
frc971::RelativePositionT flipper_arm_right;
CopyPosition(*flipper_arm_right_potentiometer_, &flipper_arm_right,
- flipper_arms_pot_translate, false,
+ flipper_arms_pot_translate, true,
values_->flipper_arm_right.potentiometer_offset);
// Intake
frc971::PotAndAbsolutePositionT intake_front;
CopyPosition(intake_encoder_front_, &intake_front,
Values::kIntakeEncoderCountsPerRevolution(),
- Values::kIntakeEncoderRatio(), intake_pot_translate, false,
+ Values::kIntakeEncoderRatio(), intake_pot_translate, true,
values_->intake_front.potentiometer_offset);
frc971::PotAndAbsolutePositionT intake_back;
CopyPosition(intake_encoder_back_, &intake_back,
Values::kIntakeEncoderCountsPerRevolution(),
- Values::kIntakeEncoderRatio(), intake_pot_translate, false,
+ Values::kIntakeEncoderRatio(), intake_pot_translate, true,
values_->intake_back.potentiometer_offset);
frc971::PotAndAbsolutePositionT turret;
CopyPosition(turret_encoder_, &turret,
@@ -437,10 +437,6 @@
catapult_falcon_1_ = ::std::move(t);
}
- void set_catapult_falcon_2(::std::unique_ptr<::frc::TalonFX> t) {
- catapult_falcon_2_ = ::std::move(t);
- }
-
void set_intake_falcon_front(::std::unique_ptr<frc::TalonFX> t) {
intake_falcon_front_ = ::std::move(t);
}
@@ -487,8 +483,12 @@
return flipper_arms_falcon_;
}
- void set_transfer_roller_victor(::std::unique_ptr<::frc::VictorSP> t) {
- transfer_roller_victor_ = ::std::move(t);
+ void set_transfer_roller_victor_front(::std::unique_ptr<::frc::VictorSP> t) {
+ transfer_roller_victor_front_ = ::std::move(t);
+ }
+
+ void set_transfer_roller_victor_back(::std::unique_ptr<::frc::VictorSP> t) {
+ transfer_roller_victor_back_ = ::std::move(t);
}
private:
@@ -503,9 +503,9 @@
ctre::phoenix::motorcontrol::ControlMode::Disabled, 0);
intake_falcon_front_->SetDisabled();
intake_falcon_back_->SetDisabled();
- transfer_roller_victor_->SetDisabled();
+ transfer_roller_victor_front_->SetDisabled();
+ transfer_roller_victor_back_->SetDisabled();
catapult_falcon_1_->SetDisabled();
- catapult_falcon_2_->SetDisabled();
turret_falcon_->SetDisabled();
}
@@ -516,14 +516,16 @@
WritePwm(output.intake_voltage_back(), intake_falcon_back_.get());
WriteCan(output.roller_voltage_front(), roller_falcon_front_.get());
WriteCan(output.roller_voltage_back(), roller_falcon_back_.get());
- WritePwm(output.transfer_roller_voltage(), transfer_roller_victor_.get());
+ WritePwm(output.transfer_roller_voltage_front(),
+ transfer_roller_victor_front_.get());
+ WritePwm(-output.transfer_roller_voltage_back(),
+ transfer_roller_victor_back_.get());
- WriteCan(output.flipper_arms_voltage(), flipper_arms_falcon_.get());
+ WriteCan(-output.flipper_arms_voltage(), flipper_arms_falcon_.get());
WritePwm(output.catapult_voltage(), catapult_falcon_1_.get());
- WritePwm(output.catapult_voltage(), catapult_falcon_2_.get());
- WritePwm(output.turret_voltage(), turret_falcon_.get());
+ WritePwm(-output.turret_voltage(), turret_falcon_.get());
}
static void WriteCan(const double voltage,
@@ -548,8 +550,9 @@
flipper_arms_falcon_;
::std::unique_ptr<::frc::TalonFX> turret_falcon_, catapult_falcon_1_,
- catapult_falcon_2_, climber_falcon_;
- ::std::unique_ptr<::frc::VictorSP> transfer_roller_victor_;
+ climber_falcon_;
+ ::std::unique_ptr<::frc::VictorSP> transfer_roller_victor_front_,
+ transfer_roller_victor_back_;
};
class CANSensorReader {
@@ -624,45 +627,46 @@
// Thread 3.
::aos::ShmEventLoop sensor_reader_event_loop(&config.message());
SensorReader sensor_reader(&sensor_reader_event_loop, values);
- sensor_reader.set_drivetrain_left_encoder(make_encoder(0));
- sensor_reader.set_drivetrain_right_encoder(make_encoder(1));
+ sensor_reader.set_drivetrain_left_encoder(make_encoder(1));
+ sensor_reader.set_drivetrain_right_encoder(make_encoder(0));
- sensor_reader.set_intake_encoder_front(make_encoder(2));
+ sensor_reader.set_intake_encoder_front(make_encoder(3));
sensor_reader.set_intake_front_absolute_pwm(
- make_unique<frc::DigitalInput>(2));
- sensor_reader.set_intake_front_potentiometer(
- make_unique<frc::AnalogInput>(2));
-
- sensor_reader.set_intake_encoder_back(make_encoder(3));
- sensor_reader.set_intake_back_absolute_pwm(
make_unique<frc::DigitalInput>(3));
- sensor_reader.set_intake_back_potentiometer(
+ sensor_reader.set_intake_front_potentiometer(
make_unique<frc::AnalogInput>(3));
- sensor_reader.set_turret_encoder(make_encoder(4));
- sensor_reader.set_turret_absolute_pwm(make_unique<frc::DigitalInput>(4));
- sensor_reader.set_turret_potentiometer(make_unique<frc::AnalogInput>(4));
+ sensor_reader.set_intake_encoder_back(make_encoder(4));
+ sensor_reader.set_intake_back_absolute_pwm(
+ make_unique<frc::DigitalInput>(4));
+ sensor_reader.set_intake_back_potentiometer(
+ make_unique<frc::AnalogInput>(4));
- sensor_reader.set_intake_beambreak_front(make_unique<frc::DigitalInput>(5));
+ sensor_reader.set_turret_encoder(make_encoder(5));
+ sensor_reader.set_turret_absolute_pwm(make_unique<frc::DigitalInput>(5));
+ sensor_reader.set_turret_potentiometer(make_unique<frc::AnalogInput>(5));
+
+ // TODO(milind): correct intake beambreak ports once set
+ sensor_reader.set_intake_beambreak_front(make_unique<frc::DigitalInput>(1));
sensor_reader.set_intake_beambreak_back(make_unique<frc::DigitalInput>(6));
sensor_reader.set_turret_beambreak(make_unique<frc::DigitalInput>(7));
- sensor_reader.set_climber_potentiometer(make_unique<frc::AnalogInput>(5));
+ sensor_reader.set_climber_potentiometer(make_unique<frc::AnalogInput>(7));
sensor_reader.set_flipper_arm_left_potentiometer(
- make_unique<frc::AnalogInput>(4));
+ make_unique<frc::AnalogInput>(0));
sensor_reader.set_flipper_arm_right_potentiometer(
- make_unique<frc::AnalogInput>(5));
+ make_unique<frc::AnalogInput>(1));
- sensor_reader.set_catapult_encoder(
- make_unique<frc::Encoder>(0, 1, false, frc::Encoder::k4X));
+ // TODO(milind): correct catapult encoder and absolute pwm ports
+ sensor_reader.set_catapult_encoder(make_encoder(2));
sensor_reader.set_catapult_absolute_pwm(
std::make_unique<frc::DigitalInput>(2));
sensor_reader.set_catapult_potentiometer(
std::make_unique<frc::AnalogInput>(2));
- sensor_reader.set_heading_input(make_unique<frc::DigitalInput>(8));
- sensor_reader.set_yaw_rate_input(make_unique<frc::DigitalInput>(9));
+ sensor_reader.set_heading_input(make_unique<frc::DigitalInput>(9));
+ sensor_reader.set_yaw_rate_input(make_unique<frc::DigitalInput>(8));
AddLoop(&sensor_reader_event_loop);
@@ -670,37 +674,33 @@
::aos::ShmEventLoop output_event_loop(&config.message());
::frc971::wpilib::DrivetrainWriter drivetrain_writer(&output_event_loop);
drivetrain_writer.set_left_controller0(
- ::std::unique_ptr<::frc::VictorSP>(new ::frc::VictorSP(1)), true);
- drivetrain_writer.set_right_controller0(
::std::unique_ptr<::frc::VictorSP>(new ::frc::VictorSP(0)), false);
+ drivetrain_writer.set_right_controller0(
+ ::std::unique_ptr<::frc::VictorSP>(new ::frc::VictorSP(1)), true);
SuperstructureWriter superstructure_writer(&output_event_loop);
- superstructure_writer.set_turret_falcon(make_unique<::frc::TalonFX>(8));
+ superstructure_writer.set_turret_falcon(make_unique<::frc::TalonFX>(3));
superstructure_writer.set_roller_falcon_front(
- make_unique<::ctre::phoenix::motorcontrol::can::TalonFX>(3));
+ make_unique<::ctre::phoenix::motorcontrol::can::TalonFX>(0));
superstructure_writer.set_roller_falcon_back(
- make_unique<::ctre::phoenix::motorcontrol::can::TalonFX>(4));
- superstructure_writer.set_transfer_roller_victor(
- make_unique<::frc::VictorSP>(9));
- superstructure_writer.set_intake_falcon_front(make_unique<frc::TalonFX>(5));
- superstructure_writer.set_intake_falcon_back(make_unique<frc::TalonFX>(6));
- superstructure_writer.set_climber_falcon(make_unique<frc::TalonFX>(7));
- superstructure_writer.set_flipper_arms_falcon(
- make_unique<::ctre::phoenix::motorcontrol::can::TalonFX>(5));
+ make_unique<::ctre::phoenix::motorcontrol::can::TalonFX>(1));
- superstructure_writer.set_catapult_falcon_1(make_unique<::frc::TalonFX>(2));
- superstructure_writer.set_catapult_falcon_2(make_unique<::frc::TalonFX>(3));
+ superstructure_writer.set_transfer_roller_victor_front(
+ make_unique<::frc::VictorSP>(6));
+ superstructure_writer.set_transfer_roller_victor_back(
+ make_unique<::frc::VictorSP>(5));
+
+ superstructure_writer.set_intake_falcon_front(make_unique<frc::TalonFX>(2));
+ superstructure_writer.set_intake_falcon_back(make_unique<frc::TalonFX>(4));
+ superstructure_writer.set_climber_falcon(make_unique<frc::TalonFX>(8));
+ superstructure_writer.set_flipper_arms_falcon(
+ make_unique<::ctre::phoenix::motorcontrol::can::TalonFX>(2));
+
+ superstructure_writer.set_catapult_falcon_1(make_unique<::frc::TalonFX>(9));
AddLoop(&output_event_loop);
- // Thread 5
- ::aos::ShmEventLoop can_sensor_reader_event_loop(&config.message());
- CANSensorReader can_sensor_reader(&can_sensor_reader_event_loop);
- can_sensor_reader.set_flipper_arms_falcon(
- superstructure_writer.flipper_arms_falcon());
- AddLoop(&can_sensor_reader_event_loop);
-
RunLoops();
}
};
diff --git a/y2022/www/2022.png b/y2022/www/2022.png
new file mode 100644
index 0000000..68087bd
--- /dev/null
+++ b/y2022/www/2022.png
Binary files differ
diff --git a/y2022/www/BUILD b/y2022/www/BUILD
index 55cbde2..4aac007 100644
--- a/y2022/www/BUILD
+++ b/y2022/www/BUILD
@@ -1,3 +1,5 @@
+load("@npm//@bazel/typescript:index.bzl", "ts_library")
+load("//tools/build_rules:js.bzl", "rollup_bundle")
load("//frc971/downloader:downloader.bzl", "aos_downloader_dir")
filegroup(
@@ -5,13 +7,44 @@
srcs = glob([
"**/*.html",
"**/*.css",
+ "**/*.png",
]),
visibility = ["//visibility:public"],
)
+ts_library(
+ 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:web_proxy_ts_fbs",
+ "//aos/network/www:proxy",
+ "//y2022/control_loops/superstructure:superstructure_status_ts_fbs",
+ "//y2022/localizer:localizer_output_ts_fbs",
+ "//y2022/localizer:localizer_visualization_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 = ["//y2022:__subpackages__"],
+ deps = [
+ ":field_main",
+ ],
+)
+
aos_downloader_dir(
name = "www_files",
srcs = [
+ ":field_main_bundle.min.js",
":files",
"//frc971/analysis:plot_index_bundle.min.js",
],
diff --git a/y2022/www/constants.ts b/y2022/www/constants.ts
new file mode 100644
index 0000000..b94d7a7
--- /dev/null
+++ b/y2022/www/constants.ts
@@ -0,0 +1,7 @@
+// Conversion constants to meters
+export const IN_TO_M = 0.0254;
+export const FT_TO_M = 0.3048;
+// Dimensions of the field in meters
+export const FIELD_WIDTH = 26 * FT_TO_M + 11.25 * IN_TO_M;
+export const FIELD_LENGTH = 52 * FT_TO_M + 5.25 * IN_TO_M;
+
diff --git a/y2022/www/field.html b/y2022/www/field.html
new file mode 100644
index 0000000..e2a1cf6
--- /dev/null
+++ b/y2022/www/field.html
@@ -0,0 +1,126 @@
+<html>
+ <head>
+ <script src="field_main_bundle.min.js" defer></script>
+ <link rel="stylesheet" href="styles.css">
+ </head>
+ <body>
+ <div id="field"> </div>
+ <div id="legend"> </div>
+ <div id="readouts">
+ <table>
+ <tr>
+ <th colspan="2">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">Aiming</th>
+ </tr>
+ <tr>
+ <td>Shot distance</td>
+ <td id="shot_distance"> NA </td>
+ </tr>
+ <tr>
+ <td>Turret</td>
+ <td id="turret"> NA </td>
+ </tr>
+ </table>
+
+ <table>
+ <tr>
+ <th colspan="2">Catapult</th>
+ </tr>
+ <tr>
+ <td>Fire</td>
+ <td id="fire"> NA </td>
+ </tr>
+ <tr>
+ <td>Solve Time</td>
+ <td id="mpc_solve_time"> NA </td>
+ </tr>
+ <tr>
+ <td>MPC Active</td>
+ <td id="mpc_active"> NA </td>
+ </tr>
+ <tr>
+ <td>Shot Count</td>
+ <td id="shot_count"> NA </td>
+ </tr>
+ <tr>
+ <td>Position</td>
+ <td id="catapult"> NA </td>
+ </tr>
+ </table>
+
+ <table>
+ <tr>
+ <th colspan="2">Superstructure</th>
+ </tr>
+ <tr>
+ <td>State</td>
+ <td id="superstructure_state"> NA </td>
+ </tr>
+ <tr>
+ <td>Intake State</td>
+ <td id="intake_state"> NA </td>
+ </tr>
+ <tr>
+ <td>Reseating</td>
+ <td id="reseating_in_catapult"> NA </td>
+ </tr>
+ <tr>
+ <td>Flippers Open</td>
+ <td id="flippers_open"> NA </td>
+ </tr>
+ <tr>
+ <td>Climber</td>
+ <td id="climber"> NA </td>
+ </tr>
+ </table>
+
+ <table>
+ <tr>
+ <th colspan="2">Intakes</th>
+ </tr>
+ <tr>
+ <td>Front Intake</td>
+ <td id="front_intake"> NA </td>
+ </tr>
+ <tr>
+ <td>Back Intake</td>
+ <td id="back_intake"> NA </td>
+ </tr>
+ </table>
+
+ <table>
+ <tr>
+ <th colspan="2">Images</th>
+ </tr>
+ <tr>
+ <td> Images Accepted </td>
+ <td id="images_accepted"> NA </td>
+ </tr>
+ <tr>
+ <td> Images Rejected </td>
+ <td id="images_rejected"> NA </td>
+ </tr>
+ </table>
+ </div>
+ <div id="vision_readouts">
+ </div>
+ </body>
+</html>
+
diff --git a/y2022/www/field_handler.ts b/y2022/www/field_handler.ts
new file mode 100644
index 0000000..584b65e
--- /dev/null
+++ b/y2022/www/field_handler.ts
@@ -0,0 +1,458 @@
+import * as web_proxy from 'org_frc971/aos/network/web_proxy_generated';
+import {Connection} from 'org_frc971/aos/network/www/proxy';
+import * as flatbuffers_builder from 'org_frc971/external/com_github_google_flatbuffers/ts/builder';
+import {ByteBuffer} from 'org_frc971/external/com_github_google_flatbuffers/ts/byte-buffer';
+import * as localizer from 'org_frc971/y2022/localizer/localizer_visualization_generated';
+import * as output from 'org_frc971/y2022/localizer/localizer_output_generated';
+import * as ss from 'org_frc971/y2022/control_loops/superstructure/superstructure_status_generated'
+
+import LocalizerVisualization = localizer.frc971.controls.LocalizerVisualization;
+import LocalizerOutput = output.frc971.controls.LocalizerOutput;
+import RejectionReason = localizer.frc971.controls.RejectionReason;
+import TargetEstimateDebug = localizer.frc971.controls.TargetEstimateDebug;
+import SuperstructureStatus = ss.y2022.control_loops.superstructure.Status;
+import SuperstructureState = ss.y2022.control_loops.superstructure.SuperstructureState;
+import IntakeState = ss.y2022.control_loops.superstructure.IntakeState;
+
+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 = 34 * IN_TO_M;
+const ROBOT_LENGTH = 36 * IN_TO_M;
+
+const PI_COLORS = ['#ff00ff', '#ffff00', '#00ffff', '#ffa500'];
+
+export class FieldHandler {
+ private canvas = document.createElement('canvas');
+ private localizerOutput: LocalizerOutput|null = null;
+ private superstructureStatus: SuperstructureStatus|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 localizerImageMatches = new Map<number, LocalizerVisualization>();
+ private outerTarget: HTMLElement =
+ (document.getElementById('outer_target') as HTMLElement);
+ private innerTarget: HTMLElement =
+ (document.getElementById('inner_target') as HTMLElement);
+ 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 shotDistance: HTMLElement =
+ (document.getElementById('shot_distance') as HTMLElement);
+ private turret: HTMLElement =
+ (document.getElementById('turret') as HTMLElement);
+ private fire: HTMLElement =
+ (document.getElementById('fire') as HTMLElement);
+ private mpcSolveTime: HTMLElement =
+ (document.getElementById('mpc_solve_time') as HTMLElement);
+ private mpcActive: HTMLElement =
+ (document.getElementById('mpc_active') as HTMLElement);
+ private shotCount: HTMLElement =
+ (document.getElementById('shot_count') as HTMLElement);
+ private catapult: HTMLElement =
+ (document.getElementById('catapult') as HTMLElement);
+ private superstructureState: HTMLElement =
+ (document.getElementById('superstructure_state') as HTMLElement);
+ private intakeState: HTMLElement =
+ (document.getElementById('intake_state') as HTMLElement);
+ private reseatingInCatapult: HTMLElement =
+ (document.getElementById('reseating_in_catapult') as HTMLElement);
+ private flippersOpen: HTMLElement =
+ (document.getElementById('flippers_open') as HTMLElement);
+ private climber: HTMLElement =
+ (document.getElementById('climber') as HTMLElement);
+ private frontIntake: HTMLElement =
+ (document.getElementById('front_intake') as HTMLElement);
+ private backIntake: HTMLElement =
+ (document.getElementById('back_intake') as HTMLElement);
+ private imagesAcceptedCounter: HTMLElement =
+ (document.getElementById('images_accepted') as HTMLElement);
+ private imagesRejectedCounter: HTMLElement =
+ (document.getElementById('images_rejected') as HTMLElement);
+ private rejectionReasonCells: HTMLElement[] = [];
+ private fieldImage: HTMLImageElement = new Image();
+
+ constructor(private readonly connection: Connection) {
+ (document.getElementById('field') as HTMLElement).appendChild(this.canvas);
+
+ this.fieldImage.src = "2022.png";
+
+ for (const value in RejectionReason) {
+ // Typescript generates an iterator that produces both numbers and
+ // strings... don't do anything on the string iterations.
+ if (isNaN(Number(value))) {
+ continue;
+ }
+ const row = document.createElement('div');
+ const nameCell = document.createElement('div');
+ nameCell.innerHTML = RejectionReason[value];
+ row.appendChild(nameCell);
+ const valueCell = document.createElement('div');
+ valueCell.innerHTML = 'NA';
+ this.rejectionReasonCells.push(valueCell);
+ row.appendChild(valueCell);
+ document.getElementById('vision_readouts').appendChild(row);
+ }
+
+ for (let ii = 0; ii < PI_COLORS.length; ++ii) {
+ const legendEntry = document.createElement('div');
+ legendEntry.style.color = PI_COLORS[ii];
+ legendEntry.innerHTML = 'PI' + (ii + 1).toString()
+ document.getElementById('legend').appendChild(legendEntry);
+ }
+
+ this.connection.addConfigHandler(() => {
+ this.connection.addHandler(
+ '/localizer', LocalizerVisualization.getFullyQualifiedName(),
+ (data) => {
+ this.handleLocalizerDebug(data);
+ });
+ this.connection.addHandler(
+ '/localizer', LocalizerOutput.getFullyQualifiedName(), (data) => {
+ this.handleLocalizerOutput(data);
+ });
+ this.connection.addHandler(
+ '/superstructure', SuperstructureStatus.getFullyQualifiedName(),
+ (data) => {
+ this.handleSuperstructureStatus(data);
+ });
+ });
+ }
+
+ private handleLocalizerDebug(data: Uint8Array): void {
+ const now = Date.now() / 1000.0;
+
+ const fbBuffer = new ByteBuffer(data);
+ this.localizerImageMatches.set(
+ now,
+ LocalizerVisualization.getRootAsLocalizerVisualization(
+ fbBuffer as unknown as flatbuffers.ByteBuffer));
+
+ const debug = this.localizerImageMatches.get(now);
+
+ if (debug.statistics()) {
+ this.imagesAcceptedCounter.innerHTML =
+ debug.statistics().totalAccepted().toString();
+ this.imagesRejectedCounter.innerHTML =
+ (debug.statistics().totalCandidates() -
+ debug.statistics().totalAccepted())
+ .toString();
+ if (debug.statistics().rejectionReasonCountLength() ==
+ this.rejectionReasonCells.length) {
+ for (let ii = 0; ii < debug.statistics().rejectionReasonCountLength();
+ ++ii) {
+ this.rejectionReasonCells[ii].innerHTML =
+ debug.statistics().rejectionReasonCount(ii).toString();
+ }
+ } else {
+ console.error('Unexpected number of rejection reasons in counter.');
+ }
+ this.imagesRejectedCounter.innerHTML =
+ (debug.statistics().totalCandidates() -
+ debug.statistics().totalAccepted())
+ .toString();
+ }
+ }
+
+ private handleLocalizerOutput(data: Uint8Array): void {
+ const fbBuffer = new ByteBuffer(data);
+ this.localizerOutput = LocalizerOutput.getRootAsLocalizerOutput(
+ fbBuffer as unknown as flatbuffers.ByteBuffer);
+ }
+
+ private handleSuperstructureStatus(data: Uint8Array): void {
+ const fbBuffer = new ByteBuffer(data);
+ this.superstructureStatus = SuperstructureStatus.getRootAsStatus(
+ fbBuffer as unknown as flatbuffers.ByteBuffer);
+ }
+
+ drawField(): void {
+ const ctx = this.canvas.getContext('2d');
+ ctx.drawImage(
+ this.fieldImage, 0, 0, this.fieldImage.width, this.fieldImage.height,
+ -FIELD_EDGE_X, -FIELD_SIDE_Y, FIELD_LENGTH, FIELD_WIDTH);
+ }
+
+ drawCamera(
+ x: number, y: number, theta: number, color: string = 'blue',
+ extendLines: boolean = true): 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);
+ if (extendLines) {
+ ctx.lineTo(100.0, 0);
+ 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, turret: number|null,
+ color: string = 'blue', dashed: boolean = false,
+ extendLines: boolean = true): 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);
+ if (extendLines) {
+ ctx.lineTo(1000.0, 0);
+ } else {
+ ctx.lineTo(ROBOT_LENGTH / 2.0, 0);
+ }
+ ctx.stroke();
+
+ if (turret !== null) {
+ ctx.save();
+ ctx.rotate(turret);
+ const turretRadius = ROBOT_WIDTH / 3.0;
+ ctx.strokeStyle = 'red';
+ // Draw circle for turret.
+ ctx.beginPath();
+ ctx.arc(0, 0, turretRadius, 0, 2.0 * Math.PI);
+ ctx.stroke();
+ // Draw line in circle to show forwards.
+ ctx.beginPath();
+ ctx.moveTo(0, 0);
+ if (extendLines) {
+ ctx.lineTo(1000.0, 0);
+ } else {
+ ctx.lineTo(turretRadius, 0);
+ }
+ ctx.stroke();
+ ctx.restore();
+ }
+ 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');
+ }
+
+ draw(): void {
+ this.reset();
+ this.drawField();
+
+ // Draw the matches with debugging information from the localizer.
+ const now = Date.now() / 1000.0;
+ for (const [time, value] of this.localizerImageMatches) {
+ const age = now - time;
+ const kRemovalAge = 2.0;
+ if (age > kRemovalAge) {
+ this.localizerImageMatches.delete(time);
+ continue;
+ }
+ const ageAlpha = (kRemovalAge - age) / kRemovalAge
+ for (let i = 0; i < value.targetsLength(); i++) {
+ const imageDebug = value.targets(i);
+ const x = imageDebug.impliedRobotX();
+ const y = imageDebug.impliedRobotY();
+ const theta = imageDebug.impliedRobotTheta();
+ const cameraX = imageDebug.cameraX();
+ const cameraY = imageDebug.cameraY();
+ const cameraTheta = imageDebug.cameraTheta();
+ const accepted = imageDebug.accepted();
+ // Make camera readings fade over time.
+ const alpha = Math.round(255 * ageAlpha).toString(16).padStart(2, '0');
+ const dashed = false;
+ const acceptedRgb = accepted ? '#00FF00' : '#FF0000';
+ const acceptedRgba = acceptedRgb + alpha;
+ const cameraRgb = PI_COLORS[imageDebug.camera()];
+ const cameraRgba = cameraRgb + alpha;
+ this.drawRobot(x, y, theta, null, acceptedRgba, dashed, false);
+ this.drawCamera(cameraX, cameraY, cameraTheta, cameraRgba, false);
+ }
+ }
+ if (this.superstructureStatus) {
+ this.shotDistance.innerHTML = this.superstructureStatus.aimer() ?
+ this.superstructureStatus.aimer().shotDistance().toFixed(2) :
+ 'NA';
+
+ this.fire.innerHTML = this.superstructureStatus.fire() ? 'true' : 'false';
+
+ this.mpcActive.innerHTML =
+ this.superstructureStatus.mpcActive() ? 'true' : 'false';
+
+ this.setValue(this.mpcSolveTime, this.superstructureStatus.solveTime());
+
+ this.shotCount.innerHTML =
+ this.superstructureStatus.shotCount().toFixed(0);
+
+ this.superstructureState.innerHTML =
+ SuperstructureState[this.superstructureStatus.state()];
+
+ this.intakeState.innerHTML =
+ IntakeState[this.superstructureStatus.intakeState()];
+
+ this.reseatingInCatapult.innerHTML =
+ this.superstructureStatus.reseatingInCatapult() ? 'true' : 'false';
+
+ this.flippersOpen.innerHTML =
+ this.superstructureStatus.flippersOpen() ? 'true' : 'false';
+
+ if (!this.superstructureStatus.catapult() ||
+ !this.superstructureStatus.catapult().zeroed()) {
+ this.setZeroing(this.catapult);
+ } else if (this.superstructureStatus.catapult().estopped()) {
+ this.setEstopped(this.catapult);
+ } else {
+ this.setTargetValue(
+ this.catapult,
+ this.superstructureStatus.catapult().unprofiledGoalPosition(),
+ this.superstructureStatus.catapult().estimatorState().position(),
+ 1e-3);
+ }
+
+ if (!this.superstructureStatus.climber() ||
+ !this.superstructureStatus.climber().zeroed()) {
+ this.setZeroing(this.climber);
+ } else if (this.superstructureStatus.climber().estopped()) {
+ this.setEstopped(this.climber);
+ } else {
+ this.setTargetValue(
+ this.climber,
+ this.superstructureStatus.climber().unprofiledGoalPosition(),
+ this.superstructureStatus.climber().estimatorState().position(),
+ 1e-3);
+ }
+
+
+
+ if (!this.superstructureStatus.turret() ||
+ !this.superstructureStatus.turret().zeroed()) {
+ this.setZeroing(this.turret);
+ } else if (this.superstructureStatus.turret().estopped()) {
+ this.setEstopped(this.turret);
+ } else {
+ this.setTargetValue(
+ this.turret,
+ this.superstructureStatus.turret().unprofiledGoalPosition(),
+ this.superstructureStatus.turret().estimatorState().position(),
+ 1e-3);
+ }
+
+ if (!this.superstructureStatus.intakeBack() ||
+ !this.superstructureStatus.intakeBack().zeroed()) {
+ this.setZeroing(this.backIntake);
+ } else if (this.superstructureStatus.intakeBack().estopped()) {
+ this.setEstopped(this.backIntake);
+ } else {
+ this.setValue(
+ this.backIntake,
+ this.superstructureStatus.intakeBack().estimatorState().position());
+ }
+
+ if (!this.superstructureStatus.intakeFront() ||
+ !this.superstructureStatus.intakeFront().zeroed()) {
+ this.setZeroing(this.frontIntake);
+ } else if (this.superstructureStatus.intakeFront().estopped()) {
+ this.setEstopped(this.frontIntake);
+ } else {
+ this.setValue(
+ this.frontIntake,
+ this.superstructureStatus.intakeFront()
+ .estimatorState()
+ .position());
+ }
+ }
+
+ if (this.localizerOutput) {
+ if (!this.localizerOutput.zeroed()) {
+ this.setZeroing(this.x);
+ this.setZeroing(this.y);
+ this.setZeroing(this.theta);
+ } else {
+ this.setValue(this.x, this.localizerOutput.x());
+ this.setValue(this.y, this.localizerOutput.y());
+ this.setValue(this.theta, this.localizerOutput.theta());
+ }
+
+ this.drawRobot(
+ this.localizerOutput.x(), this.localizerOutput.y(),
+ this.localizerOutput.theta(),
+ this.superstructureStatus ?
+ this.superstructureStatus.turret().position() :
+ null);
+ }
+
+ window.requestAnimationFrame(() => this.draw());
+ }
+
+ reset(): void {
+ const ctx = this.canvas.getContext('2d');
+ 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 - 10) / FIELD_LENGTH;
+ ctx.scale(M_TO_PX, M_TO_PX);
+ ctx.lineWidth = 1 / M_TO_PX;
+ }
+}
diff --git a/y2022/www/field_main.ts b/y2022/www/field_main.ts
new file mode 100644
index 0000000..7e2e392
--- /dev/null
+++ b/y2022/www/field_main.ts
@@ -0,0 +1,12 @@
+import {Connection} from 'org_frc971/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/y2022/www/index.html b/y2022/www/index.html
index 70442f9..e4e185e 100644
--- a/y2022/www/index.html
+++ b/y2022/www/index.html
@@ -1,5 +1,6 @@
<html>
<body>
+ <a href="field.html">Field Visualization</a><br>
<a href="plotter.html">Plots</a>
</body>
</html>
diff --git a/y2022/y2022_imu.json b/y2022/y2022_imu.json
index d4fe8e4..c5c7904 100644
--- a/y2022/y2022_imu.json
+++ b/y2022/y2022_imu.json
@@ -223,10 +223,26 @@
"type": "frc971.controls.LocalizerStatus",
"source_node": "imu",
"frequency": 2200,
+ "max_size": 2000
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/logger/localizer/frc971-controls-LocalizerStatus",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "imu",
+ "logger": "NOT_LOGGED",
+ "frequency": 2200,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/localizer",
+ "type": "frc971.controls.LocalizerVisualization",
+ "source_node": "imu",
+ "frequency": 200,
"max_size": 2000,
"logger": "LOCAL_AND_REMOTE_LOGGER",
"logger_nodes": [
- "roborio"
+ "logger"
],
"destination_nodes": [
{
@@ -241,11 +257,11 @@
]
},
{
- "name": "/imu/aos/remote_timestamps/logger/localizer/frc971-controls-LocalizerStatus",
+ "name": "/imu/aos/remote_timestamps/logger/localizer/frc971-controls-LocalizerVisualization",
"type": "aos.message_bridge.RemoteMessage",
"source_node": "imu",
"logger": "NOT_LOGGED",
- "frequency": 2200,
+ "frequency": 200,
"num_senders": 2,
"max_size": 200
},
@@ -257,7 +273,8 @@
"max_size": 200,
"logger": "LOCAL_AND_REMOTE_LOGGER",
"logger_nodes": [
- "roborio"
+ "roborio",
+ "logger"
],
"destination_nodes": [
{
@@ -341,9 +358,7 @@
},
{
"name": "localizer",
- "executable_name": "localizer",
- "autostart": false,
- "autorestart": false,
+ "executable_name": "localizer_main",
"nodes": [
"imu"
]
@@ -365,9 +380,10 @@
{
"name": "localizer_logger",
"executable_name": "logger_main",
- "args": ["--logging_folder", "", "--snappy_compress"],
+ "autostart": false,
+ "args": ["--snappy_compress"],
"nodes": [
- "logger"
+ "imu"
]
},
{
diff --git a/y2022/y2022_logger.json b/y2022/y2022_logger.json
index 2407b9e..b72abeb 100644
--- a/y2022/y2022_logger.json
+++ b/y2022/y2022_logger.json
@@ -35,6 +35,22 @@
]
},
{
+ "name": "/drivetrain",
+ "type": "frc971.control_loops.drivetrain.Output",
+ "source_node": "roborio",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "logger",
+ "priority": 2,
+ "time_to_live": 500000000
+ }
+ ]
+ },
+ {
"name": "/pi1/aos",
"type": "aos.message_bridge.Timestamp",
"source_node": "pi1",
@@ -306,7 +322,7 @@
"max_size": 200
},
{
- "name": "/pi1/camera",
+ "name": "/pi1/camera/decimated",
"type": "frc971.vision.CameraImage",
"source_node": "pi1",
"logger": "LOCAL_AND_REMOTE_LOGGER",
@@ -322,7 +338,7 @@
]
},
{
- "name": "/pi2/camera",
+ "name": "/pi2/camera/decimated",
"type": "frc971.vision.CameraImage",
"source_node": "pi2",
"logger": "LOCAL_AND_REMOTE_LOGGER",
@@ -333,12 +349,12 @@
{
"name": "logger",
"priority": 3,
- "time_to_live": 5000000
+ "time_to_live": 500000000
}
]
},
{
- "name": "/pi3/camera",
+ "name": "/pi3/camera/decimated",
"type": "frc971.vision.CameraImage",
"source_node": "pi3",
"logger": "LOCAL_AND_REMOTE_LOGGER",
@@ -354,7 +370,7 @@
]
},
{
- "name": "/pi4/camera",
+ "name": "/pi4/camera/decimated",
"type": "frc971.vision.CameraImage",
"source_node": "pi4",
"logger": "LOCAL_AND_REMOTE_LOGGER",
@@ -383,16 +399,17 @@
],
"applications": [
{
- "name": "message_bridge_client",
+ "name": "logger_message_bridge_client",
"executable_name": "message_bridge_client",
- "args": ["--rmem=8388608"],
+ "args": ["--rmem=8388608", "--rt_priority=16"],
"nodes": [
"logger"
]
},
{
- "name": "message_bridge_server",
+ "name": "logger_message_bridge_server",
"executable_name": "message_bridge_server",
+ "args": ["--rt_priority=16"],
"nodes": [
"logger"
]
diff --git a/y2022/y2022_pi_template.json b/y2022/y2022_pi_template.json
index 7f49e41..3dff81e 100644
--- a/y2022/y2022_pi_template.json
+++ b/y2022/y2022_pi_template.json
@@ -146,6 +146,14 @@
"num_senders": 18
},
{
+ "name": "/pi{{ NUM }}/camera/decimated",
+ "type": "frc971.vision.CameraImage",
+ "source_node": "pi{{ NUM }}",
+ "frequency": 2,
+ "max_size": 620000,
+ "num_senders": 18
+ },
+ {
"name": "/pi{{ NUM }}/camera",
"type": "frc971.vision.calibration.CalibrationData",
"source_node": "pi{{ NUM }}",
@@ -200,6 +208,18 @@
"max_size": 208
},
{
+ "name": "/localizer",
+ "type": "frc971.controls.LocalizerOutput",
+ "source_node": "imu",
+ "destination_nodes": [
+ {
+ "name": "pi{{ NUM }}",
+ "priority": 5,
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
"name": "/logger/aos",
"type": "aos.starter.StarterRpc",
"source_node": "logger",
@@ -328,6 +348,13 @@
"nodes": [
"pi{{ NUM }}"
]
+ },
+ {
+ "name": "image_decimator",
+ "executable_name": "image_decimator",
+ "nodes": [
+ "pi{{ NUM }}"
+ ]
}
],
"maps": [
diff --git a/y2022/y2022_roborio.json b/y2022/y2022_roborio.json
index f3bf5d0..e342094 100644
--- a/y2022/y2022_roborio.json
+++ b/y2022/y2022_roborio.json
@@ -211,13 +211,19 @@
"num_senders": 2,
"logger": "LOCAL_AND_REMOTE_LOGGER",
"logger_nodes": [
- "imu"
+ "imu",
+ "logger"
],
"destination_nodes": [
{
"name": "imu",
"priority": 5,
- "time_to_live": 5000000
+ "time_to_live": 50000000
+ },
+ {
+ "name": "logger",
+ "priority": 5,
+ "time_to_live": 50000000
}
]
},
@@ -246,6 +252,12 @@
"max_size": 72
},
{
+ "name": "/superstructure",
+ "type": "y2022.input.joysticks.Setpoint",
+ "source_node": "roborio",
+ "num_senders": 2
+ },
+ {
"name": "/drivetrain",
"type": "frc971.sensors.GyroReading",
"source_node": "roborio",
diff --git a/yarn.lock b/yarn.lock
index 2c63fab..e76092f 100644
--- a/yarn.lock
+++ b/yarn.lock
@@ -2,53 +2,53 @@
# yarn lockfile v1
-"@angular-devkit/architect@0.1301.4":
- version "0.1301.4"
- resolved "https://registry.yarnpkg.com/@angular-devkit/architect/-/architect-0.1301.4.tgz#2fc51bcae0dcb581c8be401e2fde7bbd10b43076"
- integrity sha512-p6G8CEMnE+gYwxRyEttj3QGsuNJ3Kusi7iwBIzWyf2RpJSdGzXdwUEiRGg6iS0YHFr06/ZFfAWfnM2DQvNm4TA==
+"@angular-devkit/architect@0.1302.0":
+ version "0.1302.0"
+ resolved "https://registry.yarnpkg.com/@angular-devkit/architect/-/architect-0.1302.0.tgz#31a2e6f0c744c5076c85b6db71e31665d7daef55"
+ integrity sha512-1CmVYvxyfvK/khTcDJwwXibm/z4upM2j5SDpwuIdaLx21E4oQPmHn+U/quT/jE5VI1zfZi2vfvIaSXn9XQzMiQ==
dependencies:
- "@angular-devkit/core" "13.1.4"
+ "@angular-devkit/core" "13.2.0"
rxjs "6.6.7"
-"@angular-devkit/core@13.1.4":
- version "13.1.4"
- resolved "https://registry.yarnpkg.com/@angular-devkit/core/-/core-13.1.4.tgz#b5b6ddd674ae351f83beff2e4a0d702096bdfd47"
- integrity sha512-225Gjy4iVxh5Jo9njJnaG75M/Dt95UW+dEPCGWKV5E/++7UUlXlo9sNWq8x2vJm2nhtsPkpnXNOt4pW1mIDwqQ==
+"@angular-devkit/core@13.2.0":
+ version "13.2.0"
+ resolved "https://registry.yarnpkg.com/@angular-devkit/core/-/core-13.2.0.tgz#d7ee99ba40af70193a436a27ee1591a1ec754cd9"
+ integrity sha512-5+aV2W2QUazySMKusBuT2pi2qsXWpTHJG2x62mKGAy0lxzwG8l3if+WP3Uh85SQS+zqlHeKxEbmm9zNn8ZrzFg==
dependencies:
- ajv "8.8.2"
+ ajv "8.9.0"
ajv-formats "2.1.1"
fast-json-stable-stringify "2.1.0"
magic-string "0.25.7"
rxjs "6.6.7"
source-map "0.7.3"
-"@angular-devkit/schematics@13.1.4":
- version "13.1.4"
- resolved "https://registry.yarnpkg.com/@angular-devkit/schematics/-/schematics-13.1.4.tgz#e8ed817887aa51268dec27d8d6188e2f3f10742a"
- integrity sha512-yBa7IeC4cLZ7s137NAQD+sMB5c6SI6UJ6xYxl6J/CvV2RLGOZZA93i4GuRALi5s82eLi1fH+HEL/gvf3JQynzQ==
+"@angular-devkit/schematics@13.2.0":
+ version "13.2.0"
+ resolved "https://registry.yarnpkg.com/@angular-devkit/schematics/-/schematics-13.2.0.tgz#656a5491be9f25e08faffd410c6ad9a75a82a8a2"
+ integrity sha512-EwoqDqLJH5YpWiLuQJwonnJu2bi4xQlyKXyUTuXsQ4gIsAPrg+ijyAe+F/brAtDLBj0sU7JHoC0U1yx2pZ7f1A==
dependencies:
- "@angular-devkit/core" "13.1.4"
+ "@angular-devkit/core" "13.2.0"
jsonc-parser "3.0.0"
magic-string "0.25.7"
ora "5.4.1"
rxjs "6.6.7"
-"@angular/animations@latest":
- version "13.1.3"
- resolved "https://registry.yarnpkg.com/@angular/animations/-/animations-13.1.3.tgz#2da6ad99602bfb450624a7499d6f81366c3a4519"
- integrity sha512-OwsVQsNHubIgRcxnjti4CU3QJnqd7Z2b+2iu3M349Oxyqxz4DNCqKXalDuJZt/b0yNfirvYO3kCgBfj4PF43QQ==
+"@angular/animations@13.2.0":
+ version "13.2.0"
+ resolved "https://registry.yarnpkg.com/@angular/animations/-/animations-13.2.0.tgz#001983463ea5a1b0ffc8e86b0cd5efeb3acb3a4d"
+ integrity sha512-zLmNxkfxDQShJ97V9gTyQdlEbCD/zDUdpHXKlUViBIbe2M13FLGV3e2D+x9jGr/PRzFe0cukOnYxNEHJqqjqPA==
dependencies:
tslib "^2.3.0"
-"@angular/cli@latest":
- version "13.1.4"
- resolved "https://registry.yarnpkg.com/@angular/cli/-/cli-13.1.4.tgz#34e6e87d1c6950408167c41293cf2cd5d1e00a2e"
- integrity sha512-PP9xpvDDCHhLTIZjewQQzzf+JbpF2s5mXTW2AgIL/E53ukaVvXwwjFMt9dQvECwut/LDpThoc3OfqcGrmwtqnA==
+"@angular/cli@13.2.0":
+ version "13.2.0"
+ resolved "https://registry.yarnpkg.com/@angular/cli/-/cli-13.2.0.tgz#550841330a4eead75466f423c68a57be3640ec53"
+ integrity sha512-xrtClCucVSBwELG6zgaHrjC71p1rZOkwjF/HewnOFNjyjXSbWIO2y5d/6O2wxmNASoeStpiEU0zPpwDGhXiYpQ==
dependencies:
- "@angular-devkit/architect" "0.1301.4"
- "@angular-devkit/core" "13.1.4"
- "@angular-devkit/schematics" "13.1.4"
- "@schematics/angular" "13.1.4"
+ "@angular-devkit/architect" "0.1302.0"
+ "@angular-devkit/core" "13.2.0"
+ "@angular-devkit/schematics" "13.2.0"
+ "@schematics/angular" "13.2.0"
"@yarnpkg/lockfile" "1.1.0"
ansi-colors "4.1.1"
debug "4.3.3"
@@ -59,23 +59,23 @@
npm-pick-manifest "6.1.1"
open "8.4.0"
ora "5.4.1"
- pacote "12.0.2"
- resolve "1.20.0"
+ pacote "12.0.3"
+ resolve "1.22.0"
semver "7.3.5"
symbol-observable "4.0.0"
uuid "8.3.2"
-"@angular/common@latest":
- version "13.1.3"
- resolved "https://registry.yarnpkg.com/@angular/common/-/common-13.1.3.tgz#4c80f45cfd00a17543559c5fbebe0a7a7cf403ed"
- integrity sha512-8qf5syeXUogf3+GSu6IRJjrk46UKh9L0QuLx+OSIl/df0y1ewx7e28q3BAUEEnOnKrLzpPNxWs2iwModc4KYfg==
+"@angular/common@13.2.0":
+ version "13.2.0"
+ resolved "https://registry.yarnpkg.com/@angular/common/-/common-13.2.0.tgz#d5e311c14c90867d5da7d1d5f539813e338a7d5f"
+ integrity sha512-zyq3kscl5BoY+xxl4YOfbKP72xwzx/vKLE+2ougjPu2spm5KIllIAo/VrxVqIBrsGWT/4gs9pvIOqOdOfufxUA==
dependencies:
tslib "^2.3.0"
-"@angular/compiler-cli@latest":
- version "13.1.3"
- resolved "https://registry.yarnpkg.com/@angular/compiler-cli/-/compiler-cli-13.1.3.tgz#0269370350e928f22f3150523f95bc490a1e7a7a"
- integrity sha512-ALURaJATc54DzPuiZBvALf/alEp1wr7Hjmw4FuMn2cU7p8lwKkra1Dz5dAZOxh7jAcD1GJfrK/+Sb7A3cuuKjQ==
+"@angular/compiler-cli@13.2.0":
+ version "13.2.0"
+ resolved "https://registry.yarnpkg.com/@angular/compiler-cli/-/compiler-cli-13.2.0.tgz#6eee613e86ec028a4a2b88a9dce45512eef7e862"
+ integrity sha512-IDX0X3GXjhUzd/cFyNZBG3eVqh6Y2W7MYvH9tXbZHcJ6vH9RkN2+zh/XQautVWy4EP33oQoDlsydfYKqbHr9TA==
dependencies:
"@babel/core" "^7.8.6"
canonical-path "1.0.0"
@@ -89,24 +89,31 @@
tslib "^2.3.0"
yargs "^17.2.1"
-"@angular/compiler@latest":
- version "13.1.3"
- resolved "https://registry.yarnpkg.com/@angular/compiler/-/compiler-13.1.3.tgz#fc33b06046599ecc943f55049e0a121d5ab46d4f"
- integrity sha512-dbHs/Oa+Dn+7i0jKtlVDE0lD0DaUC+lVzAcTK/zS37LrckrTMn1CA+z9bZ4gpHig9RU0wgV3YORxv0wokyiB8A==
+"@angular/compiler@13.2.0":
+ version "13.2.0"
+ resolved "https://registry.yarnpkg.com/@angular/compiler/-/compiler-13.2.0.tgz#4112970f2bf6e347511de1e32459d717141750e3"
+ integrity sha512-TTA+Mn31vAwI4qiaH0h8DqNV3DWgZF+Q9G8Qqbw17k8Jf+B5CdLkMYBF8wbGegIdsEfo+6DebCp71W+aJxuSlw==
dependencies:
tslib "^2.3.0"
-"@angular/core@latest":
- version "13.1.3"
- resolved "https://registry.yarnpkg.com/@angular/core/-/core-13.1.3.tgz#4afd71f674f9ead1aada81315f84846cdba10fa4"
- integrity sha512-rvCnIAonRx7VnH2Mv9lQR+UYdlFQQetZCjPw8QOswOspEpHpEPDrp1HxDIqJnHxNqW0n8J3Zev/VgQYr0481UA==
+"@angular/core@13.2.0":
+ version "13.2.0"
+ resolved "https://registry.yarnpkg.com/@angular/core/-/core-13.2.0.tgz#8db7b6f56eb2f211b72d943582061b247f39fe7f"
+ integrity sha512-mWRWbbZ6k00AicA/GrxmWKaw8upo77sRQz4tSYKpwVKt2TtCeoW8OkdYUpnmuVjxpF0bD6PtVc0e1fD6es/ElA==
dependencies:
tslib "^2.3.0"
-"@angular/platform-browser@latest":
- version "13.1.3"
- resolved "https://registry.yarnpkg.com/@angular/platform-browser/-/platform-browser-13.1.3.tgz#69d90b10e89e11f14f5798d1b6fd788255a6114e"
- integrity sha512-mnWjdr9UTNZvGk8jPI6O9FIhun8Q/0ghy3dg3I9AfRzEG4vPiIZW1ICksTiB+jV9etzhKpidtmg71bwgeXax1A==
+"@angular/forms@13.2.0":
+ version "13.2.0"
+ resolved "https://registry.yarnpkg.com/@angular/forms/-/forms-13.2.0.tgz#67d505c09175d1ba809be721303316db7b0c60d4"
+ integrity sha512-aduXLuvqynDRRdb316yY1O5rdMQ2DKeNxu5P2FG1nkLQ3hqZvpiaUMhFyXvKDG3s0rV5e/PZs1cpg0Aqdfwevw==
+ dependencies:
+ tslib "^2.3.0"
+
+"@angular/platform-browser@13.2.0":
+ version "13.2.0"
+ resolved "https://registry.yarnpkg.com/@angular/platform-browser/-/platform-browser-13.2.0.tgz#d8a309c231dec646ab1dad28240466a00151b54b"
+ integrity sha512-FB9eKdRqpjopTFbea5JXnqSPFR7DZD4nepOSGnYttV9cVj4pABqx2A6FJCnyvPPUSTamODye/pNkGmzP2P1gcw==
dependencies:
tslib "^2.3.0"
@@ -351,10 +358,10 @@
"@babel/helper-validator-identifier" "^7.16.7"
to-fast-properties "^2.0.0"
-"@bazel/concatjs@latest":
- version "4.6.1"
- resolved "https://registry.yarnpkg.com/@bazel/concatjs/-/concatjs-4.6.1.tgz#c40abc3fbe362cbad1e3383c4e78b58d1f4c8e13"
- integrity sha512-eI79oS1F8vK9kw8ttg/zeQYyOiN9FfhJjYyammkc3q4WlNs3Xm717Cp/CquSwPyFh022mB00Tib4gHJ7zp+VpA==
+"@bazel/concatjs@4.4.6":
+ version "4.4.6"
+ resolved "https://registry.yarnpkg.com/@bazel/concatjs/-/concatjs-4.4.6.tgz#842e4472f5d766a610a93ecc1315dd89a17f0cd3"
+ integrity sha512-2qt6M9G5S3gPTTB/VG8KwhTtv5w9ZqedFvOQS7yBbHHyV4UEWSxijhqHinpbJs0iKOWRbsDGE+jtRdgq8Vu+ZQ==
dependencies:
protobufjs "6.8.8"
source-map-support "0.5.9"
@@ -365,17 +372,17 @@
resolved "https://registry.yarnpkg.com/@bazel/protractor/-/protractor-4.4.6.tgz#2ed9c3780caf741bbe6e6947bcb84635fe0aa2a1"
integrity sha512-jLg2FDf7pCx87P56+HFEdXmcACpHJiGvePnVhKohLs0QOj+SEi1hDz4YgUsTBmcxZOEftI/v0zmXwgi9FFZ8QA==
-"@bazel/rollup@latest":
- version "4.6.1"
- resolved "https://registry.yarnpkg.com/@bazel/rollup/-/rollup-4.6.1.tgz#7e5054b1b43c1052bdd8824d9f1a11a410d540e2"
- integrity sha512-8a2halG0dnzjs0BgGiHOM47LVCotGW0I9lSWLdwrTxTNOp8fEdbZ8C7TMHFE+8Zc3Z5oerqR8uvIpMarOJQumQ==
+"@bazel/rollup@4.4.6":
+ version "4.4.6"
+ resolved "https://registry.yarnpkg.com/@bazel/rollup/-/rollup-4.4.6.tgz#936d34c9c8159d42f84f1ac3c9ebb1bed27f691a"
+ integrity sha512-VujfM6QGuNpQZVzOf2nfAi3Xoi4EdA9nXXy6Gq4WiSaDPbgZrlXl/4Db+Hb6Nej5uvWqqppgvigCPHcWX9yM/w==
dependencies:
- "@bazel/worker" "4.6.1"
+ "@bazel/worker" "4.4.6"
-"@bazel/terser@latest":
- version "4.6.1"
- resolved "https://registry.yarnpkg.com/@bazel/terser/-/terser-4.6.1.tgz#a3f70672cef7b9383b42930691d6fc8be4b8d993"
- integrity sha512-LOXNSLCscyiNDxhLEgIL+Unj7UQpH6s+IkujizRpEyMrVVrhun5do972ab4TdqCXi9rxQKBBkgj8EL43gMimwg==
+"@bazel/terser@4.4.6":
+ version "4.4.6"
+ resolved "https://registry.yarnpkg.com/@bazel/terser/-/terser-4.4.6.tgz#7e1579078ab604a0b53135f43086c0a060c83804"
+ integrity sha512-mJKxI3Vinj5kPEXR+XZXch11T18D7nHBle4+pcVmh675xlXRVTTvptYf7Qm0x9FMdjq4D6d1gJOeyxjz8YKaIg==
"@bazel/typescript@4.4.6":
version "4.4.6"
@@ -395,13 +402,6 @@
dependencies:
google-protobuf "^3.6.1"
-"@bazel/worker@4.6.1":
- version "4.6.1"
- resolved "https://registry.yarnpkg.com/@bazel/worker/-/worker-4.6.1.tgz#96925f5819344225d4fe40ffa630a3c5f4847a0b"
- integrity sha512-D6TsHxGSljmlLoz8FXL1+ISh8XnDuRkBpT6Mz0wD62eWajUZASTfX9I4HNiLNbsWY4Omc7nKXI+j4R8/BLciFg==
- dependencies:
- google-protobuf "^3.6.1"
-
"@gar/promisify@^1.0.1":
version "1.1.2"
resolved "https://registry.yarnpkg.com/@gar/promisify/-/promisify-1.1.2.tgz#30aa825f11d438671d585bd44e7fd564535fc210"
@@ -525,7 +525,7 @@
resolved "https://registry.yarnpkg.com/@protobufjs/utf8/-/utf8-1.1.0.tgz#a777360b5b39a1a2e5106f8e858f2fd2d060c570"
integrity sha1-p3c2C1s5oaLlEG+OhY8v0tBgxXA=
-"@rollup/plugin-node-resolve@latest":
+"@rollup/plugin-node-resolve@13.1.3":
version "13.1.3"
resolved "https://registry.yarnpkg.com/@rollup/plugin-node-resolve/-/plugin-node-resolve-13.1.3.tgz#2ed277fb3ad98745424c1d2ba152484508a92d79"
integrity sha512-BdxNk+LtmElRo5d06MGY4zoepyrXX1tkzX2hrnPEZ53k78GuOMWLqmJDGIIOPwVRIFZrLQOo+Yr6KtCuLIA0AQ==
@@ -546,13 +546,13 @@
estree-walker "^1.0.1"
picomatch "^2.2.2"
-"@schematics/angular@13.1.4":
- version "13.1.4"
- resolved "https://registry.yarnpkg.com/@schematics/angular/-/angular-13.1.4.tgz#8b8c9ad40403c485bae9adeb51649711651189d2"
- integrity sha512-P1YsHn1LLAmdpB9X2TBuUgrvEW/KaoBbHr8ifYO8/uQEXyeiIF+So8h/dnegkYkdsr3OwQ2X/j3UF6/+HS0odg==
+"@schematics/angular@13.2.0":
+ version "13.2.0"
+ resolved "https://registry.yarnpkg.com/@schematics/angular/-/angular-13.2.0.tgz#fee1ef0810d16d7090822233e6e6e01a91a04a2c"
+ integrity sha512-DlUJ+ix9u/wz7IWc82dix5xsDGu0nztZ6Litrv+EsFDRYc95IFxTWuNwwjL2eRkI2KLIk79wmO7xhlUwrUyNlg==
dependencies:
- "@angular-devkit/core" "13.1.4"
- "@angular-devkit/schematics" "13.1.4"
+ "@angular-devkit/core" "13.2.0"
+ "@angular-devkit/schematics" "13.2.0"
jsonc-parser "3.0.0"
"@socket.io/base64-arraybuffer@~1.0.2":
@@ -565,6 +565,11 @@
resolved "https://registry.yarnpkg.com/@tootallnate/once/-/once-1.1.2.tgz#ccb91445360179a04e7fe6aff78c00ffc1eeaf82"
integrity sha512-RbzJvlNzmRq5c3O09UipeuXno4tA1FE6ikOjxZK0tuxVv3412l64l5t1W5pj4+rJq9vpkm/kwiR07aZXnsKPxw==
+"@tootallnate/once@2":
+ version "2.0.0"
+ resolved "https://registry.yarnpkg.com/@tootallnate/once/-/once-2.0.0.tgz#f544a148d3ab35801c1f633a7441fd87c2e484bf"
+ integrity sha512-XCuKFP5PS55gnMVu3dty8KPatLqUoy/ZYzDzAGCQ8JNFCkLXzmI7vNHCR+XpbZaMWQK/vQubr7PkYq8g470J/A==
+
"@types/component-emitter@^1.2.10":
version "1.2.11"
resolved "https://registry.yarnpkg.com/@types/component-emitter/-/component-emitter-1.2.11.tgz#50d47d42b347253817a39709fef03ce66a108506"
@@ -585,12 +590,12 @@
resolved "https://registry.yarnpkg.com/@types/estree/-/estree-0.0.39.tgz#e177e699ee1b8c22d23174caaa7422644389509f"
integrity sha512-EYNwp3bU+98cpU4lAWYYL7Zz+2gryWH1qbdDTidVd6hkiR6weksdbMadyXKXNPEkQFhXM+hVO9ZygomHXp+AIw==
-"@types/flatbuffers@latest":
+"@types/flatbuffers@1.10.0":
version "1.10.0"
resolved "https://registry.yarnpkg.com/@types/flatbuffers/-/flatbuffers-1.10.0.tgz#aa74e30ffdc86445f2f060e1808fc9d56b5603ba"
integrity sha512-7btbphLrKvo5yl/5CC2OCxUSMx1wV1wvGT1qDXkSt7yi00/YW7E8k6qzXqJHsp+WU0eoG7r6MTQQXI9lIvd0qA==
-"@types/jasmine@latest":
+"@types/jasmine@3.10.3":
version "3.10.3"
resolved "https://registry.yarnpkg.com/@types/jasmine/-/jasmine-3.10.3.tgz#a89798b3d5a8bd23ca56e855a9aee3e5a93bdaaa"
integrity sha512-SWyMrjgdAUHNQmutvDcKablrJhkDLy4wunTme8oYLjKp41GnHGxMRXr2MQMvy/qy8H3LdzwQk9gH4hZ6T++H8g==
@@ -605,6 +610,11 @@
resolved "https://registry.yarnpkg.com/@types/node/-/node-17.0.8.tgz#50d680c8a8a78fe30abe6906453b21ad8ab0ad7b"
integrity sha512-YofkM6fGv4gDJq78g4j0mMuGMkZVxZDgtU0JRdx6FgiJDG+0fY0GKVolOV8WqVmEhLCXkQRjwDdKyPxJp/uucg==
+"@types/node@17.0.21":
+ version "17.0.21"
+ resolved "https://registry.yarnpkg.com/@types/node/-/node-17.0.21.tgz#864b987c0c68d07b4345845c3e63b75edd143644"
+ integrity sha512-DBZCJbhII3r90XbQxI8Y9IjjiiOGlZ0Hr32omXIZvwwZ7p4DMMXGrKXVyPfuoBOri9XNtL0UK69jYIBIsRX3QQ==
+
"@types/node@>=10.0.0":
version "17.0.10"
resolved "https://registry.yarnpkg.com/@types/node/-/node-17.0.10.tgz#616f16e9d3a2a3d618136b1be244315d95bd7cab"
@@ -615,11 +625,6 @@
resolved "https://registry.yarnpkg.com/@types/node/-/node-10.14.18.tgz#b7d45fc950e6ffd7edc685e890d13aa7b8535dce"
integrity sha512-ryO3Q3++yZC/+b8j8BdKd/dn9JlzlHBPdm80656xwYUdmPkpTGTjkAdt6BByiNupGPE8w0FhBgvYy/fX9hRNGQ==
-"@types/node@latest":
- version "17.0.12"
- resolved "https://registry.yarnpkg.com/@types/node/-/node-17.0.12.tgz#f7aa331b27f08244888c47b7df126184bc2339c5"
- integrity sha512-4YpbAsnJXWYK/fpTVFlMIcUIho2AYCi4wg5aNPrG1ng7fn/1/RZfCIpRCiBX+12RVa34RluilnvCqD+g3KiSiA==
-
"@types/q@^0.0.32":
version "0.0.32"
resolved "https://registry.yarnpkg.com/@types/q/-/q-0.0.32.tgz#bd284e57c84f1325da702babfc82a5328190c0c5"
@@ -683,6 +688,15 @@
depd "^1.1.2"
humanize-ms "^1.2.1"
+agentkeepalive@^4.2.1:
+ version "4.2.1"
+ resolved "https://registry.yarnpkg.com/agentkeepalive/-/agentkeepalive-4.2.1.tgz#a7975cbb9f83b367f06c90cc51ff28fe7d499717"
+ integrity sha512-Zn4cw2NEqd+9fiSVWMscnjyQ1a8Yfoc5oBajLeo5w+YBHgDUcEBY2hS4YpTz6iN5f/2zQiktcuM6tS8x1p9dpA==
+ dependencies:
+ debug "^4.1.0"
+ depd "^1.1.2"
+ humanize-ms "^1.2.1"
+
aggregate-error@^3.0.0:
version "3.1.0"
resolved "https://registry.yarnpkg.com/aggregate-error/-/aggregate-error-3.1.0.tgz#92670ff50f5359bdb7a3e0d40d0ec30c5737687a"
@@ -698,10 +712,10 @@
dependencies:
ajv "^8.0.0"
-ajv@8.8.2:
- version "8.8.2"
- resolved "https://registry.yarnpkg.com/ajv/-/ajv-8.8.2.tgz#01b4fef2007a28bf75f0b7fc009f62679de4abbb"
- integrity sha512-x9VuX+R/jcFj1DHo/fCp99esgGDWiHENrKxaCENuCxpoMCmAt/COCGVDwA7kleEpEzJjDnvh3yGoOuLu0Dtllw==
+ajv@8.9.0, ajv@^8.0.0:
+ version "8.9.0"
+ resolved "https://registry.yarnpkg.com/ajv/-/ajv-8.9.0.tgz#738019146638824dea25edcf299dcba1b0e7eb18"
+ integrity sha512-qOKJyNj/h+OWx7s5DePL6Zu1KeM9jPZhwBqs+7DzP6bGOvqzVCSf0xueYmVuaC/oQ/VtS2zLMLHdQFbkka+XDQ==
dependencies:
fast-deep-equal "^3.1.1"
json-schema-traverse "^1.0.0"
@@ -718,16 +732,6 @@
json-schema-traverse "^0.4.1"
uri-js "^4.2.2"
-ajv@^8.0.0:
- version "8.9.0"
- resolved "https://registry.yarnpkg.com/ajv/-/ajv-8.9.0.tgz#738019146638824dea25edcf299dcba1b0e7eb18"
- integrity sha512-qOKJyNj/h+OWx7s5DePL6Zu1KeM9jPZhwBqs+7DzP6bGOvqzVCSf0xueYmVuaC/oQ/VtS2zLMLHdQFbkka+XDQ==
- dependencies:
- fast-deep-equal "^3.1.1"
- json-schema-traverse "^1.0.0"
- require-from-string "^2.0.2"
- uri-js "^4.2.2"
-
ansi-colors@4.1.1:
version "4.1.1"
resolved "https://registry.yarnpkg.com/ansi-colors/-/ansi-colors-4.1.1.tgz#cbb9ae256bf750af1eab344f229aa27fe94ba348"
@@ -953,7 +957,7 @@
resolved "https://registry.yarnpkg.com/bytes/-/bytes-3.1.1.tgz#3f018291cb4cbad9accb6e6970bca9c8889e879a"
integrity sha512-dWe4nWO/ruEOY7HkUJ5gFt1DCFV9zPRoJr8pV0/ASQermOZjtq8jMjOprC0Kd10GLN+l7xaUPvxzJFWtxGu8Fg==
-cacache@^15.0.5, cacache@^15.2.0:
+cacache@^15.0.5, cacache@^15.2.0, cacache@^15.3.0:
version "15.3.0"
resolved "https://registry.yarnpkg.com/cacache/-/cacache-15.3.0.tgz#dc85380fb2f556fe3dda4c719bfa0ec875a7f1eb"
integrity sha512-VVdYzXEn+cnbXpFgWs5hTT7OScegHVmLhJIR8Ufqk3iFD6A6j5iSX1KuBTfNEv4tdJWE2PzA6IVFtcLC7fN9wQ==
@@ -1357,7 +1361,7 @@
resolved "https://registry.yarnpkg.com/encodeurl/-/encodeurl-1.0.2.tgz#ad3ff4c86ec2d029322f5a02c3a9a606c95b3f59"
integrity sha1-rT/0yG7C0CkyL1oCw6mmBslbP1k=
-encoding@^0.1.12:
+encoding@^0.1.12, encoding@^0.1.13:
version "0.1.13"
resolved "https://registry.yarnpkg.com/encoding/-/encoding-0.1.13.tgz#56574afdd791f54a8e9b2785c0582a2d26210fa9"
integrity sha512-ETBauow1T35Y/WZMkio9jiM0Z5xjHHmJ4XmjZOq1l/dXz3lr2sRn87nJy20RupqSh1F2m3HHPSp8ShIPQJrJ3A==
@@ -1725,6 +1729,15 @@
agent-base "6"
debug "4"
+http-proxy-agent@^5.0.0:
+ version "5.0.0"
+ resolved "https://registry.yarnpkg.com/http-proxy-agent/-/http-proxy-agent-5.0.0.tgz#5129800203520d434f142bc78ff3c170800f2b43"
+ integrity sha512-n2hY8YdoRE1i7r6M0w9DIw5GgZN0G25P8zLCRQ8rjXtTU3vsNFBI/vWK/UIeE6g5MUUz6avwAPXmL6Fy9D/90w==
+ dependencies:
+ "@tootallnate/once" "2"
+ agent-base "6"
+ debug "4"
+
http-proxy@^1.18.1:
version "1.18.1"
resolved "https://registry.yarnpkg.com/http-proxy/-/http-proxy-1.18.1.tgz#401541f0534884bbf95260334e72f88ee3976549"
@@ -1867,7 +1880,7 @@
dependencies:
binary-extensions "^2.0.0"
-is-core-module@^2.2.0, is-core-module@^2.8.0:
+is-core-module@^2.8.0, is-core-module@^2.8.1:
version "2.8.1"
resolved "https://registry.yarnpkg.com/is-core-module/-/is-core-module-2.8.1.tgz#f59fdfca701d5879d0a6b100a40aa1560ce27211"
integrity sha512-SdNCUs284hr40hFTFP6l0IfZ/RSrMXF3qgoRHd3/79unUTvrFO/JoXwkGm+5J/Oe3E/b5GsnG330uUNgRpu1PA==
@@ -1977,16 +1990,16 @@
resolved "https://registry.yarnpkg.com/jasmine-core/-/jasmine-core-3.99.0.tgz#99a3da0d38ba2de82614d9198b7b1bc1c32a5960"
integrity sha512-+ZDaJlEfRopINQqgE+hvzRyDIQDeKfqqTvF8RzXsvU1yE3pBDRud2+Qfh9WvGgRpuzqxyQJVI6Amy5XQ11r/3w==
-jasmine-core@^4.0.0:
- version "4.0.0"
- resolved "https://registry.yarnpkg.com/jasmine-core/-/jasmine-core-4.0.0.tgz#8299ed38a100c47a1d154af63449a40967a7be5c"
- integrity sha512-tq24OCqHElgU9KDpb/8O21r1IfotgjIzalfW9eCmRR40LZpvwXT68iariIyayMwi0m98RDt16aljdbwK0sBMmQ==
-
jasmine-core@~2.8.0:
version "2.8.0"
resolved "https://registry.yarnpkg.com/jasmine-core/-/jasmine-core-2.8.0.tgz#bcc979ae1f9fd05701e45e52e65d3a5d63f1a24e"
integrity sha1-vMl5rh+f0FcB5F5S5l06XWPxok4=
+jasmine-core@~3.10.0:
+ version "3.10.1"
+ resolved "https://registry.yarnpkg.com/jasmine-core/-/jasmine-core-3.10.1.tgz#7aa6fa2b834a522315c651a128d940eca553989a"
+ integrity sha512-ooZWSDVAdh79Rrj4/nnfklL3NQVra0BcuhcuWoAwwi+znLDoUeH87AFfeX8s+YeYi6xlv5nveRyaA1v7CintfA==
+
jasmine@2.8.0:
version "2.8.0"
resolved "https://registry.yarnpkg.com/jasmine/-/jasmine-2.8.0.tgz#6b089c0a11576b1f16df11b80146d91d4e8b8a3e"
@@ -1996,13 +2009,13 @@
glob "^7.0.6"
jasmine-core "~2.8.0"
-jasmine@latest:
- version "4.0.2"
- resolved "https://registry.yarnpkg.com/jasmine/-/jasmine-4.0.2.tgz#6f5ff7fbf6b67f56600235fdb7d299ac52876c4b"
- integrity sha512-YsrgxJQEggxzByYe4j68eQLOiQeSrPDYGv4sHhGBp3c6HHdq+uPXeAQ73kOAQpdLZ3/0zN7x/TZTloqeE1/qIA==
+jasmine@3.10.0:
+ version "3.10.0"
+ resolved "https://registry.yarnpkg.com/jasmine/-/jasmine-3.10.0.tgz#acd3cd560a9d20d8fdad6bd2dd05867d188503f3"
+ integrity sha512-2Y42VsC+3CQCTzTwJezOvji4qLORmKIE0kwowWC+934Krn6ZXNQYljiwK5st9V3PVx96BSiDYXSB60VVah3IlQ==
dependencies:
glob "^7.1.6"
- jasmine-core "^4.0.0"
+ jasmine-core "~3.10.0"
jasminewd2@^2.1.0:
version "2.2.0"
@@ -2095,14 +2108,14 @@
readable-stream "~2.3.6"
set-immediate-shim "~1.0.1"
-karma-chrome-launcher@latest:
+karma-chrome-launcher@3.1.0:
version "3.1.0"
resolved "https://registry.yarnpkg.com/karma-chrome-launcher/-/karma-chrome-launcher-3.1.0.tgz#805a586799a4d05f4e54f72a204979f3f3066738"
integrity sha512-3dPs/n7vgz1rxxtynpzZTvb9y/GIaW8xjAwcIGttLbycqoFtI7yo1NGnQi6oFTherRE+GIhCAHZC4vEqWGhNvg==
dependencies:
which "^1.2.1"
-karma-firefox-launcher@latest:
+karma-firefox-launcher@2.1.2:
version "2.1.2"
resolved "https://registry.yarnpkg.com/karma-firefox-launcher/-/karma-firefox-launcher-2.1.2.tgz#9a38cc783c579a50f3ed2a82b7386186385cfc2d"
integrity sha512-VV9xDQU1QIboTrjtGVD4NCfzIH7n01ZXqy/qpBhnOeGVOkG5JYPEm8kuSd7psHE6WouZaQ9Ool92g8LFweSNMA==
@@ -2110,29 +2123,29 @@
is-wsl "^2.2.0"
which "^2.0.1"
-karma-jasmine@latest:
+karma-jasmine@4.0.1:
version "4.0.1"
resolved "https://registry.yarnpkg.com/karma-jasmine/-/karma-jasmine-4.0.1.tgz#b99e073b6d99a5196fc4bffc121b89313b0abd82"
integrity sha512-h8XDAhTiZjJKzfkoO1laMH+zfNlra+dEQHUAjpn5JV1zCPtOIVWGQjLBrqhnzQa/hrU2XrZwSyBa6XjEBzfXzw==
dependencies:
jasmine-core "^3.6.0"
-karma-requirejs@latest:
+karma-requirejs@1.1.0:
version "1.1.0"
resolved "https://registry.yarnpkg.com/karma-requirejs/-/karma-requirejs-1.1.0.tgz#fddae2cb87d7ebc16fb0222893564d7fee578798"
integrity sha1-/driy4fX68FvsCIok1ZNf+5Xh5g=
-karma-sourcemap-loader@latest:
+karma-sourcemap-loader@0.3.8:
version "0.3.8"
resolved "https://registry.yarnpkg.com/karma-sourcemap-loader/-/karma-sourcemap-loader-0.3.8.tgz#d4bae72fb7a8397328a62b75013d2df937bdcf9c"
integrity sha512-zorxyAakYZuBcHRJE+vbrK2o2JXLFWK8VVjiT/6P+ltLBUGUvqTEkUiQ119MGdOrK7mrmxXHZF1/pfT6GgIZ6g==
dependencies:
graceful-fs "^4.1.2"
-karma@latest:
- version "6.3.11"
- resolved "https://registry.yarnpkg.com/karma/-/karma-6.3.11.tgz#2c2fb09f1a9f52e1a0739adeedace2a68d4c0d34"
- integrity sha512-QGUh4yXgizzDNPLB5nWTvP+wysKexngbyLVWFOyikB661hpa2RZLf5anZQzqliWtAQuYVep0ot0D1U7UQKpsxQ==
+karma@6.3.12:
+ version "6.3.12"
+ resolved "https://registry.yarnpkg.com/karma/-/karma-6.3.12.tgz#fe6347f027385fc16da1a9bb87d766e2d25981c6"
+ integrity sha512-qwIG+oB2YmHx4hjvYSRMNzL3YWAJ9baHaLAxiP7biFNkfpwYTUTtPck0joFpucalNLzMr+7z/FX1uY/kl8DV9A==
dependencies:
body-parser "^1.19.0"
braces "^3.0.2"
@@ -2208,6 +2221,11 @@
dependencies:
yallist "^4.0.0"
+lru-cache@^7.4.0:
+ version "7.4.1"
+ resolved "https://registry.yarnpkg.com/lru-cache/-/lru-cache-7.4.1.tgz#afe07e885ef0cd5bf99f62f4fa7545d48746d779"
+ integrity sha512-NCD7/WRlFmADccuHjsRUYqdluYBr//n/O0fesCb/n52FoGcgKh8o4Dpm7YIbZwVcDs8rPBQbCZLmWWsp6m+xGQ==
+
magic-string@0.25.7, magic-string@^0.25.0:
version "0.25.7"
resolved "https://registry.yarnpkg.com/magic-string/-/magic-string-0.25.7.tgz#3f497d6fd34c669c6798dcb821f2ef31f5445051"
@@ -2223,7 +2241,29 @@
pify "^4.0.1"
semver "^5.6.0"
-make-fetch-happen@^9.0.1, make-fetch-happen@^9.1.0:
+make-fetch-happen@^10.0.1:
+ version "10.0.4"
+ resolved "https://registry.yarnpkg.com/make-fetch-happen/-/make-fetch-happen-10.0.4.tgz#309823c7a2b4c947465274220e169112c977b94f"
+ integrity sha512-CiReW6usy3UXby5N46XjWfLPFPq1glugCszh18I0NYJCwr129ZAx9j3Dlv+cRsK0q3VjlVysEzhdtdw2+NhdYA==
+ dependencies:
+ agentkeepalive "^4.2.1"
+ cacache "^15.3.0"
+ http-cache-semantics "^4.1.0"
+ http-proxy-agent "^5.0.0"
+ https-proxy-agent "^5.0.0"
+ is-lambda "^1.0.1"
+ lru-cache "^7.4.0"
+ minipass "^3.1.6"
+ minipass-collect "^1.0.2"
+ minipass-fetch "^2.0.1"
+ minipass-flush "^1.0.5"
+ minipass-pipeline "^1.2.4"
+ negotiator "^0.6.3"
+ promise-retry "^2.0.1"
+ socks-proxy-agent "^6.1.1"
+ ssri "^8.0.1"
+
+make-fetch-happen@^9.1.0:
version "9.1.0"
resolved "https://registry.yarnpkg.com/make-fetch-happen/-/make-fetch-happen-9.1.0.tgz#53085a09e7971433e6765f7971bf63f4e05cb968"
integrity sha512-+zopwDy7DNknmwPQplem5lAZX/eCOzSvSNNcSKm5eVwTkOBzoktEfXsa9L23J/GIRhxRsaxzkPEhrJEpE2F4Gg==
@@ -2291,7 +2331,7 @@
dependencies:
minipass "^3.0.0"
-minipass-fetch@^1.3.0, minipass-fetch@^1.3.2:
+minipass-fetch@^1.3.2, minipass-fetch@^1.4.1:
version "1.4.1"
resolved "https://registry.yarnpkg.com/minipass-fetch/-/minipass-fetch-1.4.1.tgz#d75e0091daac1b0ffd7e9d41629faff7d0c1f1b6"
integrity sha512-CGH1eblLq26Y15+Azk7ey4xh0J/XfJfrCox5LDJiKqI2Q2iwOLOKrlmIaODiSQS8d18jalF6y2K2ePUm0CmShw==
@@ -2302,6 +2342,17 @@
optionalDependencies:
encoding "^0.1.12"
+minipass-fetch@^2.0.1:
+ version "2.0.2"
+ resolved "https://registry.yarnpkg.com/minipass-fetch/-/minipass-fetch-2.0.2.tgz#5ea5fb9a2e24ccd3cfb489563540bb4024fc6c31"
+ integrity sha512-M63u5yWX0yxY1C3DcLVY1xWai0pNM3qa1xCMXFgdejY5F/NTmyzNVHGcBxKerX51lssqxwWWTjpg/ZPuD39gOQ==
+ dependencies:
+ minipass "^3.1.6"
+ minipass-sized "^1.0.3"
+ minizlib "^2.1.2"
+ optionalDependencies:
+ encoding "^0.1.13"
+
minipass-flush@^1.0.5:
version "1.0.5"
resolved "https://registry.yarnpkg.com/minipass-flush/-/minipass-flush-1.0.5.tgz#82e7135d7e89a50ffe64610a787953c4c4cbb373"
@@ -2331,14 +2382,14 @@
dependencies:
minipass "^3.0.0"
-minipass@^3.0.0, minipass@^3.1.0, minipass@^3.1.1, minipass@^3.1.3:
+minipass@^3.0.0, minipass@^3.1.0, minipass@^3.1.1, minipass@^3.1.3, minipass@^3.1.6:
version "3.1.6"
resolved "https://registry.yarnpkg.com/minipass/-/minipass-3.1.6.tgz#3b8150aa688a711a1521af5e8779c1d3bb4f45ee"
integrity sha512-rty5kpw9/z8SX9dmxblFA6edItUmwJgMeYDZRrwlIVN27i8gysGbznJwUggw2V/FVqFSDdWy040ZPS811DYAqQ==
dependencies:
yallist "^4.0.0"
-minizlib@^2.0.0, minizlib@^2.1.1:
+minizlib@^2.0.0, minizlib@^2.1.1, minizlib@^2.1.2:
version "2.1.2"
resolved "https://registry.yarnpkg.com/minizlib/-/minizlib-2.1.2.tgz#e90d3466ba209b932451508a11ce3d3632145931"
integrity sha512-bAxsR8BVfj60DWXHE3u30oHzfl4G7khkSuPW+qvpd7jFRHm7dLxOjUk1EHACJ/hxLY8phGJ0YhYHZo7jil7Qdg==
@@ -2376,6 +2427,11 @@
resolved "https://registry.yarnpkg.com/negotiator/-/negotiator-0.6.2.tgz#feacf7ccf525a77ae9634436a64883ffeca346fb"
integrity sha512-hZXc7K2e+PgeI1eDBe/10Ard4ekbfrrqG8Ep+8Jmf4JID2bNg7NvCPOZN+kfF574pFQI7mum2AUqDidoKqcTOw==
+negotiator@^0.6.3:
+ version "0.6.3"
+ resolved "https://registry.yarnpkg.com/negotiator/-/negotiator-0.6.3.tgz#58e323a72fedc0d6f9cd4d31fe49f51479590ccd"
+ integrity sha512-+EUsqGPLsM+j/zdChZjsnX51g4XrHFOIXwfnCVPGlQk/k5giakcKsuxCObBRu6DSm9opw/O6slWbJdghQM4bBg==
+
node-gyp@^8.2.0:
version "8.4.1"
resolved "https://registry.yarnpkg.com/node-gyp/-/node-gyp-8.4.1.tgz#3d49308fc31f768180957d6b5746845fbd429937"
@@ -2428,7 +2484,7 @@
resolved "https://registry.yarnpkg.com/npm-normalize-package-bin/-/npm-normalize-package-bin-1.0.1.tgz#6e79a41f23fd235c0623218228da7d9c23b8f6e2"
integrity sha512-EPfafl6JL5/rU+ot6P3gRSCpPDW5VmIzX959Ob1+ySFUuuYHWHekXpwdUZcKP5C+DS4GEtdJluwBjnsNDl+fSA==
-npm-package-arg@8.1.5, npm-package-arg@^8.0.0, npm-package-arg@^8.0.1, npm-package-arg@^8.1.2:
+npm-package-arg@8.1.5, npm-package-arg@^8.0.1, npm-package-arg@^8.1.2, npm-package-arg@^8.1.5:
version "8.1.5"
resolved "https://registry.yarnpkg.com/npm-package-arg/-/npm-package-arg-8.1.5.tgz#3369b2d5fe8fdc674baa7f1786514ddc15466e44"
integrity sha512-LhgZrg0n0VgvzVdSm1oiZworPbTxYHUJCgtsJW8mGvlDpxTM1vSJc3m5QZeUkhAHIzbz3VCHd/R4osi1L1Tg/Q==
@@ -2457,17 +2513,17 @@
npm-package-arg "^8.1.2"
semver "^7.3.4"
-npm-registry-fetch@^11.0.0:
- version "11.0.0"
- resolved "https://registry.yarnpkg.com/npm-registry-fetch/-/npm-registry-fetch-11.0.0.tgz#68c1bb810c46542760d62a6a965f85a702d43a76"
- integrity sha512-jmlgSxoDNuhAtxUIG6pVwwtz840i994dL14FoNVZisrmZW5kWd63IUTNv1m/hyRSGSqWjCUp/YZlS1BJyNp9XA==
+npm-registry-fetch@^12.0.0:
+ version "12.0.2"
+ resolved "https://registry.yarnpkg.com/npm-registry-fetch/-/npm-registry-fetch-12.0.2.tgz#ae583bb3c902a60dae43675b5e33b5b1f6159f1e"
+ integrity sha512-Df5QT3RaJnXYuOwtXBXS9BWs+tHH2olvkCLh6jcR/b/u3DvPMlp3J0TvvYwplPKxHMOwfg287PYih9QqaVFoKA==
dependencies:
- make-fetch-happen "^9.0.1"
- minipass "^3.1.3"
- minipass-fetch "^1.3.0"
+ make-fetch-happen "^10.0.1"
+ minipass "^3.1.6"
+ minipass-fetch "^1.4.1"
minipass-json-stream "^1.0.1"
- minizlib "^2.0.0"
- npm-package-arg "^8.0.0"
+ minizlib "^2.1.2"
+ npm-package-arg "^8.1.5"
npmlog@^6.0.0:
version "6.0.0"
@@ -2565,10 +2621,10 @@
resolved "https://registry.yarnpkg.com/p-try/-/p-try-2.2.0.tgz#cb2868540e313d61de58fafbe35ce9004d5540e6"
integrity sha512-R4nPAVTAU0B9D35/Gk3uJf/7XYbQcyohSKdvAxIRSNghFl4e71hVoGnBNQz9cWaXxO2I10KTC+3jMdvvoKw6dQ==
-pacote@12.0.2:
- version "12.0.2"
- resolved "https://registry.yarnpkg.com/pacote/-/pacote-12.0.2.tgz#14ae30a81fe62ec4fc18c071150e6763e932527c"
- integrity sha512-Ar3mhjcxhMzk+OVZ8pbnXdb0l8+pimvlsqBGRNkble2NVgyqOGE3yrCGi/lAYq7E7NRDMz89R1Wx5HIMCGgeYg==
+pacote@12.0.3:
+ version "12.0.3"
+ resolved "https://registry.yarnpkg.com/pacote/-/pacote-12.0.3.tgz#b6f25868deb810e7e0ddf001be88da2bcaca57c7"
+ integrity sha512-CdYEl03JDrRO3x18uHjBYA9TyoW8gy+ThVcypcDkxPtKlw76e4ejhYB6i9lJ+/cebbjpqPW/CijjqxwDTts8Ow==
dependencies:
"@npmcli/git" "^2.1.0"
"@npmcli/installed-package-contents" "^1.0.6"
@@ -2583,7 +2639,7 @@
npm-package-arg "^8.0.1"
npm-packlist "^3.0.0"
npm-pick-manifest "^6.0.0"
- npm-registry-fetch "^11.0.0"
+ npm-registry-fetch "^12.0.0"
promise-retry "^2.0.1"
read-package-json-fast "^2.0.1"
rimraf "^3.0.2"
@@ -2615,7 +2671,7 @@
resolved "https://registry.yarnpkg.com/path-is-inside/-/path-is-inside-1.0.2.tgz#365417dede44430d1c11af61027facf074bdfc53"
integrity sha1-NlQX3t5EQw0cEa9hAn+s8HS9/FM=
-path-parse@^1.0.6, path-parse@^1.0.7:
+path-parse@^1.0.7:
version "1.0.7"
resolved "https://registry.yarnpkg.com/path-parse/-/path-parse-1.0.7.tgz#fbc114b60ca42b30d9daf5858e4bd68bbedb6735"
integrity sha512-LDJzPVEEEPR+y48z93A0Ed0yXb8pAByGWo/k5YYdYgpY2/2EsOsksJrq7lOHxryrVOn1ejG6oAp8ahvOIQD8sw==
@@ -2694,7 +2750,7 @@
"@types/node" "^10.1.0"
long "^4.0.0"
-protractor@latest:
+protractor@7.0.0:
version "7.0.0"
resolved "https://registry.yarnpkg.com/protractor/-/protractor-7.0.0.tgz#c3e263608bd72e2c2dc802b11a772711a4792d03"
integrity sha512-UqkFjivi4GcvUQYzqGYNe0mLzfn5jiLmO8w9nMhQoJRLhy2grJonpga2IWhI6yJO30LibWXJJtA4MOIZD2GgZw==
@@ -2848,7 +2904,7 @@
resolved "https://registry.yarnpkg.com/require-main-filename/-/require-main-filename-2.0.0.tgz#d0b329ecc7cc0f61649f62215be69af54aa8989b"
integrity sha512-NKN5kMDylKuldxYLSUfrbo5Tuzh4hd+2E8NPPX02mZtn1VuREQToYe/ZdlJy+J3uCpfaiGF05e7B8W0iXbQHmg==
-requirejs@latest:
+requirejs@2.3.6:
version "2.3.6"
resolved "https://registry.yarnpkg.com/requirejs/-/requirejs-2.3.6.tgz#e5093d9601c2829251258c0b9445d4d19fa9e7c9"
integrity sha512-ipEzlWQe6RK3jkzikgCupiTbTvm4S0/CAU5GlgptkN5SO6F3u0UD0K18wy6ErDqiCyP4J4YYe1HuAShvsxePLg==
@@ -2858,13 +2914,14 @@
resolved "https://registry.yarnpkg.com/requires-port/-/requires-port-1.0.0.tgz#925d2601d39ac485e091cf0da5c6e694dc3dcaff"
integrity sha1-kl0mAdOaxIXgkc8NpcbmlNw9yv8=
-resolve@1.20.0:
- version "1.20.0"
- resolved "https://registry.yarnpkg.com/resolve/-/resolve-1.20.0.tgz#629a013fb3f70755d6f0b7935cc1c2c5378b1975"
- integrity sha512-wENBPt4ySzg4ybFQW2TT1zMQucPK95HSh/nq2CFTZVOGut2+pQvSsgtda4d26YrYcr067wjbmzOG8byDPBX63A==
+resolve@1.22.0:
+ version "1.22.0"
+ resolved "https://registry.yarnpkg.com/resolve/-/resolve-1.22.0.tgz#5e0b8c67c15df57a89bdbabe603a002f21731198"
+ integrity sha512-Hhtrw0nLeSrFQ7phPp4OOcVjLPIeMnRlr5mcnVuMe7M/7eBn98A3hmFRLoFo3DLZkivSYwhRUJTyPyWAk56WLw==
dependencies:
- is-core-module "^2.2.0"
- path-parse "^1.0.6"
+ is-core-module "^2.8.1"
+ path-parse "^1.0.7"
+ supports-preserve-symlinks-flag "^1.0.0"
resolve@^1.19.0:
version "1.21.0"
@@ -2907,10 +2964,10 @@
dependencies:
glob "^7.1.3"
-rollup@latest:
- version "2.64.0"
- resolved "https://registry.yarnpkg.com/rollup/-/rollup-2.64.0.tgz#f0f59774e21fbb56de438a37d06a2189632b207a"
- integrity sha512-+c+lbw1lexBKSMb1yxGDVfJ+vchJH3qLbmavR+awDinTDA2C5Ug9u7lkOzj62SCu0PKUExsW36tpgW7Fmpn3yQ==
+rollup@2.66.1:
+ version "2.66.1"
+ resolved "https://registry.yarnpkg.com/rollup/-/rollup-2.66.1.tgz#366b0404de353c4331d538c3ad2963934fcb4937"
+ integrity sha512-crSgLhSkLMnKr4s9iZ/1qJCplgAgrRY+igWv8KhG/AjKOJ0YX/WpmANyn8oxrw+zenF3BXWDLa7Xl/QZISH+7w==
optionalDependencies:
fsevents "~2.3.2"
@@ -3048,7 +3105,7 @@
socket.io-adapter "~2.3.3"
socket.io-parser "~4.0.4"
-socks-proxy-agent@^6.0.0:
+socks-proxy-agent@^6.0.0, socks-proxy-agent@^6.1.1:
version "6.1.1"
resolved "https://registry.yarnpkg.com/socks-proxy-agent/-/socks-proxy-agent-6.1.1.tgz#e664e8f1aaf4e1fb3df945f09e3d94f911137f87"
integrity sha512-t8J0kG3csjA4g6FTbsMOWws+7R7vuRC8aQ/wy3/1OWmsgwA68zs/+cExQ0koSitUDXqhufF/YJr9wtNMZHw5Ew==
@@ -3221,7 +3278,7 @@
mkdirp "^1.0.3"
yallist "^4.0.0"
-terser@latest:
+terser@5.10.0:
version "5.10.0"
resolved "https://registry.yarnpkg.com/terser/-/terser-5.10.0.tgz#b86390809c0389105eb0a0b62397563096ddafcc"
integrity sha512-AMmF99DMfEDiRJfxfY5jj5wNH/bYO09cniSqhfoyxc8sFoYIgkJy86G04UoZU5VjlpnplVu0K6Tx6E9b5+DlHA==
@@ -3327,10 +3384,10 @@
media-typer "0.3.0"
mime-types "~2.1.24"
-typescript@latest:
- version "4.5.4"
- resolved "https://registry.yarnpkg.com/typescript/-/typescript-4.5.4.tgz#a17d3a0263bf5c8723b9c52f43c5084edf13c2e8"
- integrity sha512-VgYs2A2QIRuGphtzFV7aQJduJ2gyfTljngLzjpfW9FoYZF6xuw1W0vW9ghCKLfcWrCFxK81CSGRAvS1pn4fIUg==
+typescript@4.5.5:
+ version "4.5.5"
+ resolved "https://registry.yarnpkg.com/typescript/-/typescript-4.5.5.tgz#d8c953832d28924a9e3d37c73d729c846c5896f3"
+ integrity sha512-TCTIul70LyWe6IJWT8QSYeA54WQe8EjQFU4wY52Fasj5UKx88LNYKCgBEHcOMOrFF1rKGbD8v/xcNWVUq9SymA==
ua-parser-js@^0.7.30:
version "0.7.31"