Merge "Create a function to populate a SZSDPS goal"
diff --git a/BUILD b/BUILD
index 2c99188..219495d 100644
--- a/BUILD
+++ b/BUILD
@@ -52,6 +52,8 @@
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_notes_response //scouting/webserver/requests/messages:submit_notes_response_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_2023_data_scouting_response //scouting/webserver/requests/messages:request_2023_data_scouting_response_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_2023_data_scouting //scouting/webserver/requests/messages:request_2023_data_scouting_go_fbs
+# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_2024_data_scouting_response //scouting/webserver/requests/messages:request_2024_data_scouting_response_go_fbs
+# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_2024_data_scouting //scouting/webserver/requests/messages:request_2024_data_scouting_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_matches_for_team_response //scouting/webserver/requests/messages:request_matches_for_team_response_go_fbs
# 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_notes_for_team_response //scouting/webserver/requests/messages:request_notes_for_team_response_go_fbs
@@ -68,12 +70,16 @@
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_shift_schedule_response //scouting/webserver/requests/messages:request_shift_schedule_response_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_actions //scouting/webserver/requests/messages:submit_actions_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_actions_response //scouting/webserver/requests/messages:submit_actions_response_go_fbs
+# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_2024_actions //scouting/webserver/requests/messages:submit_2024_actions_go_fbs
+# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_2024_actions_response //scouting/webserver/requests/messages:submit_2024_actions_response_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_shift_schedule //scouting/webserver/requests/messages:submit_shift_schedule_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_shift_schedule_response //scouting/webserver/requests/messages:submit_shift_schedule_response_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_driver_ranking //scouting/webserver/requests/messages:submit_driver_ranking_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_driver_ranking_response //scouting/webserver/requests/messages:submit_driver_ranking_response_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/delete_2023_data_scouting //scouting/webserver/requests/messages:delete_2023_data_scouting_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/delete_2023_data_scouting_response //scouting/webserver/requests/messages:delete_2023_data_scouting_response_go_fbs
+# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/delete_2024_data_scouting //scouting/webserver/requests/messages:delete_2024_data_scouting_go_fbs
+# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/delete_2024_data_scouting_response //scouting/webserver/requests/messages:delete_2024_data_scouting_response_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_pit_image //scouting/webserver/requests/messages:submit_pit_image_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_pit_image_response //scouting/webserver/requests/messages:submit_pit_image_response_go_fbs
# gazelle:resolve go github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_pit_images //scouting/webserver/requests/messages:request_pit_images_go_fbs
diff --git a/aos/actions/actions.h b/aos/actions/actions.h
index 1b5d607..f60f20b 100644
--- a/aos/actions/actions.h
+++ b/aos/actions/actions.h
@@ -14,9 +14,7 @@
#include "aos/json_to_flatbuffer.h"
#include "aos/logging/logging.h"
-namespace aos {
-namespace common {
-namespace actions {
+namespace aos::common::actions {
class Action;
@@ -407,8 +405,6 @@
}
}
-} // namespace actions
-} // namespace common
-} // namespace aos
+} // namespace aos::common::actions
#endif // AOS_ACTIONS_ACTIONS_H_
diff --git a/aos/actions/actor.h b/aos/actions/actor.h
index a689af9..f7066fc 100644
--- a/aos/actions/actor.h
+++ b/aos/actions/actor.h
@@ -12,9 +12,7 @@
#include "aos/time/time.h"
#include "aos/util/phased_loop.h"
-namespace aos {
-namespace common {
-namespace actions {
+namespace aos::common::actions {
constexpr monotonic_clock::duration kLoopFrequency =
std::chrono::milliseconds(5);
@@ -227,8 +225,6 @@
return ans;
}
-} // namespace actions
-} // namespace common
-} // namespace aos
+} // namespace aos::common::actions
#endif // AOS_ACTIONS_ACTOR_H_
diff --git a/aos/analysis/BUILD b/aos/analysis/BUILD
new file mode 100644
index 0000000..63f2d57
--- /dev/null
+++ b/aos/analysis/BUILD
@@ -0,0 +1,108 @@
+load("//aos/flatbuffers:generate.bzl", "static_flatbuffer")
+load("//tools/build_rules:js.bzl", "ts_project")
+load("@com_github_google_flatbuffers//:typescript.bzl", "flatbuffer_ts_library")
+load("//aos:config.bzl", "aos_config")
+
+package(default_visibility = ["//visibility:public"])
+
+cc_binary(
+ name = "py_log_reader.so",
+ srcs = ["py_log_reader.cc"],
+ linkshared = True,
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ "//aos:configuration",
+ "//aos:json_to_flatbuffer",
+ "//aos/events:shm_event_loop",
+ "//aos/events:simulated_event_loop",
+ "//aos/events/logging:log_reader",
+ "//third_party/python",
+ "@com_github_google_glog//:glog",
+ ],
+)
+
+py_test(
+ name = "log_reader_test",
+ srcs = ["log_reader_test.py"],
+ data = [
+ ":py_log_reader.so",
+ "@sample_logfile//file",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = ["//aos:configuration_fbs_python"],
+)
+
+static_flatbuffer(
+ name = "plot_data_fbs",
+ srcs = [
+ "plot_data.fbs",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+)
+
+flatbuffer_ts_library(
+ name = "plot_data_ts_fbs",
+ srcs = [
+ "plot_data.fbs",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+)
+
+ts_project(
+ name = "plot_data_utils",
+ srcs = ["plot_data_utils.ts"],
+ visibility = ["//visibility:public"],
+ deps = [
+ ":plot_data_ts_fbs",
+ "//aos:configuration_ts_fbs",
+ "//aos/network/www:aos_plotter",
+ "//aos/network/www:plotter",
+ "//aos/network/www:proxy",
+ "@com_github_google_flatbuffers//reflection:reflection_ts_fbs",
+ "@com_github_google_flatbuffers//ts:flatbuffers_ts",
+ ],
+)
+
+aos_config(
+ name = "plotter",
+ src = "plotter_config.json",
+ flatbuffers = [":plot_data_fbs"],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = ["//aos/events:aos_config"],
+)
+
+cc_library(
+ name = "in_process_plotter",
+ srcs = ["in_process_plotter.cc"],
+ hdrs = ["in_process_plotter.h"],
+ data = [
+ ":plotter",
+ "//aos/analysis/cpp_plot:cpp_plot_files",
+ ],
+ deps = [
+ ":plot_data_fbs",
+ "//aos/events:simulated_event_loop",
+ "//aos/network:web_proxy",
+ ],
+)
+
+cc_binary(
+ name = "in_process_plotter_demo",
+ srcs = ["in_process_plotter_demo.cc"],
+ deps = [
+ ":in_process_plotter",
+ "//aos:init",
+ ],
+)
+
+cc_binary(
+ name = "local_foxglove",
+ srcs = ["local_foxglove.cc"],
+ data = ["@foxglove_studio"],
+ deps = [
+ "//aos:init",
+ "//aos/network:gen_embedded",
+ "//aos/seasocks:seasocks_logger",
+ "//third_party/seasocks",
+ ],
+)
diff --git a/frc971/analysis/cpp_plot/BUILD b/aos/analysis/cpp_plot/BUILD
similarity index 94%
rename from frc971/analysis/cpp_plot/BUILD
rename to aos/analysis/cpp_plot/BUILD
index 7f34afe..7286aaf 100644
--- a/frc971/analysis/cpp_plot/BUILD
+++ b/aos/analysis/cpp_plot/BUILD
@@ -8,8 +8,8 @@
target_compatible_with = ["@platforms//os:linux"],
deps = [
"//aos:configuration_ts_fbs",
+ "//aos/analysis:plot_data_utils",
"//aos/network/www:proxy",
- "//frc971/analysis:plot_data_utils",
],
)
diff --git a/frc971/analysis/cpp_plot/cpp_plot.ts b/aos/analysis/cpp_plot/cpp_plot.ts
similarity index 100%
rename from frc971/analysis/cpp_plot/cpp_plot.ts
rename to aos/analysis/cpp_plot/cpp_plot.ts
diff --git a/frc971/analysis/cpp_plot/index.html b/aos/analysis/cpp_plot/index.html
similarity index 100%
rename from frc971/analysis/cpp_plot/index.html
rename to aos/analysis/cpp_plot/index.html
diff --git a/frc971/analysis/in_process_plotter.cc b/aos/analysis/in_process_plotter.cc
similarity index 95%
rename from frc971/analysis/in_process_plotter.cc
rename to aos/analysis/in_process_plotter.cc
index b537aa4..88591b3 100644
--- a/frc971/analysis/in_process_plotter.cc
+++ b/aos/analysis/in_process_plotter.cc
@@ -1,12 +1,12 @@
-#include "frc971/analysis/in_process_plotter.h"
+#include "aos/analysis/in_process_plotter.h"
#include "aos/configuration.h"
-namespace frc971::analysis {
+namespace aos::analysis {
namespace {
-const char *kDataPath = "frc971/analysis/cpp_plot";
-const char *kConfigPath = "frc971/analysis/plotter.json";
+const char *kDataPath = "aos/analysis/cpp_plot";
+const char *kConfigPath = "aos/analysis/plotter.json";
} // namespace
Plotter::Plotter()
@@ -167,4 +167,4 @@
next_top_ = 0;
}
-} // namespace frc971::analysis
+} // namespace aos::analysis
diff --git a/frc971/analysis/in_process_plotter.h b/aos/analysis/in_process_plotter.h
similarity index 91%
rename from frc971/analysis/in_process_plotter.h
rename to aos/analysis/in_process_plotter.h
index 6dab308..0d00deb 100644
--- a/frc971/analysis/in_process_plotter.h
+++ b/aos/analysis/in_process_plotter.h
@@ -1,14 +1,13 @@
-#ifndef FRC971_ANALYSIS_IN_PROCESS_PLOTTER_H_
-#define FRC971_ANALYSIS_IN_PROCESS_PLOTTER_H_
+#ifndef AOS_ANALYSIS_IN_PROCESS_PLOTTER_H_
+#define AOS_ANALYSIS_IN_PROCESS_PLOTTER_H_
#include <vector>
+#include "aos/analysis/plot_data_generated.h"
#include "aos/events/simulated_event_loop.h"
#include "aos/network/web_proxy.h"
-#include "frc971/analysis/plot_data_generated.h"
-namespace frc971 {
-namespace analysis {
+namespace aos::analysis {
// This class wraps the WebProxy class to provide a convenient C++ interface to
// dynamically generate plots.
@@ -96,6 +95,5 @@
std::vector<ColorWheelColor> color_wheel_;
};
-} // namespace analysis
-} // namespace frc971
-#endif // FRC971_ANALYSIS_IN_PROCESS_PLOTTER_H_
+} // namespace aos::analysis
+#endif // AOS_ANALYSIS_IN_PROCESS_PLOTTER_H_
diff --git a/frc971/analysis/in_process_plotter_demo.cc b/aos/analysis/in_process_plotter_demo.cc
similarity index 93%
rename from frc971/analysis/in_process_plotter_demo.cc
rename to aos/analysis/in_process_plotter_demo.cc
index 99e0c1d..6141d6a 100644
--- a/frc971/analysis/in_process_plotter_demo.cc
+++ b/aos/analysis/in_process_plotter_demo.cc
@@ -1,5 +1,5 @@
+#include "aos/analysis/in_process_plotter.h"
#include "aos/init.h"
-#include "frc971/analysis/in_process_plotter.h"
// To run this example, do:
// bazel run -c opt //frc971/analysis:in_process_plotter_demo
@@ -8,7 +8,7 @@
// each plot.
int main(int argc, char *argv[]) {
aos::InitGoogle(&argc, &argv);
- frc971::analysis::Plotter plotter;
+ aos::analysis::Plotter plotter;
plotter.Title("TITLE!");
plotter.AddFigure("Fig Foo");
plotter.ShareXAxis(true);
diff --git a/frc971/analysis/local_foxglove.cc b/aos/analysis/local_foxglove.cc
similarity index 100%
rename from frc971/analysis/local_foxglove.cc
rename to aos/analysis/local_foxglove.cc
diff --git a/frc971/analysis/log_reader_test.py b/aos/analysis/log_reader_test.py
similarity index 98%
rename from frc971/analysis/log_reader_test.py
rename to aos/analysis/log_reader_test.py
index 7af08e6..69627aa 100644
--- a/frc971/analysis/log_reader_test.py
+++ b/aos/analysis/log_reader_test.py
@@ -2,7 +2,7 @@
import json
import unittest
-from frc971.analysis.py_log_reader import LogReader
+from aos.analysis.py_log_reader import LogReader
class LogReaderTest(unittest.TestCase):
diff --git a/frc971/analysis/plot_data.fbs b/aos/analysis/plot_data.fbs
similarity index 97%
rename from frc971/analysis/plot_data.fbs
rename to aos/analysis/plot_data.fbs
index 641cd6e..20689c5 100644
--- a/frc971/analysis/plot_data.fbs
+++ b/aos/analysis/plot_data.fbs
@@ -3,7 +3,7 @@
// the data to plot is all packaged within a single Plot message. Each Plot
// message will correspond to a single view/tab on the web-page, and can have
// multiple figures, each of which can have multiple lines.
-namespace frc971.analysis;
+namespace aos.analysis;
// Position within the web-page to plot a figure at. [0, 0] will be the upper
// left corner of the allowable places where plots can be put, and should
diff --git a/frc971/analysis/plot_data_utils.ts b/aos/analysis/plot_data_utils.ts
similarity index 96%
rename from frc971/analysis/plot_data_utils.ts
rename to aos/analysis/plot_data_utils.ts
index 25131fb..0153cdb 100644
--- a/frc971/analysis/plot_data_utils.ts
+++ b/aos/analysis/plot_data_utils.ts
@@ -1,5 +1,5 @@
// Provides a plot which handles plotting the plot defined by a
-// frc971.analysis.Plot message.
+// aos.analysis.Plot message.
import {Plot as PlotFb} from './plot_data_generated';
import {MessageHandler, TimestampedMessage} from '../../aos/network/www/aos_plotter';
import {ByteBuffer} from 'flatbuffers';
@@ -28,7 +28,7 @@
parentDiv.appendChild(plotDiv);
conn.addReliableHandler(
- '/analysis', 'frc971.analysis.Plot', (data: Uint8Array, time: number) => {
+ '/analysis', 'aos.analysis.Plot', (data: Uint8Array, time: number) => {
const plotFb = PlotFb.getRootAsPlot(new ByteBuffer(data));
const name = (!plotFb.title()) ? 'Plot ' + plots.size : plotFb.title();
const div = document.createElement('div');
diff --git a/frc971/analysis/plotter_config.json b/aos/analysis/plotter_config.json
similarity index 78%
rename from frc971/analysis/plotter_config.json
rename to aos/analysis/plotter_config.json
index fef4a50..2ebde74 100644
--- a/frc971/analysis/plotter_config.json
+++ b/aos/analysis/plotter_config.json
@@ -2,7 +2,7 @@
"channels": [
{
"name": "/analysis",
- "type": "frc971.analysis.Plot",
+ "type": "aos.analysis.Plot",
"max_size": 1000000000
}
],
diff --git a/frc971/analysis/py_log_reader.cc b/aos/analysis/py_log_reader.cc
similarity index 98%
rename from frc971/analysis/py_log_reader.cc
rename to aos/analysis/py_log_reader.cc
index 57d57d0..4a97a0f 100644
--- a/frc971/analysis/py_log_reader.cc
+++ b/aos/analysis/py_log_reader.cc
@@ -27,7 +27,7 @@
#include "aos/init.h"
#include "aos/json_to_flatbuffer.h"
-namespace frc971::analysis {
+namespace aos::analysis {
namespace {
// All the data corresponding to a single message.
@@ -299,8 +299,8 @@
}
} // namespace
-} // namespace frc971::analysis
+} // namespace aos::analysis
PyMODINIT_FUNC PyInit_py_log_reader(void) {
- return frc971::analysis::InitModule();
+ return aos::analysis::InitModule();
}
diff --git a/aos/events/epoll.h b/aos/events/epoll.h
index 2b7eb76..526c6a7 100644
--- a/aos/events/epoll.h
+++ b/aos/events/epoll.h
@@ -12,8 +12,7 @@
#include "aos/time/time.h"
-namespace aos {
-namespace internal {
+namespace aos::internal {
// Class wrapping up timerfd.
class TimerFd {
@@ -187,7 +186,6 @@
std::vector<std::function<void()>> before_epoll_wait_functions_;
};
-} // namespace internal
-} // namespace aos
+} // namespace aos::internal
#endif // AOS_EVENTS_EPOLL_H_
diff --git a/aos/events/event_loop_param_test.h b/aos/events/event_loop_param_test.h
index d466a1e..f2b16c5 100644
--- a/aos/events/event_loop_param_test.h
+++ b/aos/events/event_loop_param_test.h
@@ -18,8 +18,7 @@
#include "aos/network/message_bridge_server_schema.h"
#include "aos/network/timestamp_schema.h"
-namespace aos {
-namespace testing {
+namespace aos::testing {
class EventLoopTestFactory {
public:
@@ -398,7 +397,6 @@
// Sends a test message with value 0 with the given sender
RawSender::Error SendTestMessage(aos::Sender<TestMessage> &sender);
-} // namespace testing
-} // namespace aos
+} // namespace aos::testing
#endif // _AOS_EVENTS_EVENT_LOOP_PARAM_TEST_H_
diff --git a/aos/events/logging/BUILD b/aos/events/logging/BUILD
index 1743f88..21754bb 100644
--- a/aos/events/logging/BUILD
+++ b/aos/events/logging/BUILD
@@ -965,7 +965,7 @@
srcs = ["timestamp_plot.cc"],
deps = [
"//aos:init",
- "//frc971/analysis:in_process_plotter",
+ "//aos/analysis:in_process_plotter",
"@com_google_absl//absl/strings",
],
)
diff --git a/aos/events/logging/log_namer.h b/aos/events/logging/log_namer.h
index 5374acf..e0660eb 100644
--- a/aos/events/logging/log_namer.h
+++ b/aos/events/logging/log_namer.h
@@ -15,8 +15,7 @@
#include "aos/events/logging/logger_generated.h"
#include "aos/uuid.h"
-namespace aos {
-namespace logger {
+namespace aos::logger {
class LogNamer;
@@ -650,7 +649,6 @@
void OpenNodeWriter(const Node *source_node, NewDataWriter *data_writer);
};
-} // namespace logger
-} // namespace aos
+} // namespace aos::logger
#endif // AOS_EVENTS_LOGGING_LOG_NAMER_H_
diff --git a/aos/events/logging/log_reader.h b/aos/events/logging/log_reader.h
index 901bf32..fb19e78 100644
--- a/aos/events/logging/log_reader.h
+++ b/aos/events/logging/log_reader.h
@@ -32,8 +32,7 @@
#include "aos/util/threaded_queue.h"
#include "aos/uuid.h"
-namespace aos {
-namespace logger {
+namespace aos::logger {
class EventNotifier;
@@ -950,7 +949,6 @@
ConfigRemapper config_remapper_;
};
-} // namespace logger
-} // namespace aos
+} // namespace aos::logger
#endif // AOS_EVENTS_LOGGING_LOG_READER_H_
diff --git a/aos/events/logging/log_writer.h b/aos/events/logging/log_writer.h
index ec02b7d..eb69d7e 100644
--- a/aos/events/logging/log_writer.h
+++ b/aos/events/logging/log_writer.h
@@ -17,8 +17,7 @@
#include "aos/time/time.h"
#include "aos/uuid.h"
-namespace aos {
-namespace logger {
+namespace aos::logger {
// Packs the provided configuration into the separate config LogFileHeader
// container.
@@ -377,7 +376,6 @@
std::chrono::nanoseconds logging_delay_ = std::chrono::nanoseconds(0);
};
-} // namespace logger
-} // namespace aos
+} // namespace aos::logger
#endif // AOS_EVENTS_LOGGING_LOG_WRITER_H_
diff --git a/aos/events/logging/logfile_sorting.h b/aos/events/logging/logfile_sorting.h
index 825a210..4f2a2e2 100644
--- a/aos/events/logging/logfile_sorting.h
+++ b/aos/events/logging/logfile_sorting.h
@@ -15,8 +15,7 @@
#include "aos/time/time.h"
#include "aos/uuid.h"
-namespace aos {
-namespace logger {
+namespace aos::logger {
struct Boots {
// Maps the boot UUID to the boot count. Since boot UUIDs are unique, we
@@ -309,7 +308,6 @@
std::vector<std::string> logger_nodes_;
};
-} // namespace logger
-} // namespace aos
+} // namespace aos::logger
#endif // AOS_EVENTS_LOGGING_LOGFILE_SORTING_H_
diff --git a/aos/events/logging/multinode_logger_test_lib.h b/aos/events/logging/multinode_logger_test_lib.h
index f5fb4cf..63604d6 100644
--- a/aos/events/logging/multinode_logger_test_lib.h
+++ b/aos/events/logging/multinode_logger_test_lib.h
@@ -17,9 +17,7 @@
#include "aos/events/logging/lzma_encoder.h"
#endif
-namespace aos {
-namespace logger {
-namespace testing {
+namespace aos::logger::testing {
struct CompressionParams {
std::string_view extension;
@@ -196,8 +194,6 @@
typedef MultinodeLoggerTest MultinodeLoggerDeathTest;
-} // namespace testing
-} // namespace logger
-} // namespace aos
+} // namespace aos::logger::testing
#endif // AOS_EVENTS_LOGGING_MULTINODE_LOGGER_TEST_LIB_H
diff --git a/aos/events/logging/replay_channels.h b/aos/events/logging/replay_channels.h
index f9ec144..0922acc 100644
--- a/aos/events/logging/replay_channels.h
+++ b/aos/events/logging/replay_channels.h
@@ -4,12 +4,10 @@
#include <string>
#include <vector>
-namespace aos {
-namespace logger {
+namespace aos::logger {
// Vector of pair of name and type of the channel
using ReplayChannels = std::vector<std::pair<std::string, std::string>>;
// Vector of channel indices
using ReplayChannelIndices = std::vector<size_t>;
-} // namespace logger
-} // namespace aos
+} // namespace aos::logger
#endif // AOS_EVENTS_LOGGING_REPLAY_CHANNELS_H_
diff --git a/aos/events/logging/timestamp_plot.cc b/aos/events/logging/timestamp_plot.cc
index e266716..5b5cdc2 100644
--- a/aos/events/logging/timestamp_plot.cc
+++ b/aos/events/logging/timestamp_plot.cc
@@ -1,11 +1,11 @@
#include "absl/strings/str_cat.h"
#include "absl/strings/str_split.h"
+#include "aos/analysis/in_process_plotter.h"
#include "aos/init.h"
#include "aos/util/file.h"
-#include "frc971/analysis/in_process_plotter.h"
-using frc971::analysis::Plotter;
+using aos::analysis::Plotter;
DEFINE_bool(all, false, "If true, plot *all* the nodes at once");
DEFINE_bool(bounds, false, "If true, plot the noncausal bounds too.");
diff --git a/aos/events/message_counter.h b/aos/events/message_counter.h
index 418c1eb..13d75c5 100644
--- a/aos/events/message_counter.h
+++ b/aos/events/message_counter.h
@@ -3,8 +3,7 @@
#include "aos/events/event_loop.h"
-namespace aos {
-namespace testing {
+namespace aos::testing {
// Simple class to count messages on a channel easily. This only counts
// messages published while running.
@@ -22,7 +21,6 @@
size_t count_ = 0;
};
-} // namespace testing
-} // namespace aos
+} // namespace aos::testing
#endif // AOS_EVENTS_MESSAGE_COUNTER_H_
diff --git a/aos/events/simulated_network_bridge.h b/aos/events/simulated_network_bridge.h
index faa6398..14a7321 100644
--- a/aos/events/simulated_network_bridge.h
+++ b/aos/events/simulated_network_bridge.h
@@ -8,8 +8,7 @@
#include "aos/network/remote_message_generated.h"
#include "aos/network/timestamp_channel.h"
-namespace aos {
-namespace message_bridge {
+namespace aos::message_bridge {
class RawMessageDelayer;
@@ -235,7 +234,6 @@
std::vector<std::unique_ptr<DelayersVector>> delayers_list_;
};
-} // namespace message_bridge
-} // namespace aos
+} // namespace aos::message_bridge
#endif // AOS_EVENTS_SIMULATED_NETWORK_BRIDGE_H_
diff --git a/aos/events/timing_statistics.h b/aos/events/timing_statistics.h
index 3c8c741..ef07254 100644
--- a/aos/events/timing_statistics.h
+++ b/aos/events/timing_statistics.h
@@ -6,8 +6,7 @@
#include "aos/events/event_loop_generated.h"
#include "aos/util/error_counter.h"
-namespace aos {
-namespace internal {
+namespace aos::internal {
// Class to compute statistics for the timing report.
class TimingStatistic {
@@ -113,7 +112,6 @@
timing::Timer *timer = nullptr;
};
-} // namespace internal
-} // namespace aos
+} // namespace aos::internal
#endif // AOS_EVENTS_TIMING_STATISTICS_H_
diff --git a/aos/flatbuffers/static_flatbuffers_test.cc b/aos/flatbuffers/static_flatbuffers_test.cc
index 83370e7..fd95db3 100644
--- a/aos/flatbuffers/static_flatbuffers_test.cc
+++ b/aos/flatbuffers/static_flatbuffers_test.cc
@@ -797,17 +797,17 @@
// Try to cover ~all supported scalar/flatbuffer types using JSON convenience
// functions.
TEST_F(StaticFlatbuffersTest, FlatbufferTypeCoverage) {
- VerifyJson<frc971::testing::ConfigurationStatic>("{\n\n}");
+ VerifyJson<aos::testing::ConfigurationStatic>("{\n\n}");
std::string populated_config =
aos::util::ReadFileToStringOrDie(aos::testing::ArtifactPath(
"aos/flatbuffers/test_dir/type_coverage.json"));
// Get rid of a pesky new line.
populated_config = populated_config.substr(0, populated_config.size() - 1);
- VerifyJson<frc971::testing::ConfigurationStatic>(populated_config);
+ VerifyJson<aos::testing::ConfigurationStatic>(populated_config);
// And now play around with mutating the buffer.
- Builder<frc971::testing::ConfigurationStatic> builder =
- aos::JsonToStaticFlatbuffer<frc971::testing::ConfigurationStatic>(
+ Builder<aos::testing::ConfigurationStatic> builder =
+ aos::JsonToStaticFlatbuffer<aos::testing::ConfigurationStatic>(
populated_config);
ASSERT_TRUE(builder.Verify());
builder.get()->clear_foo_float();
diff --git a/aos/flatbuffers/test_dir/type_coverage.fbs b/aos/flatbuffers/test_dir/type_coverage.fbs
index d364fd5..96f6890 100644
--- a/aos/flatbuffers/test_dir/type_coverage.fbs
+++ b/aos/flatbuffers/test_dir/type_coverage.fbs
@@ -3,7 +3,7 @@
// other sources.
// Use a namespace that has no overlap with the aos::fbs namespace of the underlying code.
-namespace frc971.testing;
+namespace aos.testing;
enum BaseType : byte {
None,
diff --git a/aos/ipc_lib/index.h b/aos/ipc_lib/index.h
index 434da7c..75f1e9b 100644
--- a/aos/ipc_lib/index.h
+++ b/aos/ipc_lib/index.h
@@ -23,8 +23,7 @@
#endif
#endif
-namespace aos {
-namespace ipc_lib {
+namespace aos::ipc_lib {
struct AtomicQueueIndex;
class AtomicIndex;
@@ -305,7 +304,6 @@
::std::atomic<Index::IndexType> index_;
};
-} // namespace ipc_lib
-} // namespace aos
+} // namespace aos::ipc_lib
#endif // AOS_IPC_LIB_INDEX_H_
diff --git a/aos/ipc_lib/lockless_queue.h b/aos/ipc_lib/lockless_queue.h
index 14a11b6..4f867b9 100644
--- a/aos/ipc_lib/lockless_queue.h
+++ b/aos/ipc_lib/lockless_queue.h
@@ -18,8 +18,7 @@
#include "aos/time/time.h"
#include "aos/uuid.h"
-namespace aos {
-namespace ipc_lib {
+namespace aos::ipc_lib {
// Structure to hold the state required to wake a watcher.
struct Watcher {
@@ -478,7 +477,6 @@
// Prints to stdout the data inside the queue for debugging.
void PrintLocklessQueueMemory(const LocklessQueueMemory *memory);
-} // namespace ipc_lib
-} // namespace aos
+} // namespace aos::ipc_lib
#endif // AOS_IPC_LIB_LOCKLESS_QUEUE_H_
diff --git a/aos/ipc_lib/lockless_queue_memory.h b/aos/ipc_lib/lockless_queue_memory.h
index 713d9cd..70fc8a8 100644
--- a/aos/ipc_lib/lockless_queue_memory.h
+++ b/aos/ipc_lib/lockless_queue_memory.h
@@ -10,8 +10,7 @@
#include "aos/ipc_lib/lockless_queue.h"
#include "aos/time/time.h"
-namespace aos {
-namespace ipc_lib {
+namespace aos::ipc_lib {
struct LocklessQueueMemory {
// This is held during initialization. Cleanup after dead processes happens
@@ -194,7 +193,6 @@
}
};
-} // namespace ipc_lib
-} // namespace aos
+} // namespace aos::ipc_lib
#endif // AOS_IPC_LIB_LOCKLESS_QUEUE_MEMORY_H_
diff --git a/aos/ipc_lib/lockless_queue_stepping.cc b/aos/ipc_lib/lockless_queue_stepping.cc
index e819795..40d1631 100644
--- a/aos/ipc_lib/lockless_queue_stepping.cc
+++ b/aos/ipc_lib/lockless_queue_stepping.cc
@@ -25,9 +25,7 @@
#ifdef SUPPORTS_SHM_ROBUSTNESS_TEST
-namespace aos {
-namespace ipc_lib {
-namespace testing {
+namespace aos::ipc_lib::testing {
namespace {
pid_t gettid() { return syscall(SYS_gettid); }
@@ -458,8 +456,6 @@
pid_t SharedTid::Get() { return *tid_; }
-} // namespace testing
-} // namespace ipc_lib
-} // namespace aos
+} // namespace aos::ipc_lib::testing
#endif // SUPPORTS_SHM_ROBSTNESS_TEST
diff --git a/aos/ipc_lib/lockless_queue_stepping.h b/aos/ipc_lib/lockless_queue_stepping.h
index 7aab193..590534f 100644
--- a/aos/ipc_lib/lockless_queue_stepping.h
+++ b/aos/ipc_lib/lockless_queue_stepping.h
@@ -7,9 +7,7 @@
#include "aos/ipc_lib/lockless_queue.h"
#include "aos/ipc_lib/lockless_queue_memory.h"
-namespace aos {
-namespace ipc_lib {
-namespace testing {
+namespace aos::ipc_lib::testing {
#if defined(__ARM_EABI__)
// There are various reasons why we might not actually be able to do this
@@ -142,8 +140,6 @@
#endif
-} // namespace testing
-} // namespace ipc_lib
-} // namespace aos
+} // namespace aos::ipc_lib::testing
#endif // AOS_IPC_LIB_LOCKLESS_QUEUE_STEPPING_H_
diff --git a/aos/ipc_lib/memory_mapped_queue.h b/aos/ipc_lib/memory_mapped_queue.h
index 653dc77..bd766c1 100644
--- a/aos/ipc_lib/memory_mapped_queue.h
+++ b/aos/ipc_lib/memory_mapped_queue.h
@@ -6,8 +6,7 @@
#include "aos/configuration.h"
#include "aos/ipc_lib/lockless_queue.h"
-namespace aos {
-namespace ipc_lib {
+namespace aos::ipc_lib {
std::string ShmFolder(std::string_view shm_base, const Channel *channel);
@@ -58,7 +57,6 @@
const void *const_data_;
};
-} // namespace ipc_lib
-} // namespace aos
+} // namespace aos::ipc_lib
#endif // AOS_IPC_LIB_MEMORY_MAPPED_QUEUE_H_
diff --git a/aos/ipc_lib/queue_racer.h b/aos/ipc_lib/queue_racer.h
index f0a2684..2cbe3ed 100644
--- a/aos/ipc_lib/queue_racer.h
+++ b/aos/ipc_lib/queue_racer.h
@@ -5,8 +5,7 @@
#include "aos/ipc_lib/lockless_queue.h"
-namespace aos {
-namespace ipc_lib {
+namespace aos::ipc_lib {
struct ThreadState;
@@ -97,7 +96,6 @@
size_t) { return true; };
};
-} // namespace ipc_lib
-} // namespace aos
+} // namespace aos::ipc_lib
#endif // AOS_IPC_LIB_QUEUE_RACER_H_
diff --git a/aos/ipc_lib/signalfd.h b/aos/ipc_lib/signalfd.h
index a6991de..014ad5c 100644
--- a/aos/ipc_lib/signalfd.h
+++ b/aos/ipc_lib/signalfd.h
@@ -6,8 +6,7 @@
#include <initializer_list>
-namespace aos {
-namespace ipc_lib {
+namespace aos::ipc_lib {
// Class to manage a signalfd.
class SignalFd {
@@ -34,7 +33,6 @@
sigset_t blocked_mask_;
};
-} // namespace ipc_lib
-} // namespace aos
+} // namespace aos::ipc_lib
#endif // AOS_IPC_LIB_SIGNALFD_H_
diff --git a/aos/libc/dirname.h b/aos/libc/dirname.h
index fa733d7..c549b3c 100644
--- a/aos/libc/dirname.h
+++ b/aos/libc/dirname.h
@@ -3,13 +3,11 @@
#include <string>
-namespace aos {
-namespace libc {
+namespace aos::libc {
// Thread-safe version of dirname(3).
::std::string Dirname(const ::std::string &path);
-} // namespace libc
-} // namespace aos
+} // namespace aos::libc
#endif // AOS_LIBC_DIRNAME_H_
diff --git a/aos/logging/dynamic_logging.h b/aos/logging/dynamic_logging.h
index 0dfd181..e3d3a6f 100644
--- a/aos/logging/dynamic_logging.h
+++ b/aos/logging/dynamic_logging.h
@@ -9,8 +9,7 @@
// and make changes to the log level of the current application based on that
// message. Currently the only supported command is changing the global vlog
// level.
-namespace aos {
-namespace logging {
+namespace aos::logging {
class DynamicLogging {
public:
@@ -23,5 +22,4 @@
DISALLOW_COPY_AND_ASSIGN(DynamicLogging);
};
-} // namespace logging
-} // namespace aos
+} // namespace aos::logging
diff --git a/aos/logging/log_namer.h b/aos/logging/log_namer.h
index a993d31..0c32d5d 100644
--- a/aos/logging/log_namer.h
+++ b/aos/logging/log_namer.h
@@ -4,8 +4,7 @@
#include <optional>
#include <string>
-namespace aos {
-namespace logging {
+namespace aos::logging {
// Returns the correct filename to log to, blocking until the usb drive
// filesystem mounts, incrementing the number on the end of the filename, and
// setting up a symlink at basename-current.
@@ -19,7 +18,6 @@
// the usb drive.
std::optional<std::string> MaybeGetLogName(const char *basename);
-} // namespace logging
-} // namespace aos
+} // namespace aos::logging
#endif // AOS_LOGGING_LOG_NAMER_H_
diff --git a/aos/network/message_bridge_client_lib.h b/aos/network/message_bridge_client_lib.h
index 2df3599..56d2563 100644
--- a/aos/network/message_bridge_client_lib.h
+++ b/aos/network/message_bridge_client_lib.h
@@ -14,8 +14,7 @@
#include "aos/network/sctp_config_request_generated.h"
#include "aos/network/sctp_lib.h"
-namespace aos {
-namespace message_bridge {
+namespace aos::message_bridge {
// Structure to hold per channel state.
struct SctpClientChannelState {
@@ -165,7 +164,6 @@
aos::Sender<SctpConfigRequest> sctp_config_request_;
};
-} // namespace message_bridge
-} // namespace aos
+} // namespace aos::message_bridge
#endif // AOS_NETWORK_MESSAGE_BRIDGE_CLIENT_LIB_H_
diff --git a/aos/network/message_bridge_client_status.h b/aos/network/message_bridge_client_status.h
index 033af95..4e6c2c5 100644
--- a/aos/network/message_bridge_client_status.h
+++ b/aos/network/message_bridge_client_status.h
@@ -8,8 +8,7 @@
#include "aos/network/message_bridge_client_generated.h"
#include "aos/network/timestamp_filter.h"
-namespace aos {
-namespace message_bridge {
+namespace aos::message_bridge {
// This class is responsible for publishing the (filtered) client side
// statistics periodically.
@@ -88,7 +87,6 @@
bool send_ = true;
};
-} // namespace message_bridge
-} // namespace aos
+} // namespace aos::message_bridge
#endif // AOS_NETWORK_MESSAGE_BRIDGE_CLIENT_STATUS_H_
diff --git a/aos/network/message_bridge_protocol.h b/aos/network/message_bridge_protocol.h
index 23a6e0f..0783466 100644
--- a/aos/network/message_bridge_protocol.h
+++ b/aos/network/message_bridge_protocol.h
@@ -7,8 +7,7 @@
#include "aos/network/connect_generated.h"
#include "aos/uuid.h"
-namespace aos {
-namespace message_bridge {
+namespace aos::message_bridge {
// The protocol between the message_bridge_client and server is pretty simple.
// The overarching design philosophy is that the server sends data to the
@@ -41,7 +40,6 @@
std::string_view remote_name, const UUID &boot_uuid,
std::string_view config_sha256);
-} // namespace message_bridge
-} // namespace aos
+} // namespace aos::message_bridge
#endif // AOS_NETWORK_MESSAGE_BRIDGE_PROTOCOL_H_
diff --git a/aos/network/message_bridge_server_lib.h b/aos/network/message_bridge_server_lib.h
index b8377c6..b47a4e6 100644
--- a/aos/network/message_bridge_server_lib.h
+++ b/aos/network/message_bridge_server_lib.h
@@ -20,8 +20,7 @@
#include "aos/network/timestamp_channel.h"
#include "aos/network/timestamp_generated.h"
-namespace aos {
-namespace message_bridge {
+namespace aos::message_bridge {
// See message_bridge_protocol.h for more details about the protocol.
@@ -237,7 +236,6 @@
aos::Sender<SctpConfigRequest> sctp_config_request_;
};
-} // namespace message_bridge
-} // namespace aos
+} // namespace aos::message_bridge
#endif // AOS_NETWORK_MESSAGE_BRIDGE_SERVER_LIB_H_
diff --git a/aos/network/message_bridge_server_status.h b/aos/network/message_bridge_server_status.h
index 3945d57..8bdf4a8 100644
--- a/aos/network/message_bridge_server_status.h
+++ b/aos/network/message_bridge_server_status.h
@@ -13,8 +13,7 @@
#include "aos/network/timestamp_generated.h"
#include "aos/time/time.h"
-namespace aos {
-namespace message_bridge {
+namespace aos::message_bridge {
// This class encapsulates the server side of sending server statistics and
// managing timestamp offsets.
@@ -158,7 +157,6 @@
std::vector<flatbuffers::Offset<ClientOffset>> client_offsets_;
};
-} // namespace message_bridge
-} // namespace aos
+} // namespace aos::message_bridge
#endif // AOS_NETWORK_MESSAGE_BRIDGE_SERVER_STATUS_H_
diff --git a/aos/network/multinode_timestamp_filter.h b/aos/network/multinode_timestamp_filter.h
index 828c489..893f816 100644
--- a/aos/network/multinode_timestamp_filter.h
+++ b/aos/network/multinode_timestamp_filter.h
@@ -16,8 +16,7 @@
#include "aos/network/timestamp_filter.h"
#include "aos/time/time.h"
-namespace aos {
-namespace message_bridge {
+namespace aos::message_bridge {
// Problem description for NewtonSolver.
class Problem {
@@ -667,7 +666,6 @@
std::vector<size_t> source_node_index_;
};
-} // namespace message_bridge
-} // namespace aos
+} // namespace aos::message_bridge
#endif // AOS_NETWORK_MULTINODE_TIMESTAMP_FILTER_H_
diff --git a/aos/network/rawrtc.h b/aos/network/rawrtc.h
index 7908124..57153f0 100644
--- a/aos/network/rawrtc.h
+++ b/aos/network/rawrtc.h
@@ -13,8 +13,7 @@
#include "flatbuffers/flatbuffers.h"
#include "glog/logging.h"
-namespace aos {
-namespace web_proxy {
+namespace aos::web_proxy {
// TODO(austin): This doesn't allow streaming data in.
#define CHECK_RAWRTC(x) \
@@ -215,7 +214,6 @@
std::function<void(std::shared_ptr<ScopedDataChannel>)> on_data_channel_;
};
-} // namespace web_proxy
-} // namespace aos
+} // namespace aos::web_proxy
#endif // AOS_NETWORK_RAWRTC_H_
diff --git a/aos/network/sctp_client.h b/aos/network/sctp_client.h
index 9b9265e..952d0e9 100644
--- a/aos/network/sctp_client.h
+++ b/aos/network/sctp_client.h
@@ -11,8 +11,7 @@
#include "aos/network/sctp_lib.h"
#include "aos/unique_malloc_ptr.h"
-namespace aos {
-namespace message_bridge {
+namespace aos::message_bridge {
// Class to encapsulate everything needed to be a SCTP client.
class SctpClient {
@@ -73,7 +72,6 @@
sctp_assoc_t sac_assoc_id_ = 0;
};
-} // namespace message_bridge
-} // namespace aos
+} // namespace aos::message_bridge
#endif // AOS_NETWORK_SCTP_CLIENT_H_
diff --git a/aos/network/sctp_lib.h b/aos/network/sctp_lib.h
index 0d021a9..3430be8 100644
--- a/aos/network/sctp_lib.h
+++ b/aos/network/sctp_lib.h
@@ -19,8 +19,7 @@
#define HAS_SCTP_AUTH LINUX_VERSION_CODE >= KERNEL_VERSION(5, 4, 0)
-namespace aos {
-namespace message_bridge {
+namespace aos::message_bridge {
constexpr bool HasSctpAuth() { return HAS_SCTP_AUTH; }
@@ -202,7 +201,6 @@
// Returns the max network buffer available for writing for a socket.
size_t ReadWMemMax();
-} // namespace message_bridge
-} // namespace aos
+} // namespace aos::message_bridge
#endif // AOS_NETWORK_SCTP_LIB_H_
diff --git a/aos/network/sctp_server.h b/aos/network/sctp_server.h
index e641fd8..996645e 100644
--- a/aos/network/sctp_server.h
+++ b/aos/network/sctp_server.h
@@ -19,8 +19,7 @@
#include "aos/network/sctp_lib.h"
#include "aos/unique_malloc_ptr.h"
-namespace aos {
-namespace message_bridge {
+namespace aos::message_bridge {
class SctpServer {
public:
@@ -74,7 +73,6 @@
SctpReadWrite sctp_;
};
-} // namespace message_bridge
-} // namespace aos
+} // namespace aos::message_bridge
#endif // AOS_NETWORK_SCTP_SERVER_H_
diff --git a/aos/network/testing_time_converter.h b/aos/network/testing_time_converter.h
index ae85cee..768d0a2 100644
--- a/aos/network/testing_time_converter.h
+++ b/aos/network/testing_time_converter.h
@@ -10,8 +10,7 @@
#include "aos/network/multinode_timestamp_filter.h"
#include "aos/time/time.h"
-namespace aos {
-namespace message_bridge {
+namespace aos::message_bridge {
// Simple class to which uses InterpolatedTimeConverter to produce an
// interpolated timeline. Should only be used for testing.
@@ -77,7 +76,6 @@
std::map<std::pair<size_t, size_t>, UUID> boot_uuids_;
};
-} // namespace message_bridge
-} // namespace aos
+} // namespace aos::message_bridge
#endif // AOS_NETWORK_TESTING_TIME_CONVERTER_H_
diff --git a/aos/network/timestamp_channel.h b/aos/network/timestamp_channel.h
index c8e88d9..7e48a00 100644
--- a/aos/network/timestamp_channel.h
+++ b/aos/network/timestamp_channel.h
@@ -11,8 +11,7 @@
#include "aos/events/event_loop.h"
#include "aos/network/remote_message_generated.h"
-namespace aos {
-namespace message_bridge {
+namespace aos::message_bridge {
// Class to find the corresponding channel where timestamps for a specified data
// channel and connection will be logged.
@@ -89,7 +88,6 @@
timestamp_loggers_;
};
-} // namespace message_bridge
-} // namespace aos
+} // namespace aos::message_bridge
#endif // AOS_NETWORK_TIMESTAMP_CHANNEL_
diff --git a/aos/network/timestamp_filter.h b/aos/network/timestamp_filter.h
index b1aff86..be9318e 100644
--- a/aos/network/timestamp_filter.h
+++ b/aos/network/timestamp_filter.h
@@ -14,8 +14,7 @@
#include "aos/events/logging/boot_timestamp.h"
#include "aos/time/time.h"
-namespace aos {
-namespace message_bridge {
+namespace aos::message_bridge {
// Max velocity to clamp the filter to in seconds/second.
typedef std::ratio<1, 1000> MaxVelocityRatio;
@@ -951,7 +950,6 @@
const Node *node_b_;
};
-} // namespace message_bridge
-} // namespace aos
+} // namespace aos::message_bridge
#endif // AOS_EVENTS_LOGGING_TIMESTAMP_FILTER_H_
diff --git a/aos/network/web_proxy.h b/aos/network/web_proxy.h
index db7fb5b..dec3078 100644
--- a/aos/network/web_proxy.h
+++ b/aos/network/web_proxy.h
@@ -19,8 +19,7 @@
#include "seasocks/StringUtil.h"
#include "seasocks/WebSocket.h"
-namespace aos {
-namespace web_proxy {
+namespace aos::web_proxy {
class Connection;
class Subscriber;
@@ -242,7 +241,6 @@
std::shared_ptr<ScopedDataChannel> channel_;
};
-} // namespace web_proxy
-} // namespace aos
+} // namespace aos::web_proxy
#endif // AOS_NETWORK_WEB_PROXY_H_
diff --git a/aos/network/web_proxy_utils.h b/aos/network/web_proxy_utils.h
index c5e2716..e35708a 100644
--- a/aos/network/web_proxy_utils.h
+++ b/aos/network/web_proxy_utils.h
@@ -4,8 +4,7 @@
#include "aos/flatbuffers.h"
#include "aos/network/web_proxy_generated.h"
-namespace aos {
-namespace web_proxy {
+namespace aos::web_proxy {
int GetPacketCount(const Context &context);
@@ -24,5 +23,4 @@
std::vector<FlatbufferDetachedBuffer<MessageHeader>> PackBuffer(
absl::Span<const uint8_t> span);
-} // namespace web_proxy
-} // namespace aos
+} // namespace aos::web_proxy
diff --git a/aos/network/www/BUILD b/aos/network/www/BUILD
index 73b991e..8cccfa6 100644
--- a/aos/network/www/BUILD
+++ b/aos/network/www/BUILD
@@ -148,7 +148,6 @@
"//aos:configuration_ts_fbs",
"//aos/network:connect_ts_fbs",
"//aos/network:web_proxy_ts_fbs",
- "//frc971/wpilib:imu_batch_ts_fbs",
"@com_github_google_flatbuffers//ts:flatbuffers_ts",
],
)
diff --git a/aos/seasocks/seasocks_logger.h b/aos/seasocks/seasocks_logger.h
index 64f13fa..f60ab48 100644
--- a/aos/seasocks/seasocks_logger.h
+++ b/aos/seasocks/seasocks_logger.h
@@ -3,8 +3,7 @@
#include "seasocks/PrintfLogger.h"
-namespace aos {
-namespace seasocks {
+namespace aos::seasocks {
class SeasocksLogger : public ::seasocks::PrintfLogger {
public:
@@ -13,7 +12,6 @@
void log(::seasocks::Logger::Level level, const char *message) override;
};
-} // namespace seasocks
-} // namespace aos
+} // namespace aos::seasocks
#endif // AOS_SEASOCKS_SEASOCKS_LOGGER_H_
diff --git a/aos/starter/mock_starter.h b/aos/starter/mock_starter.h
index a0c1b76..212f1e5 100644
--- a/aos/starter/mock_starter.h
+++ b/aos/starter/mock_starter.h
@@ -6,8 +6,7 @@
#include "aos/starter/starter_rpc_generated.h"
#include "aos/starter/starterd_lib.h"
-namespace aos {
-namespace starter {
+namespace aos::starter {
// Simple mock of starterd that updates the starter status message to act as
// though applications are started and stopped when requested.
@@ -50,5 +49,4 @@
std::vector<std::unique_ptr<MockStarter>> mock_starters_;
};
-} // namespace starter
-} // namespace aos
+} // namespace aos::starter
diff --git a/aos/starter/starter_rpc_lib.h b/aos/starter/starter_rpc_lib.h
index eadf5c6..ae2450c 100644
--- a/aos/starter/starter_rpc_lib.h
+++ b/aos/starter/starter_rpc_lib.h
@@ -11,8 +11,7 @@
#include "aos/starter/starter_generated.h"
#include "aos/starter/starter_rpc_generated.h"
-namespace aos {
-namespace starter {
+namespace aos::starter {
// Data required to command that starter start/stop/restart a given application.
struct ApplicationCommand {
@@ -119,7 +118,6 @@
const aos::FlatbufferVector<aos::starter::Status>>>
GetStarterStatus(const aos::Configuration *config, const aos::Node *node);
-} // namespace starter
-} // namespace aos
+} // namespace aos::starter
#endif // AOS_STARTER_STARTER_RPC_LIB_H_
diff --git a/aos/starter/starterd_lib.h b/aos/starter/starterd_lib.h
index 92b20fa..3779c84 100644
--- a/aos/starter/starterd_lib.h
+++ b/aos/starter/starterd_lib.h
@@ -19,8 +19,7 @@
#include "aos/starter/subprocess.h"
#include "aos/util/top.h"
-namespace aos {
-namespace starter {
+namespace aos::starter {
const aos::Channel *StatusChannelForNode(const aos::Configuration *config,
const aos::Node *node);
@@ -107,7 +106,6 @@
DISALLOW_COPY_AND_ASSIGN(Starter);
};
-} // namespace starter
-} // namespace aos
+} // namespace aos::starter
#endif // AOS_STARTER_STARTERD_LIB_H_
diff --git a/aos/testing/flatbuffer_eq.h b/aos/testing/flatbuffer_eq.h
index b560aaa..8a42b5f 100644
--- a/aos/testing/flatbuffer_eq.h
+++ b/aos/testing/flatbuffer_eq.h
@@ -7,8 +7,7 @@
#include "aos/flatbuffers.h"
#include "aos/json_to_flatbuffer.h"
-namespace aos {
-namespace testing {
+namespace aos::testing {
// Use FlatbufferUnwrapped to instantiate this.
template <typename T>
@@ -85,7 +84,6 @@
new FlatbufferEqMatcher(aos::FlatbufferVector<T>(expected))));
}
-} // namespace testing
-} // namespace aos
+} // namespace aos::testing
#endif // AOS_TESTING_FLATBUFFER_EQ_H_
diff --git a/aos/testing/path.h b/aos/testing/path.h
index 7f4187d..ebe63fe 100644
--- a/aos/testing/path.h
+++ b/aos/testing/path.h
@@ -4,13 +4,11 @@
#include <string>
#include <string_view>
-namespace aos {
-namespace testing {
+namespace aos::testing {
// Returns the path to the provided artifact which works
std::string ArtifactPath(std::string_view path);
-} // namespace testing
-} // namespace aos
+} // namespace aos::testing
#endif // AOS_TESTING_PATH_H_
diff --git a/aos/testing/test_logging.h b/aos/testing/test_logging.h
index 5e01879..3671aa1 100644
--- a/aos/testing/test_logging.h
+++ b/aos/testing/test_logging.h
@@ -3,8 +3,7 @@
#include "aos/time/time.h"
-namespace aos {
-namespace testing {
+namespace aos::testing {
// Enables the logging framework for use during a gtest test.
// It will print out all WARNING and above messages all of the time. It will
@@ -23,7 +22,6 @@
// we want to use graphing tools to verify what's happening.
void ForcePrintLogsDuringTests();
-} // namespace testing
-} // namespace aos
+} // namespace aos::testing
#endif // AOS_TESTING_TEST_LOGGING_H_
diff --git a/aos/testing/test_shm.h b/aos/testing/test_shm.h
index a1c79ee..658a72d 100644
--- a/aos/testing/test_shm.h
+++ b/aos/testing/test_shm.h
@@ -3,8 +3,7 @@
#include "aos/ipc_lib/shared_mem.h"
-namespace aos {
-namespace testing {
+namespace aos::testing {
// Manages creating and cleaning up "shared memory" which works within this
// process and any that it fork(2)s.
@@ -18,7 +17,6 @@
struct aos_core global_core_data_;
};
-} // namespace testing
-} // namespace aos
+} // namespace aos::testing
#endif // AOS_TESTING_TEST_SHM_H_
diff --git a/aos/testing/tmpdir.h b/aos/testing/tmpdir.h
index 8eabf86..bf8e7d7 100644
--- a/aos/testing/tmpdir.h
+++ b/aos/testing/tmpdir.h
@@ -3,8 +3,7 @@
#include <string>
-namespace aos {
-namespace testing {
+namespace aos::testing {
// Returns a usable temporary directory.
std::string TestTmpDir();
@@ -13,7 +12,6 @@
// otherwise.
void SetTestShmBase();
-} // namespace testing
-} // namespace aos
+} // namespace aos::testing
#endif // AOS_TESTING_TMPDIR_H_
diff --git a/aos/time/time.h b/aos/time/time.h
index cd4ecda..1a5cbd1 100644
--- a/aos/time/time.h
+++ b/aos/time/time.h
@@ -118,15 +118,13 @@
#ifdef __linux__
-namespace std {
-namespace this_thread {
+namespace std::this_thread {
// Template specialization for monotonic_clock, since we can use clock_nanosleep
// with TIMER_ABSTIME and get very precise absolute time sleeps.
template <>
void sleep_until(const ::aos::monotonic_clock::time_point &end_time);
-} // namespace this_thread
-} // namespace std
+} // namespace std::this_thread
#endif // __linux__
diff --git a/aos/util/death_test_log_implementation.h b/aos/util/death_test_log_implementation.h
index 7765b5b..e35f365 100644
--- a/aos/util/death_test_log_implementation.h
+++ b/aos/util/death_test_log_implementation.h
@@ -6,8 +6,7 @@
#include "aos/logging/context.h"
#include "aos/logging/implementations.h"
-namespace aos {
-namespace util {
+namespace aos::util {
// Prints all FATAL messages to stderr and then abort(3)s before the regular
// stuff can print out anything else. Ignores all other messages.
@@ -27,7 +26,6 @@
}
};
-} // namespace util
-} // namespace aos
+} // namespace aos::util
#endif // AOS_UTIL_DEATH_TEST_LOG_IMPLEMENTATION_H_
diff --git a/aos/util/file.h b/aos/util/file.h
index e825e4c..e0d5c6b 100644
--- a/aos/util/file.h
+++ b/aos/util/file.h
@@ -17,8 +17,7 @@
#include "aos/scoped/scoped_fd.h"
-namespace aos {
-namespace util {
+namespace aos::util {
// Returns the complete contents of filename. LOG(FATAL)s if any errors are
// encountered.
@@ -122,7 +121,6 @@
aos::ScopedFD file_;
};
-} // namespace util
-} // namespace aos
+} // namespace aos::util
#endif // AOS_UTIL_FILE_H_
diff --git a/aos/util/log_interval.h b/aos/util/log_interval.h
index d346852..08d06bb 100644
--- a/aos/util/log_interval.h
+++ b/aos/util/log_interval.h
@@ -6,8 +6,7 @@
#include "aos/logging/logging.h"
#include "aos/time/time.h"
-namespace aos {
-namespace util {
+namespace aos::util {
// A class to help with logging things that happen a lot only occasionally.
//
@@ -91,7 +90,6 @@
const char *context_ = NULL;
};
-} // namespace util
-} // namespace aos
+} // namespace aos::util
#endif // AOS_UTIL_LOG_INTERVAL_H_
diff --git a/aos/util/math.h b/aos/util/math.h
index 5efc3c9..5a3df11 100644
--- a/aos/util/math.h
+++ b/aos/util/math.h
@@ -5,8 +5,7 @@
#include "Eigen/Dense"
-namespace aos {
-namespace math {
+namespace aos::math {
// Normalizes an angle to be in (-M_PI, M_PI]
template <typename Scalar>
@@ -64,7 +63,6 @@
return (C.y() - A.y()) * (B.x() - A.x()) > (B.y() - A.y()) * (C.x() - A.x());
}
-} // namespace math
-} // namespace aos
+} // namespace aos::math
#endif // AOS_UTIL_MATH_H_
diff --git a/aos/util/phased_loop.h b/aos/util/phased_loop.h
index 64a3302..dc2dc96 100644
--- a/aos/util/phased_loop.h
+++ b/aos/util/phased_loop.h
@@ -5,8 +5,7 @@
#include "aos/time/time.h"
-namespace aos {
-namespace time {
+namespace aos::time {
// Handles sleeping until a fixed offset from some time interval.
class PhasedLoop {
@@ -88,7 +87,6 @@
monotonic_clock::time_point last_time_ = monotonic_clock::epoch();
};
-} // namespace time
-} // namespace aos
+} // namespace aos::time
#endif // AOS_UTIL_PHASED_LOOP_H_
diff --git a/aos/util/threaded_consumer.h b/aos/util/threaded_consumer.h
index 95ec79a..3bf4f36 100644
--- a/aos/util/threaded_consumer.h
+++ b/aos/util/threaded_consumer.h
@@ -10,8 +10,7 @@
#include "aos/mutex/mutex.h"
#include "aos/realtime.h"
-namespace aos {
-namespace util {
+namespace aos::util {
// This class implements a threadpool of a single worker that accepts work
// from the main thread through a queue and executes it at a different realtime
@@ -96,7 +95,6 @@
std::thread worker_thread_;
};
-} // namespace util
-} // namespace aos
+} // namespace aos::util
#endif // AOS_UTIL_THREADWORKER_H_
diff --git a/aos/util/trapezoid_profile.h b/aos/util/trapezoid_profile.h
index 944c423..6669777 100644
--- a/aos/util/trapezoid_profile.h
+++ b/aos/util/trapezoid_profile.h
@@ -6,8 +6,7 @@
#include "aos/macros.h"
#include "aos/time/time.h"
-namespace aos {
-namespace util {
+namespace aos::util {
// Calculates a trapezoidal motion profile (like for a control loop's goals).
// Supports having the end speed and position changed in the middle.
@@ -63,7 +62,6 @@
DISALLOW_COPY_AND_ASSIGN(TrapezoidProfile);
};
-} // namespace util
-} // namespace aos
+} // namespace aos::util
#endif // AOS_UTIL_TRAPEZOID_PROFILE_H_
diff --git a/aos/util/wrapping_counter.h b/aos/util/wrapping_counter.h
index ea79ec6..0353e2e 100644
--- a/aos/util/wrapping_counter.h
+++ b/aos/util/wrapping_counter.h
@@ -3,8 +3,7 @@
#include <cstdint>
-namespace aos {
-namespace util {
+namespace aos::util {
// Deals correctly with 1-byte counters which wrap.
// This is only possible if the counter never wraps twice between Update calls.
@@ -28,7 +27,6 @@
uint8_t last_count_;
};
-} // namespace util
-} // namespace aos
+} // namespace aos::util
#endif // AOS_UTIL_WRAPPING_COUNTER_H_
diff --git a/aos/vision/blob/codec.h b/aos/vision/blob/codec.h
index b8a8089..5872b44 100644
--- a/aos/vision/blob/codec.h
+++ b/aos/vision/blob/codec.h
@@ -5,8 +5,7 @@
#include "aos/vision/blob/range_image.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
template <typename T>
struct IntCodec {
@@ -45,7 +44,6 @@
// Parses a blob from data (Advancing data pointer by the size of the image).
const char *ParseBlobList(BlobList *blob_list, const char *data);
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // _AOS_VISION_BLOB_CODEC_H_
diff --git a/aos/vision/blob/contour.h b/aos/vision/blob/contour.h
index bbd59a9..c192a75 100644
--- a/aos/vision/blob/contour.h
+++ b/aos/vision/blob/contour.h
@@ -4,8 +4,7 @@
#include "aos/vision/blob/range_image.h"
#include "aos/vision/blob/region_alloc.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
// Countour nodes are slingly linked list chains of pixels that go around
// the boundary of a blob.
@@ -35,7 +34,6 @@
ContourNode *RangeImgToContour(const RangeImage &rimg,
AnalysisAllocator *alloc);
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // _AOS_VIISON_BLOB_CONTOUR_H_
diff --git a/aos/vision/blob/disjoint_set.h b/aos/vision/blob/disjoint_set.h
index 38cca1d..6343e9f 100644
--- a/aos/vision/blob/disjoint_set.h
+++ b/aos/vision/blob/disjoint_set.h
@@ -3,8 +3,7 @@
#include <vector>
-namespace aos {
-namespace vision {
+namespace aos::vision {
// Disjoint set algorithm, which is similar to what this class does:
// https://en.wikipedia.org/wiki/Disjoint-set_data_structure
@@ -40,7 +39,6 @@
std::vector<int> nodes_;
};
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // _AOS_VISION_BLOB_DISJOINT_SET_H_
diff --git a/aos/vision/blob/find_blob.h b/aos/vision/blob/find_blob.h
index d633354..f811749 100644
--- a/aos/vision/blob/find_blob.h
+++ b/aos/vision/blob/find_blob.h
@@ -3,14 +3,12 @@
#include "aos/vision/blob/range_image.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
// Uses disjoint sets to group ranges into disjoint RangeImage.
// ranges that overlap are grouped into the same output RangeImage.
BlobList FindBlobs(const RangeImage &input_image);
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // AOS_VISION_BLOB_FIND_BLOB_H_
diff --git a/aos/vision/blob/hierarchical_contour_merge.h b/aos/vision/blob/hierarchical_contour_merge.h
index 9dd471d..83243bd 100644
--- a/aos/vision/blob/hierarchical_contour_merge.h
+++ b/aos/vision/blob/hierarchical_contour_merge.h
@@ -6,8 +6,7 @@
#include "aos/vision/blob/contour.h"
#include "aos/vision/blob/range_image.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
struct FittedLine {
Point st;
@@ -19,7 +18,6 @@
void HierarchicalMerge(ContourNode *stval, std::vector<FittedLine> *fit_lines,
float merge_rate = 4.0, int min_len = 15);
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // _AOS_VISION_BLOB_HIERARCHICAL_CONTOUR_MERGE_H_
diff --git a/aos/vision/blob/move_scale.h b/aos/vision/blob/move_scale.h
index 061da5c..94a9e9d 100644
--- a/aos/vision/blob/move_scale.h
+++ b/aos/vision/blob/move_scale.h
@@ -7,8 +7,7 @@
#include "aos/vision/blob/range_image.h"
#include "aos/vision/image/image_types.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
// Sums img into bbox. bbox is constructed empty and grows with each call
// to GetBBox.
@@ -22,7 +21,6 @@
RangeImage MoveScale(const RangeImage &img, int dx, int dy, int scale);
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // AOS_VISION_BLOB_MOVE_SCALE_H_
diff --git a/aos/vision/blob/range_image.h b/aos/vision/blob/range_image.h
index d962788..10e801f 100644
--- a/aos/vision/blob/range_image.h
+++ b/aos/vision/blob/range_image.h
@@ -5,8 +5,7 @@
#include "aos/vision/image/image_types.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
struct Point {
int x;
@@ -100,7 +99,6 @@
// Debug print range image as ### for the ranges.
void DebugPrint(const BlobList &blobl);
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // _AOS_VISION_BLOB_RANGE_IMAGE_H_
diff --git a/aos/vision/blob/region_alloc.h b/aos/vision/blob/region_alloc.h
index 3275f3e..101ee6a 100644
--- a/aos/vision/blob/region_alloc.h
+++ b/aos/vision/blob/region_alloc.h
@@ -9,8 +9,7 @@
#include <utility>
#include <vector>
-namespace aos {
-namespace vision {
+namespace aos::vision {
// Region based allocator. Used for arena allocations in vision code.
// Example use: Storing contour nodes.
@@ -52,7 +51,6 @@
size_t used_size_ = 0;
};
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // _AOS_VISION_IMAGE_REGION_ALLOC_H_
diff --git a/aos/vision/blob/stream_view.h b/aos/vision/blob/stream_view.h
index 0db69e5..9841ca2 100644
--- a/aos/vision/blob/stream_view.h
+++ b/aos/vision/blob/stream_view.h
@@ -7,8 +7,7 @@
#include "aos/vision/debug/debug_window.h"
#include "aos/vision/image/image_types.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
class BlobStreamViewer : public DebugWindow {
public:
@@ -85,7 +84,6 @@
ImageValue image_;
};
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // _AOS_VISION_BLOB_STREAM_VIEW_H_
diff --git a/aos/vision/blob/test_utils.h b/aos/vision/blob/test_utils.h
index e0c706c..92c087c 100644
--- a/aos/vision/blob/test_utils.h
+++ b/aos/vision/blob/test_utils.h
@@ -3,8 +3,7 @@
#include "aos/vision/blob/range_image.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
// For tests. Loads a RangeImage from a constant string.
//
@@ -18,7 +17,6 @@
// )"
RangeImage LoadFromTestData(int mini, const char *data);
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // AOS_VISION_BLOB_TEST_UTILS_H_
diff --git a/aos/vision/blob/transpose.h b/aos/vision/blob/transpose.h
index f61ec5c..d2b609e 100644
--- a/aos/vision/blob/transpose.h
+++ b/aos/vision/blob/transpose.h
@@ -3,8 +3,7 @@
#include "aos/vision/blob/range_image.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
RangeImage Transpose(const RangeImage &img);
inline std::vector<RangeImage> Transpose(const std::vector<RangeImage> &imgs) {
@@ -14,7 +13,6 @@
return out;
}
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // AOS_VISION_BLOB_TRANSPOSE_H_
diff --git a/aos/vision/debug/debug_framework.h b/aos/vision/debug/debug_framework.h
index c2913c2..b9fa166 100644
--- a/aos/vision/debug/debug_framework.h
+++ b/aos/vision/debug/debug_framework.h
@@ -7,8 +7,7 @@
#include "aos/vision/image/camera_params.pb.h"
#include "aos/vision/image/image_types.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
class BlobStreamViewer;
@@ -120,7 +119,6 @@
void DebugFrameworkMain(int argc, char **argv, FilterHarness *filter,
CameraParams camera_params);
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // _AOS_VISION_DEBUG_DEBUG_FRAMEWORK_H_
diff --git a/aos/vision/debug/debug_window.h b/aos/vision/debug/debug_window.h
index 573cef5..dcbc5f7 100644
--- a/aos/vision/debug/debug_window.h
+++ b/aos/vision/debug/debug_window.h
@@ -8,8 +8,7 @@
#include "aos/vision/debug/overlay.h"
#include "aos/vision/image/image_types.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
// Implement Cairo version of RenderInterface.
class CairoRender : public RenderInterface {
@@ -84,7 +83,6 @@
std::unique_ptr<Internals> self;
};
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // AOS_VISION_DEBUG_DEBUG_WINDOW_H_
diff --git a/aos/vision/debug/overlay.h b/aos/vision/debug/overlay.h
index a2cecd5..3beb9e1 100644
--- a/aos/vision/debug/overlay.h
+++ b/aos/vision/debug/overlay.h
@@ -8,8 +8,7 @@
#include "aos/vision/math/segment.h"
#include "aos/vision/math/vector.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
// Abstract away rendering to avoid compiling gtk for arm.
// This should match a reduced cairo rendering api.
@@ -239,7 +238,6 @@
std::vector<std::pair<Vector<2>, double>> circles_;
};
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // _AOS_VISION_IMAGE_DEBUG_OVERLAY_H_
diff --git a/aos/vision/events/epoll_events.h b/aos/vision/events/epoll_events.h
index 7562f41..e3eeb85 100644
--- a/aos/vision/events/epoll_events.h
+++ b/aos/vision/events/epoll_events.h
@@ -11,8 +11,7 @@
#include "aos/scoped/scoped_fd.h"
#include "aos/time/time.h"
-namespace aos {
-namespace events {
+namespace aos::events {
class EpollLoop;
@@ -129,7 +128,6 @@
::std::vector<EpollWait *> waits_;
};
-} // namespace events
-} // namespace aos
+} // namespace aos::events
#endif // AOS_VISION_EVENTS_EPOLL_EVENTS_H_
diff --git a/aos/vision/events/socket_types.h b/aos/vision/events/socket_types.h
index 237bdb1..d3dcf42 100644
--- a/aos/vision/events/socket_types.h
+++ b/aos/vision/events/socket_types.h
@@ -12,8 +12,7 @@
#include "aos/vision/events/tcp_server.h"
#include "aos/vision/image/image_types.h"
-namespace aos {
-namespace events {
+namespace aos::events {
// Simple TCP client connection that sends messages prefixed by length.
// Useful to broadcast to a message all connected clients.
@@ -89,7 +88,6 @@
}
};
-} // namespace events
-} // namespace aos
+} // namespace aos::events
#endif // _AOS_VISION_EVENTS_SOCKET_TYPES_H_
diff --git a/aos/vision/events/tcp_client.h b/aos/vision/events/tcp_client.h
index 8aab2cc..16d7265 100644
--- a/aos/vision/events/tcp_client.h
+++ b/aos/vision/events/tcp_client.h
@@ -6,8 +6,7 @@
#include "aos/vision/events/epoll_events.h"
-namespace aos {
-namespace events {
+namespace aos::events {
// Handles the client connection logic to hostname:portno
class TcpClient : public EpollEvent {
@@ -17,7 +16,6 @@
// Implement ReadEvent from EpollEvent to use this class.
};
-} // namespace events
-} // namespace aos
+} // namespace aos::events
#endif // _AOS_VISION_DEBUG_TCP_CLIENT_H_
diff --git a/aos/vision/events/tcp_server.h b/aos/vision/events/tcp_server.h
index 24b4f60..49a5a8c 100644
--- a/aos/vision/events/tcp_server.h
+++ b/aos/vision/events/tcp_server.h
@@ -7,8 +7,7 @@
#include "aos/vision/events/epoll_events.h"
#include "aos/vision/events/intrusive_free_list.h"
-namespace aos {
-namespace events {
+namespace aos::events {
// Non-templatized base class of TCP server.
// TCPServer implements Construct which specializes the client connection
@@ -71,7 +70,6 @@
}
};
-} // namespace events
-} // namespace aos
+} // namespace aos::events
#endif // _AOS_VISION_EVENTS_TCP_SERVER_H_
diff --git a/aos/vision/events/udp.h b/aos/vision/events/udp.h
index 3c16b28..4acb04d 100644
--- a/aos/vision/events/udp.h
+++ b/aos/vision/events/udp.h
@@ -12,8 +12,7 @@
#include "aos/macros.h"
#include "aos/scoped/scoped_fd.h"
-namespace aos {
-namespace events {
+namespace aos::events {
// Simple wrapper around a transmitting UDP socket.
//
@@ -67,7 +66,6 @@
DISALLOW_COPY_AND_ASSIGN(RXUdpSocket);
};
-} // namespace events
-} // namespace aos
+} // namespace aos::events
#endif // AOS_VISION_EVENTS_UDP_H_
diff --git a/aos/vision/image/image_dataset.h b/aos/vision/image/image_dataset.h
index 7801cec..10ea13e 100644
--- a/aos/vision/image/image_dataset.h
+++ b/aos/vision/image/image_dataset.h
@@ -4,8 +4,7 @@
#include <string>
#include <vector>
-namespace aos {
-namespace vision {
+namespace aos::vision {
struct DatasetFrame {
// TODO: These should be V4L formats ideally.
@@ -17,7 +16,6 @@
DatasetFrame LoadFile(const std::string &jpeg_filename);
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // _AOS_VISION_IMAGE_IMAGE_DATASET_H_
diff --git a/aos/vision/image/image_stream.h b/aos/vision/image/image_stream.h
index 60e71b2..5a45c6f 100644
--- a/aos/vision/image/image_stream.h
+++ b/aos/vision/image/image_stream.h
@@ -7,8 +7,7 @@
#include "aos/vision/image/camera_params.pb.h"
#include "aos/vision/image/reader.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
// Converts a camera reader into a virtual base class that calls ProcessImage
// on each new image.
@@ -45,7 +44,6 @@
std::unique_ptr<::camera::Reader> reader_;
};
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // AOS_VISION_IMAGE_IMAGE_STREAM_H_
diff --git a/aos/vision/image/image_types.h b/aos/vision/image/image_types.h
index ee56f7d..80b802e 100644
--- a/aos/vision/image/image_types.h
+++ b/aos/vision/image/image_types.h
@@ -8,8 +8,7 @@
#include <sstream>
#include <string_view>
-namespace aos {
-namespace vision {
+namespace aos::vision {
// Bounding box for a RangeImage.
struct ImageBBox {
@@ -106,7 +105,6 @@
using ImagePtr = Array2dPtr<PixelRef>;
using ImageValue = ValueArray2d<PixelRef>;
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // _AOS_VISION_IMAGE_IMAGE_TYPES_H_
diff --git a/aos/vision/image/jpeg_routines.h b/aos/vision/image/jpeg_routines.h
index 59ad296..4bac976 100644
--- a/aos/vision/image/jpeg_routines.h
+++ b/aos/vision/image/jpeg_routines.h
@@ -8,8 +8,7 @@
#include "aos/vision/image/image_types.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
// Returns true if successful false if an error was encountered.
// Will decompress data into out. Out must be of the right size
@@ -32,7 +31,6 @@
return ProcessJpeg(data, value->data());
}
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // _AOS_VISION_IMAGE_JPEGROUTINES_H_
diff --git a/aos/vision/math/segment.h b/aos/vision/math/segment.h
index d6927cb..8ae91e3 100644
--- a/aos/vision/math/segment.h
+++ b/aos/vision/math/segment.h
@@ -5,8 +5,7 @@
#include "aos/vision/math/vector.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
template <int Size>
class Segment {
@@ -76,7 +75,6 @@
Vector<Size> B_;
};
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // AOS_VISION_COMP_GEO_VECTOR_H_
diff --git a/aos/vision/math/vector.h b/aos/vision/math/vector.h
index 5e7520f..ce29901 100644
--- a/aos/vision/math/vector.h
+++ b/aos/vision/math/vector.h
@@ -5,8 +5,7 @@
#include "Eigen/Dense"
-namespace aos {
-namespace vision {
+namespace aos::vision {
// Represents an n-dimensional vector of doubles with various convenient
// shortcuts for common operations.
@@ -222,7 +221,6 @@
return nv;
}
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // AOS_VISION_MATH_VECTOR_H_
diff --git a/frc971/analysis/BUILD b/frc971/analysis/BUILD
index 93f50f4..b179ad9 100644
--- a/frc971/analysis/BUILD
+++ b/frc971/analysis/BUILD
@@ -1,37 +1,7 @@
-load("//aos/flatbuffers:generate.bzl", "static_flatbuffer")
load("//tools/build_rules:js.bzl", "rollup_bundle", "ts_project")
-load("@com_github_google_flatbuffers//:typescript.bzl", "flatbuffer_ts_library")
-load("//aos:config.bzl", "aos_config")
package(default_visibility = ["//visibility:public"])
-cc_binary(
- name = "py_log_reader.so",
- srcs = ["py_log_reader.cc"],
- linkshared = True,
- target_compatible_with = ["@platforms//os:linux"],
- deps = [
- "//aos:configuration",
- "//aos:json_to_flatbuffer",
- "//aos/events:shm_event_loop",
- "//aos/events:simulated_event_loop",
- "//aos/events/logging:log_reader",
- "//third_party/python",
- "@com_github_google_glog//:glog",
- ],
-)
-
-py_test(
- name = "log_reader_test",
- srcs = ["log_reader_test.py"],
- data = [
- ":py_log_reader.so",
- "@sample_logfile//file",
- ],
- target_compatible_with = ["@platforms//os:linux"],
- deps = ["//aos:configuration_fbs_python"],
-)
-
ts_project(
name = "plot_index",
srcs = ["plot_index.ts"],
@@ -73,15 +43,6 @@
],
)
-genrule(
- name = "copy_css",
- srcs = [
- "//aos/network/www:styles.css",
- ],
- outs = ["styles.css"],
- cmd = "cp $< $@",
-)
-
filegroup(
name = "plotter_files",
srcs = [
@@ -112,67 +73,13 @@
target_compatible_with = ["@platforms//os:linux"],
)
-static_flatbuffer(
- name = "plot_data_fbs",
+genrule(
+ name = "copy_css",
srcs = [
- "plot_data.fbs",
+ "//aos/network/www:styles.css",
],
- target_compatible_with = ["@platforms//os:linux"],
-)
-
-flatbuffer_ts_library(
- name = "plot_data_ts_fbs",
- srcs = [
- "plot_data.fbs",
- ],
- target_compatible_with = ["@platforms//os:linux"],
-)
-
-ts_project(
- name = "plot_data_utils",
- srcs = ["plot_data_utils.ts"],
- visibility = ["//visibility:public"],
- deps = [
- ":plot_data_ts_fbs",
- "//aos:configuration_ts_fbs",
- "//aos/network/www:aos_plotter",
- "//aos/network/www:plotter",
- "//aos/network/www:proxy",
- "@com_github_google_flatbuffers//reflection:reflection_ts_fbs",
- "@com_github_google_flatbuffers//ts:flatbuffers_ts",
- ],
-)
-
-aos_config(
- name = "plotter",
- src = "plotter_config.json",
- flatbuffers = [":plot_data_fbs"],
- target_compatible_with = ["@platforms//os:linux"],
- deps = ["//aos/events:aos_config"],
-)
-
-cc_library(
- name = "in_process_plotter",
- srcs = ["in_process_plotter.cc"],
- hdrs = ["in_process_plotter.h"],
- data = [
- ":plotter",
- "//frc971/analysis/cpp_plot:cpp_plot_files",
- ],
- deps = [
- ":plot_data_fbs",
- "//aos/events:simulated_event_loop",
- "//aos/network:web_proxy",
- ],
-)
-
-cc_binary(
- name = "in_process_plotter_demo",
- srcs = ["in_process_plotter_demo.cc"],
- deps = [
- ":in_process_plotter",
- "//aos:init",
- ],
+ outs = ["styles.css"],
+ cmd = "cp $< $@",
)
cc_binary(
@@ -204,18 +111,6 @@
],
)
-cc_binary(
- name = "local_foxglove",
- srcs = ["local_foxglove.cc"],
- data = ["@foxglove_studio"],
- deps = [
- "//aos:init",
- "//aos/network:gen_embedded",
- "//aos/seasocks:seasocks_logger",
- "//third_party/seasocks",
- ],
-)
-
py_binary(
name = "trim_and_plot_foxglove",
srcs = ["trim_and_plot_foxglove.py"],
diff --git a/frc971/autonomous/base_autonomous_actor.h b/frc971/autonomous/base_autonomous_actor.h
index 403854f..15c88d4 100644
--- a/frc971/autonomous/base_autonomous_actor.h
+++ b/frc971/autonomous/base_autonomous_actor.h
@@ -13,8 +13,7 @@
#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
#include "y2019/control_loops/drivetrain/target_selector_generated.h"
-namespace frc971 {
-namespace autonomous {
+namespace frc971::autonomous {
class BaseAutonomousActor : public ::aos::common::actions::ActorBase<Goal> {
public:
@@ -156,7 +155,6 @@
int32_t goal_spline_handle_ = 0;
};
-} // namespace autonomous
-} // namespace frc971
+} // namespace frc971::autonomous
#endif // FRC971_AUTONOMOUS_BASE_AUTONOMOUS_ACTOR_H_
diff --git a/frc971/autonomous/user_button_localized_autonomous_actor.cc b/frc971/autonomous/user_button_localized_autonomous_actor.cc
index 5358a28..21fb42a 100644
--- a/frc971/autonomous/user_button_localized_autonomous_actor.cc
+++ b/frc971/autonomous/user_button_localized_autonomous_actor.cc
@@ -5,8 +5,7 @@
namespace this_thread = ::std::this_thread;
namespace drivetrain = frc971::control_loops::drivetrain;
-namespace frc971 {
-namespace autonomous {
+namespace frc971::autonomous {
UserButtonLocalizedAutonomousActor::UserButtonLocalizedAutonomousActor(
::aos::EventLoop *event_loop,
@@ -109,5 +108,4 @@
return Run(params);
}
-} // namespace autonomous
-} // namespace frc971
+} // namespace frc971::autonomous
diff --git a/frc971/autonomous/user_button_localized_autonomous_actor.h b/frc971/autonomous/user_button_localized_autonomous_actor.h
index 07d083a..3f6503d 100644
--- a/frc971/autonomous/user_button_localized_autonomous_actor.h
+++ b/frc971/autonomous/user_button_localized_autonomous_actor.h
@@ -14,8 +14,7 @@
#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
#include "y2019/control_loops/drivetrain/target_selector_generated.h"
-namespace frc971 {
-namespace autonomous {
+namespace frc971::autonomous {
class UserButtonLocalizedAutonomousActor : public BaseAutonomousActor {
public:
@@ -54,7 +53,6 @@
bool user_indicated_safe_to_reset_ = false;
};
-} // namespace autonomous
-} // namespace frc971
+} // namespace frc971::autonomous
#endif // FRC971_AUTONOMOUS_EXTENDED_AUTONOMOUS_ACTOR_H_
diff --git a/frc971/can_logger/asc_logger.h b/frc971/can_logger/asc_logger.h
index 19a1cb9..2be2eb2 100644
--- a/frc971/can_logger/asc_logger.h
+++ b/frc971/can_logger/asc_logger.h
@@ -10,8 +10,7 @@
#include "aos/events/event_loop.h"
#include "frc971/can_logger/can_logging_generated.h"
-namespace frc971 {
-namespace can_logger {
+namespace frc971::can_logger {
class AscLogger {
public:
@@ -33,7 +32,6 @@
aos::EventLoop *event_loop_;
};
-} // namespace can_logger
-} // namespace frc971
+} // namespace frc971::can_logger
#endif // FRC971_CAN_LOGGER_ASC_LOGGER_H_
diff --git a/frc971/can_logger/can_logger.cc b/frc971/can_logger/can_logger.cc
index ad885de..d7c2df7 100644
--- a/frc971/can_logger/can_logger.cc
+++ b/frc971/can_logger/can_logger.cc
@@ -7,6 +7,8 @@
std::string_view interface_name)
: fd_(socket(PF_CAN, SOCK_RAW | SOCK_NONBLOCK, CAN_RAW)),
frames_sender_(event_loop->MakeSender<CanFrame>(channel_name)) {
+ // TOOD(max): Figure out a proper priority
+ event_loop->SetRuntimeRealtimePriority(10);
struct ifreq ifr;
strcpy(ifr.ifr_name, interface_name.data());
PCHECK(ioctl(fd_.get(), SIOCGIFINDEX, &ifr) == 0)
diff --git a/frc971/can_logger/can_logger.h b/frc971/can_logger/can_logger.h
index 432bac8..a144265 100644
--- a/frc971/can_logger/can_logger.h
+++ b/frc971/can_logger/can_logger.h
@@ -16,8 +16,7 @@
#include "aos/scoped/scoped_fd.h"
#include "frc971/can_logger/can_logging_generated.h"
-namespace frc971 {
-namespace can_logger {
+namespace frc971::can_logger {
// This class listens to all the traffic on a SocketCAN interface and sends it
// on the aos event loop so it can be logged with the aos logging
@@ -45,7 +44,6 @@
aos::Sender<CanFrame> frames_sender_;
};
-} // namespace can_logger
-} // namespace frc971
+} // namespace frc971::can_logger
#endif // FRC971_CAN_LOGGER_CAN_LOGGER_H_
diff --git a/frc971/codelab/basic.h b/frc971/codelab/basic.h
index 3aac567..6439d84 100644
--- a/frc971/codelab/basic.h
+++ b/frc971/codelab/basic.h
@@ -8,8 +8,7 @@
#include "frc971/codelab/basic_status_generated.h"
#include "frc971/control_loops/control_loop.h"
-namespace frc971 {
-namespace codelab {
+namespace frc971::codelab {
class Basic
: public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
@@ -23,7 +22,6 @@
aos::Sender<Status>::Builder *status) override;
};
-} // namespace codelab
-} // namespace frc971
+} // namespace frc971::codelab
#endif // FRC971_CODELAB_BASIC_H_
diff --git a/frc971/control_loops/BUILD b/frc971/control_loops/BUILD
index 925dd43..9986fef 100644
--- a/frc971/control_loops/BUILD
+++ b/frc971/control_loops/BUILD
@@ -176,6 +176,30 @@
)
cc_library(
+ name = "encoder_fault_detector",
+ srcs = ["encoder_fault_detector.cc"],
+ hdrs = ["encoder_fault_detector.h"],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ ":encoder_fault_status_fbs",
+ "//aos/containers:sized_array",
+ "//aos/time",
+ "//frc971/control_loops:can_talonfx_fbs",
+ ],
+)
+
+cc_test(
+ name = "encoder_fault_detector_test",
+ srcs = ["encoder_fault_detector_test.cc"],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ ":encoder_fault_detector",
+ "//aos:json_to_flatbuffer",
+ "//aos/testing:googletest",
+ ],
+)
+
+cc_library(
name = "hall_effect_tracker",
hdrs = [
"hall_effect_tracker.h",
@@ -201,6 +225,20 @@
)
flatbuffer_ts_library(
+ name = "encoder_fault_status_ts_fbs",
+ srcs = [
+ "encoder_fault_status.fbs",
+ ],
+)
+
+static_flatbuffer(
+ name = "encoder_fault_status_fbs",
+ srcs = [
+ "encoder_fault_status.fbs",
+ ],
+)
+
+flatbuffer_ts_library(
name = "can_talonfx_ts_fbs",
srcs = [
"can_talonfx.fbs",
diff --git a/frc971/control_loops/c2d.h b/frc971/control_loops/c2d.h
index 7c1bf81..f80f88f 100644
--- a/frc971/control_loops/c2d.h
+++ b/frc971/control_loops/c2d.h
@@ -9,8 +9,7 @@
// We need to include MatrixFunctions for the matrix exponential.
#include "unsupported/Eigen/MatrixFunctions"
-namespace frc971 {
-namespace controls {
+namespace frc971::controls {
template <typename Scalar, int num_states, int num_inputs>
void C2D(const ::Eigen::Matrix<Scalar, num_states, num_states> &A_continuous,
@@ -116,7 +115,6 @@
*A_d = phi22t;
}
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls
#endif // FRC971_CONTROL_LOOPS_C2D_H_
diff --git a/frc971/control_loops/capped_test_plant.h b/frc971/control_loops/capped_test_plant.h
index 8b4cefd..4171719 100644
--- a/frc971/control_loops/capped_test_plant.h
+++ b/frc971/control_loops/capped_test_plant.h
@@ -5,8 +5,7 @@
#include "frc971/control_loops/state_feedback_loop.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// Basic state feedback plant for use in tests.
class CappedTestPlant : public StateFeedbackPlant<2, 1, 1> {
@@ -28,6 +27,5 @@
double voltage_offset_ = 0.0;
};
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_CAPPED_TEST_PLANT_H_
diff --git a/frc971/control_loops/coerce_goal.h b/frc971/control_loops/coerce_goal.h
index 6867540..3d34e94 100644
--- a/frc971/control_loops/coerce_goal.h
+++ b/frc971/control_loops/coerce_goal.h
@@ -5,8 +5,7 @@
#include "frc971/control_loops/polytope.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
template <typename Scalar = double>
Eigen::Matrix<Scalar, 2, 1> DoCoerceGoal(
@@ -127,7 +126,6 @@
}
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_COERCE_GOAL_H_
diff --git a/frc971/control_loops/control_loop-tmpl.h b/frc971/control_loops/control_loop-tmpl.h
index 7e20227..d86c97c 100644
--- a/frc971/control_loops/control_loop-tmpl.h
+++ b/frc971/control_loops/control_loop-tmpl.h
@@ -3,8 +3,7 @@
#include "aos/logging/logging.h"
-namespace frc971 {
-namespace controls {
+namespace frc971::controls {
// TODO(aschuh): Tests.
@@ -91,5 +90,4 @@
status.CheckSent();
}
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls
diff --git a/frc971/control_loops/control_loop.h b/frc971/control_loops/control_loop.h
index 3430dbd..c7b8a6d 100644
--- a/frc971/control_loops/control_loop.h
+++ b/frc971/control_loops/control_loop.h
@@ -11,8 +11,7 @@
#include "frc971/input/joystick_state_generated.h"
#include "frc971/input/robot_state_generated.h"
-namespace frc971 {
-namespace controls {
+namespace frc971::controls {
// Control loops run this often, "starting" at time 0.
constexpr ::std::chrono::nanoseconds kLoopFrequency =
@@ -133,8 +132,7 @@
SimpleLogInterval(kStaleLogInterval, ERROR, "no goal");
};
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls
#include "frc971/control_loops/control_loop-tmpl.h" // IWYU pragma: export
diff --git a/frc971/control_loops/control_loop_test.h b/frc971/control_loops/control_loop_test.h
index 00062b9..8b6ba09 100644
--- a/frc971/control_loops/control_loop_test.h
+++ b/frc971/control_loops/control_loop_test.h
@@ -16,8 +16,7 @@
#include "frc971/input/joystick_state_generated.h"
#include "frc971/input/robot_state_generated.h"
-namespace frc971 {
-namespace testing {
+namespace frc971::testing {
// Handles setting up the environment that all control loops need to actually
// run.
@@ -219,7 +218,6 @@
constexpr ::std::chrono::milliseconds
ControlLoopTestTemplated<TestBaseClass>::kDSPacketTime;
-} // namespace testing
-} // namespace frc971
+} // namespace frc971::testing
#endif // AOS_CONTROLS_CONTROL_LOOP_TEST_H_
diff --git a/frc971/control_loops/dlqr.h b/frc971/control_loops/dlqr.h
index 48e8474..57aa88b 100644
--- a/frc971/control_loops/dlqr.h
+++ b/frc971/control_loops/dlqr.h
@@ -3,8 +3,7 @@
#include <Eigen/Dense>
-namespace frc971 {
-namespace controls {
+namespace frc971::controls {
template <int num_states, int num_inputs>
int Controllability(const ::Eigen::Matrix<double, num_states, num_states> &A,
@@ -114,7 +113,6 @@
return INFO;
}
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls
#endif // FRC971_CONTROL_LOOPS_DLQR_H_
diff --git a/frc971/control_loops/double_jointed_arm/demo_path.h b/frc971/control_loops/double_jointed_arm/demo_path.h
index 9a9d393..691258b 100644
--- a/frc971/control_loops/double_jointed_arm/demo_path.h
+++ b/frc971/control_loops/double_jointed_arm/demo_path.h
@@ -5,15 +5,11 @@
#include "frc971/control_loops/double_jointed_arm/trajectory.h"
-namespace frc971 {
-namespace control_loops {
-namespace arm {
+namespace frc971::control_loops::arm {
::std::unique_ptr<Path> MakeDemoPath();
::std::unique_ptr<Path> MakeReversedDemoPath();
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm
#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_DEMO_PATH_H_
diff --git a/frc971/control_loops/double_jointed_arm/dynamics.h b/frc971/control_loops/double_jointed_arm/dynamics.h
index c6b078b..c28a20d 100644
--- a/frc971/control_loops/double_jointed_arm/dynamics.h
+++ b/frc971/control_loops/double_jointed_arm/dynamics.h
@@ -8,9 +8,7 @@
DECLARE_bool(gravity);
-namespace frc971 {
-namespace control_loops {
-namespace arm {
+namespace frc971::control_loops::arm {
struct ArmConstants {
// Below, 0 refers to the proximal joint, and 1 refers to the distal joint.
@@ -242,8 +240,6 @@
const double gamma_;
};
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm
#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_DYNAMICS_H_
diff --git a/frc971/control_loops/double_jointed_arm/ekf.h b/frc971/control_loops/double_jointed_arm/ekf.h
index 45e1641..f815807 100644
--- a/frc971/control_loops/double_jointed_arm/ekf.h
+++ b/frc971/control_loops/double_jointed_arm/ekf.h
@@ -5,9 +5,7 @@
#include "frc971/control_loops/double_jointed_arm/dynamics.h"
-namespace frc971 {
-namespace control_loops {
-namespace arm {
+namespace frc971::control_loops::arm {
// An extended kalman filter for the Arm.
// Our states are:
@@ -48,8 +46,6 @@
const Dynamics *dynamics_;
};
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm
#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_EKF_H_
diff --git a/frc971/control_loops/double_jointed_arm/graph.h b/frc971/control_loops/double_jointed_arm/graph.h
index 06d396c..c1c09ef 100644
--- a/frc971/control_loops/double_jointed_arm/graph.h
+++ b/frc971/control_loops/double_jointed_arm/graph.h
@@ -8,9 +8,7 @@
#include <memory>
#include <vector>
-namespace frc971 {
-namespace control_loops {
-namespace arm {
+namespace frc971::control_loops::arm {
// Grr... normal priority queues don't allow modifying the node cost.
// This relies on pointer stability for the passed in T.
@@ -181,8 +179,6 @@
size_t last_searched_vertex_ = std::numeric_limits<size_t>::max();
};
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm
#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_GRAPH_H_
diff --git a/frc971/control_loops/double_jointed_arm/test_constants.h b/frc971/control_loops/double_jointed_arm/test_constants.h
index 4ca2293..d71717d 100644
--- a/frc971/control_loops/double_jointed_arm/test_constants.h
+++ b/frc971/control_loops/double_jointed_arm/test_constants.h
@@ -3,10 +3,7 @@
#include "frc971/control_loops/double_jointed_arm/dynamics.h"
-namespace frc971 {
-namespace control_loops {
-namespace arm {
-namespace testing {
+namespace frc971::control_loops::arm::testing {
constexpr double kEfficiencyTweak = 0.95;
constexpr double kStallTorque = 1.41 * kEfficiencyTweak;
@@ -44,9 +41,6 @@
.num_distal_motors = 2.0,
};
-} // namespace testing
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm::testing
#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_TEST_CONSTANTS_H_
diff --git a/frc971/control_loops/double_jointed_arm/trajectory.h b/frc971/control_loops/double_jointed_arm/trajectory.h
index ca570d2..82cf2a7 100644
--- a/frc971/control_loops/double_jointed_arm/trajectory.h
+++ b/frc971/control_loops/double_jointed_arm/trajectory.h
@@ -10,9 +10,7 @@
#include "frc971/control_loops/double_jointed_arm/dynamics.h"
-namespace frc971 {
-namespace control_loops {
-namespace arm {
+namespace frc971::control_loops::arm {
// This class represents a path in theta0, theta1 space. It also returns the
// position, velocity and acceleration of the path as a function of path
@@ -439,8 +437,6 @@
int failed_solutions_ = 0;
};
-} // namespace arm
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::arm
#endif // FRC971_CONTROL_LOOPS_DOUBLE_JOINTED_ARM_TRAJECTORY_H_
diff --git a/frc971/control_loops/drivetrain/BUILD b/frc971/control_loops/drivetrain/BUILD
index 6f98839..afbce9b 100644
--- a/frc971/control_loops/drivetrain/BUILD
+++ b/frc971/control_loops/drivetrain/BUILD
@@ -606,8 +606,8 @@
target_compatible_with = ["@platforms//os:linux"],
deps = [
":spline",
+ "//aos/analysis:in_process_plotter",
"//aos/testing:googletest",
- "//frc971/analysis:in_process_plotter",
"@com_github_gflags_gflags//:gflags",
],
)
diff --git a/frc971/control_loops/drivetrain/camera.h b/frc971/control_loops/drivetrain/camera.h
index e1d4b76..6e87357 100644
--- a/frc971/control_loops/drivetrain/camera.h
+++ b/frc971/control_loops/drivetrain/camera.h
@@ -6,8 +6,7 @@
#include "aos/containers/sized_array.h"
#include "frc971/control_loops/pose.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// Represents a target on the field. Currently just consists of a pose and a
// indicator for whether it is occluded (occlusion is only used by the simulator
@@ -366,7 +365,6 @@
views->push_back(view);
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // Y2019_CONTROL_LOOPS_DRIVETRAIN_CAMERA_H_
diff --git a/frc971/control_loops/drivetrain/distance_spline.h b/frc971/control_loops/drivetrain/distance_spline.h
index 63156fe..5c404a0 100644
--- a/frc971/control_loops/drivetrain/distance_spline.h
+++ b/frc971/control_loops/drivetrain/distance_spline.h
@@ -11,9 +11,7 @@
#include "frc971/control_loops/drivetrain/trajectory_generated.h"
#include "frc971/control_loops/fixed_quadrature.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
std::vector<Spline> FlatbufferToSplines(const MultiSpline *fb);
@@ -127,8 +125,6 @@
absl::Span<const float> distances_;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_DISTANCE_SPLINE_H_
diff --git a/frc971/control_loops/drivetrain/drivetrain.h b/frc971/control_loops/drivetrain/drivetrain.h
index c92b7d7..87266f1 100644
--- a/frc971/control_loops/drivetrain/drivetrain.h
+++ b/frc971/control_loops/drivetrain/drivetrain.h
@@ -25,9 +25,7 @@
#include "frc971/wpilib/imu_batch_generated.h"
#include "frc971/zeroing/imu_zeroer.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
namespace chrono = std::chrono;
@@ -195,8 +193,6 @@
aos::SendFailureCounter status_failure_counter_;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_H_
diff --git a/frc971/control_loops/drivetrain/drivetrain_can_position.fbs b/frc971/control_loops/drivetrain/drivetrain_can_position.fbs
index b451ea9..29c0b85 100644
--- a/frc971/control_loops/drivetrain/drivetrain_can_position.fbs
+++ b/frc971/control_loops/drivetrain/drivetrain_can_position.fbs
@@ -1,9 +1,10 @@
include "frc971/control_loops/can_talonfx.fbs";
namespace frc971.control_loops.drivetrain;
+attribute "static_length";
// CAN readings from the CAN sensor reader loop
table CANPosition {
- talonfxs: [CANTalonFX] (id: 0);
+ talonfxs: [CANTalonFX] (id: 0, static_length: 6);
// The timestamp of the measurement on the canivore clock in nanoseconds
// This will have less jitter than the
diff --git a/frc971/control_loops/drivetrain/drivetrain_config.h b/frc971/control_loops/drivetrain/drivetrain_config.h
index 31c911a..8e0a58d 100644
--- a/frc971/control_loops/drivetrain/drivetrain_config.h
+++ b/frc971/control_loops/drivetrain/drivetrain_config.h
@@ -13,9 +13,7 @@
#include "frc971/control_loops/state_feedback_loop_converters.h"
#include "frc971/shifter_hall_effect.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
// Configuration for line-following mode.
struct LineFollowConfig {
@@ -236,8 +234,6 @@
};
}
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_CONSTANTS_H_
diff --git a/frc971/control_loops/drivetrain/drivetrain_test_lib.h b/frc971/control_loops/drivetrain/drivetrain_test_lib.h
index 4368b00..a79ba72 100644
--- a/frc971/control_loops/drivetrain/drivetrain_test_lib.h
+++ b/frc971/control_loops/drivetrain/drivetrain_test_lib.h
@@ -15,10 +15,7 @@
#include "frc971/queues/gyro_generated.h"
#include "frc971/wpilib/imu_batch_generated.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
-namespace testing {
+namespace frc971::control_loops::drivetrain::testing {
const DrivetrainConfig<double> &GetTestDrivetrainConfig();
@@ -174,9 +171,6 @@
double accel_sin_wave_magnitude_ = 0.0;
};
-} // namespace testing
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain::testing
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_TEST_LIB_H_
diff --git a/frc971/control_loops/drivetrain/drivetrain_uc.q.h b/frc971/control_loops/drivetrain/drivetrain_uc.q.h
index 95a2000..5b0bb83 100644
--- a/frc971/control_loops/drivetrain/drivetrain_uc.q.h
+++ b/frc971/control_loops/drivetrain/drivetrain_uc.q.h
@@ -4,8 +4,7 @@
#include "aos/macros.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
struct GearLogging {
GearLogging();
@@ -111,7 +110,6 @@
DrivetrainQueue_Status status;
};
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_Q_H_
diff --git a/frc971/control_loops/drivetrain/hybrid_ekf.h b/frc971/control_loops/drivetrain/hybrid_ekf.h
index 743e494..f784f2e 100644
--- a/frc971/control_loops/drivetrain/hybrid_ekf.h
+++ b/frc971/control_loops/drivetrain/hybrid_ekf.h
@@ -12,17 +12,11 @@
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
#include "frc971/control_loops/runge_kutta.h"
-namespace y2019 {
-namespace control_loops {
-namespace testing {
+namespace y2019::control_loops::testing {
class ParameterizedLocalizerTest;
-} // namespace testing
-} // namespace control_loops
-} // namespace y2019
+} // namespace y2019::control_loops::testing
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
namespace testing {
class HybridEkfTest;
@@ -934,8 +928,6 @@
P_.setZero();
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_HYBRID_EKF_H_
diff --git a/frc971/control_loops/drivetrain/improved_down_estimator.h b/frc971/control_loops/drivetrain/improved_down_estimator.h
index b5cc509..c778ad5 100644
--- a/frc971/control_loops/drivetrain/improved_down_estimator.h
+++ b/frc971/control_loops/drivetrain/improved_down_estimator.h
@@ -12,9 +12,7 @@
#include "frc971/control_loops/quaternion_utils.h"
#include "frc971/control_loops/runge_kutta.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
// Generates the sigma points to use in the UKF given the current estimate and
// covariance.
@@ -256,8 +254,6 @@
aos::monotonic_clock::time_point now);
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_IMPROVED_DOWN_ESTIMATOR_H_
diff --git a/frc971/control_loops/drivetrain/line_follow_drivetrain.h b/frc971/control_loops/drivetrain/line_follow_drivetrain.h
index bb2f7ae..245d0e9 100644
--- a/frc971/control_loops/drivetrain/line_follow_drivetrain.h
+++ b/frc971/control_loops/drivetrain/line_follow_drivetrain.h
@@ -12,9 +12,7 @@
#include "frc971/control_loops/profiled_subsystem_generated.h"
#include "y2019/control_loops/superstructure/superstructure_goal_generated.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
namespace testing {
class LineFollowDrivetrainTest;
@@ -93,8 +91,6 @@
friend class testing::LineFollowDrivetrainTest;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_LINE_FOLLOW_DRIVETRAIN_H_
diff --git a/frc971/control_loops/drivetrain/localization/puppet_localizer.h b/frc971/control_loops/drivetrain/localization/puppet_localizer.h
index 9b348a7..a3ebe1d 100644
--- a/frc971/control_loops/drivetrain/localization/puppet_localizer.h
+++ b/frc971/control_loops/drivetrain/localization/puppet_localizer.h
@@ -9,9 +9,7 @@
#include "frc971/control_loops/drivetrain/localization/localizer_output_generated.h"
#include "frc971/control_loops/drivetrain/localizer.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
// This class handles the localization for the 2022/2023 robots. Rather than
// actually doing any work on the roborio, we farm all the localization out to a
@@ -104,8 +102,6 @@
target_selector_;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_LOCALIZATION_PUPPET_LOCALIZER_H_
diff --git a/frc971/control_loops/drivetrain/localizer.h b/frc971/control_loops/drivetrain/localizer.h
index 867b3c0..6f5bf3d 100644
--- a/frc971/control_loops/drivetrain/localizer.h
+++ b/frc971/control_loops/drivetrain/localizer.h
@@ -7,9 +7,7 @@
#include "frc971/control_loops/drivetrain/hybrid_ekf.h"
#include "frc971/control_loops/pose.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
// An interface for target selection. This provides an object that will take in
// state updates and then determine what poes we should be driving to.
@@ -214,8 +212,6 @@
TrivialTargetSelector target_selector_;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_FIELD_ESTIMATOR_H_
diff --git a/frc971/control_loops/drivetrain/polydrivetrain.h b/frc971/control_loops/drivetrain/polydrivetrain.h
index a9dea7e..f4c608d 100644
--- a/frc971/control_loops/drivetrain/polydrivetrain.h
+++ b/frc971/control_loops/drivetrain/polydrivetrain.h
@@ -23,9 +23,7 @@
#include "frc971/control_loops/drivetrain/drivetrain_states.h"
#include "frc971/control_loops/state_feedback_loop.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
template <typename Scalar = double>
class PolyDrivetrain {
@@ -457,8 +455,6 @@
return builder.Finish();
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_POLYDRIVETRAIN_H_
diff --git a/frc971/control_loops/drivetrain/spline.h b/frc971/control_loops/drivetrain/spline.h
index 2c000bf..af42040 100644
--- a/frc971/control_loops/drivetrain/spline.h
+++ b/frc971/control_loops/drivetrain/spline.h
@@ -5,9 +5,7 @@
#include "frc971/control_loops/binomial.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
// Class to hold a spline as a function of alpha. Alpha can only range between
// 0.0 and 1.0.
@@ -190,8 +188,6 @@
return ans;
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_SPLINE_H_
diff --git a/frc971/control_loops/drivetrain/spline_test.cc b/frc971/control_loops/drivetrain/spline_test.cc
index 6d84d53..b47f4ac 100644
--- a/frc971/control_loops/drivetrain/spline_test.cc
+++ b/frc971/control_loops/drivetrain/spline_test.cc
@@ -5,7 +5,7 @@
#include "gflags/gflags.h"
#include "gtest/gtest.h"
-#include "frc971/analysis/in_process_plotter.h"
+#include "aos/analysis/in_process_plotter.h"
DEFINE_bool(plot, false, "If true, plot");
@@ -22,7 +22,7 @@
public:
static void SetUpTestSuite() {
if (FLAGS_plot) {
- plotter_ = std::make_unique<analysis::Plotter>();
+ plotter_ = std::make_unique<aos::analysis::Plotter>();
}
}
@@ -52,14 +52,14 @@
}
}
- static std::unique_ptr<analysis::Plotter> plotter_;
+ static std::unique_ptr<aos::analysis::Plotter> plotter_;
::Eigen::Matrix<double, 2, 4> control_points_;
NSpline<4> spline4_;
NSpline<6> spline6_;
};
-std::unique_ptr<analysis::Plotter> SplineTest::plotter_;
+std::unique_ptr<aos::analysis::Plotter> SplineTest::plotter_;
// Tests that the derivitives of xy integrate back up to the position.
TEST_F(SplineTest, XYIntegral) {
diff --git a/frc971/control_loops/drivetrain/splinedrivetrain.h b/frc971/control_loops/drivetrain/splinedrivetrain.h
index c528733..f02a5b6 100644
--- a/frc971/control_loops/drivetrain/splinedrivetrain.h
+++ b/frc971/control_loops/drivetrain/splinedrivetrain.h
@@ -17,9 +17,7 @@
#include "frc971/control_loops/drivetrain/spline.h"
#include "frc971/control_loops/drivetrain/trajectory.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
class SplineDrivetrain {
public:
@@ -111,8 +109,6 @@
bool output_was_capped_ = false;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_SPLINEDRIVETRAIN_H_
diff --git a/frc971/control_loops/drivetrain/ssdrivetrain.h b/frc971/control_loops/drivetrain/ssdrivetrain.h
index 77f1e25..7059f15 100644
--- a/frc971/control_loops/drivetrain/ssdrivetrain.h
+++ b/frc971/control_loops/drivetrain/ssdrivetrain.h
@@ -15,9 +15,7 @@
#include "frc971/control_loops/polytope.h"
#include "frc971/control_loops/state_feedback_loop.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
class DrivetrainMotorsSS {
public:
@@ -70,8 +68,6 @@
LocalizerInterface *localizer_;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_SSDRIVETRAIN_H_
diff --git a/frc971/control_loops/drivetrain/trajectory.h b/frc971/control_loops/drivetrain/trajectory.h
index b2cecc0..a9f14f6 100644
--- a/frc971/control_loops/drivetrain/trajectory.h
+++ b/frc971/control_loops/drivetrain/trajectory.h
@@ -14,9 +14,7 @@
#include "frc971/control_loops/runge_kutta.h"
#include "frc971/control_loops/state_feedback_loop.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
template <typename F>
double IntegrateAccelForDistance(const F &fn, double v, double x, double dx) {
@@ -423,8 +421,6 @@
.finished();
}
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_TRAJECTORY_H_
diff --git a/frc971/control_loops/drivetrain/trajectory_generator.h b/frc971/control_loops/drivetrain/trajectory_generator.h
index 234d386..5d638d3 100644
--- a/frc971/control_loops/drivetrain/trajectory_generator.h
+++ b/frc971/control_loops/drivetrain/trajectory_generator.h
@@ -6,9 +6,7 @@
#include "frc971/control_loops/drivetrain/spline_goal_generated.h"
#include "frc971/control_loops/drivetrain/trajectory.h"
-namespace frc971 {
-namespace control_loops {
-namespace drivetrain {
+namespace frc971::control_loops::drivetrain {
class TrajectoryGenerator {
public:
@@ -22,8 +20,6 @@
aos::Sender<fb::Trajectory> trajectory_sender_;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::drivetrain
#endif // FRC971_CONTROL_LOOPS_DRIVETRAIN_TRAJECTORY_GENERATOR_H_
diff --git a/frc971/control_loops/encoder_fault_detector.cc b/frc971/control_loops/encoder_fault_detector.cc
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/frc971/control_loops/encoder_fault_detector.cc
diff --git a/frc971/control_loops/encoder_fault_detector.h b/frc971/control_loops/encoder_fault_detector.h
new file mode 100644
index 0000000..0be3464
--- /dev/null
+++ b/frc971/control_loops/encoder_fault_detector.h
@@ -0,0 +1,127 @@
+#ifndef FRC971_CONTROL_LOOPS_ENCODER_FAULT_DETECTOR_H_
+#define FRC971_CONTROL_LOOPS_ENCODER_FAULT_DETECTOR_H_
+
+#include "aos/containers/sized_array.h"
+#include "aos/time/time.h"
+#include "frc971/control_loops/can_talonfx_generated.h"
+#include "frc971/control_loops/encoder_fault_status_generated.h"
+
+namespace frc971 {
+namespace control_loops {
+// The EncoderFaultDetector class will check for faults within a subsystem by
+// taking in an array of CAN encoder positions and an encoder position. When any
+// encoder gives a value that does not align with the others, the class will set
+// faulted to true
+template <uint8_t NumberofMotors>
+class EncoderFaultDetector {
+ public:
+ enum EncoderState {
+ SAME,
+ INCREASING,
+ DECREASING,
+ };
+
+ void Iterate(double encoder_position,
+ const flatbuffers::Vector<
+ flatbuffers::Offset<frc971::control_loops::CANTalonFX>>
+ *falcon_positions,
+ aos::monotonic_clock::time_point current_time);
+
+ void Iterate(double encoder_position,
+ aos::SizedArray<double, NumberofMotors> motor_positions,
+ aos::monotonic_clock::time_point current_time);
+
+ flatbuffers::Offset<EncoderFaultStatus> PopulateStatus(
+ flatbuffers::FlatBufferBuilder *fbb);
+
+ bool isfaulted() { return faulted_; }
+
+ private:
+ // The amount of time in milliseconds it will take before new data is ignored
+ static constexpr std::chrono::milliseconds kMaxTimeWithNoUpdate{10};
+ // Whether the encoders are faulted or not
+ bool faulted_ = false;
+ // The previous encoder position
+ double prev_encoder_position_;
+ // The previous motor positions
+ aos::SizedArray<double, NumberofMotors> prev_motor_positions_;
+ // A timestamp representing the last time data was updated
+ aos::monotonic_clock::time_point last_accepted_time_{
+ aos::monotonic_clock::min_time};
+};
+
+template <uint8_t NumberofMotors>
+void EncoderFaultDetector<NumberofMotors>::Iterate(
+ double encoder_position,
+ const flatbuffers::Vector<
+ flatbuffers::Offset<frc971::control_loops::CANTalonFX>>
+ *falcon_positions,
+ aos::monotonic_clock::time_point current_time) {
+ aos::SizedArray<double, NumberofMotors> motors;
+
+ for (const auto &motor : *falcon_positions) {
+ motors.push_back(motor->position());
+ }
+
+ Iterate(encoder_position, motors, current_time);
+}
+
+template <uint8_t NumberofMotors>
+void EncoderFaultDetector<NumberofMotors>::Iterate(
+ double encoder_position,
+ aos::SizedArray<double, NumberofMotors> motor_positions,
+ aos::monotonic_clock::time_point current_time) {
+ if (prev_motor_positions_.empty()) {
+ prev_encoder_position_ = encoder_position;
+ prev_motor_positions_ = motor_positions;
+ last_accepted_time_ = current_time;
+ return;
+ }
+
+ aos::monotonic_clock::duration time_elapsed =
+ current_time - last_accepted_time_;
+
+ // If more than 10 milliseconds has passed, then do not check for a fault
+ if (time_elapsed <= EncoderFaultDetector::kMaxTimeWithNoUpdate) {
+ constexpr auto get_encoder_state =
+ [](const double now, const double previous) -> EncoderState {
+ if (now > previous) {
+ return INCREASING;
+ }
+ if (now < previous) {
+ return DECREASING;
+ }
+ return SAME;
+ };
+
+ for (uint64_t i = 0; i < motor_positions.size(); i++) {
+ const EncoderState encoder =
+ get_encoder_state(encoder_position, prev_encoder_position_);
+ const EncoderState motor =
+ get_encoder_state(motor_positions[i], prev_motor_positions_[i]);
+
+ if (encoder != motor) { // If the encoder and the motor states are not
+ // the same set faulted to true
+ faulted_ = true;
+ }
+ }
+ }
+
+ prev_encoder_position_ = encoder_position;
+ prev_motor_positions_ = motor_positions;
+ last_accepted_time_ = current_time;
+}
+
+template <uint8_t NumberofMotors>
+flatbuffers::Offset<EncoderFaultStatus>
+EncoderFaultDetector<NumberofMotors>::PopulateStatus(
+ flatbuffers::FlatBufferBuilder *fbb) {
+ EncoderFaultStatus::Builder builder(*fbb);
+ builder.add_faulted(faulted_);
+ return builder.Finish();
+}
+
+} // namespace control_loops
+} // namespace frc971
+
+#endif // FRC971_CONTROL_LOOPS_ENCODER_FAULT_DETECTOR_H_
\ No newline at end of file
diff --git a/frc971/control_loops/encoder_fault_detector_test.cc b/frc971/control_loops/encoder_fault_detector_test.cc
new file mode 100644
index 0000000..a4974ef
--- /dev/null
+++ b/frc971/control_loops/encoder_fault_detector_test.cc
@@ -0,0 +1,244 @@
+#include "frc971/control_loops/encoder_fault_detector.h"
+
+#include "gtest/gtest.h"
+
+#include "aos/json_to_flatbuffer.h"
+
+namespace frc971 {
+namespace control_loops {
+namespace testing {
+
+// Test for simulating if encoder values are idle.
+TEST(EncoderFaultDetector, Idle) {
+ EncoderFaultDetector<2> detector;
+ aos::monotonic_clock::time_point t;
+
+ double encoder_position = 0.0;
+ aos::SizedArray<double, 2> falcon_positions = {0.0, 0.0};
+
+ for (int i = 0; i < 10; i++) {
+ detector.Iterate(encoder_position, falcon_positions, t);
+ t += std::chrono::milliseconds(5);
+ }
+
+ EXPECT_FALSE(detector.isfaulted());
+}
+
+// Test for simulating if we have three motors
+TEST(EncoderFaultDetector, ThreeMotors) {
+ EncoderFaultDetector<3> detector;
+ aos::monotonic_clock::time_point t;
+
+ double encoder_position = 0.0;
+ aos::SizedArray<double, 3> falcon_positions = {0.0, 0.0, 0.0};
+
+ for (int i = 0; i < 10; i++) {
+ detector.Iterate(encoder_position, falcon_positions, t);
+ t += std::chrono::milliseconds(5);
+ }
+
+ EXPECT_FALSE(detector.isfaulted());
+}
+
+// Test for simulating faulting with three motors
+TEST(EncoderFaultDetector, FaultThreeMotors) {
+ EncoderFaultDetector<3> detector;
+ aos::monotonic_clock::time_point t;
+
+ double encoder_position = 0.0;
+ aos::SizedArray<double, 3> falcon_positions = {0.0, 0.0, 0.0};
+
+ for (int i = 0; i < 10; i++) {
+ for (double &falcon : falcon_positions) {
+ falcon++;
+ }
+ detector.Iterate(encoder_position, falcon_positions, t);
+ t += std::chrono::milliseconds(5);
+ }
+
+ EXPECT_TRUE(detector.isfaulted());
+}
+
+// Test for simulating if encoder values are increasing.
+TEST(EncoderFaultDetector, Increasing) {
+ EncoderFaultDetector<2> detector;
+ aos::monotonic_clock::time_point t;
+
+ double encoder_position = 0.0;
+ aos::SizedArray<double, 2> falcon_positions = {0.0, 0.0};
+
+ for (int i = 0; i < 10; ++i) {
+ detector.Iterate(encoder_position, falcon_positions, t);
+ encoder_position++;
+ for (double &falcon : falcon_positions) {
+ falcon++;
+ }
+ t += std::chrono::milliseconds(5);
+ }
+
+ EXPECT_FALSE(detector.isfaulted());
+}
+
+// Test for simulating if encoder values are decreasing.
+TEST(EncoderFaultDetector, Decreasing) {
+ EncoderFaultDetector<2> detector;
+ aos::monotonic_clock::time_point t;
+
+ double encoder_position = 0.0;
+ aos::SizedArray<double, 2> falcon_positions = {0.0, 0.0};
+
+ for (int i = 0; i < 10; ++i) {
+ detector.Iterate(encoder_position, falcon_positions, t);
+ encoder_position--;
+ for (double &falcon : falcon_positions) {
+ falcon--;
+ }
+ t += std::chrono::milliseconds(5);
+ }
+
+ EXPECT_FALSE(detector.isfaulted());
+}
+
+// Test for simulating if only falcon values are increasing.
+TEST(EncoderFaultDetector, FalconsOnlyIncrease) {
+ EncoderFaultDetector<2> detector;
+ aos::monotonic_clock::time_point t;
+
+ double encoder_position = 0.0;
+ aos::SizedArray<double, 2> falcon_positions = {0.0, 0.0};
+
+ for (int i = 0; i < 5; ++i) {
+ detector.Iterate(encoder_position, falcon_positions, t);
+ for (double &falcon : falcon_positions) {
+ falcon++;
+ }
+ t += std::chrono::milliseconds(5);
+ }
+
+ EXPECT_TRUE(detector.isfaulted());
+}
+
+// Test for simulating if only encoder value is increasing.
+TEST(EncoderFaultDetector, EncoderOnlyIncrease) {
+ EncoderFaultDetector<2> detector;
+ aos::monotonic_clock::time_point t;
+
+ double encoder_position = 0.0;
+ aos::SizedArray<double, 2> falcon_positions = {0.0, 0.0};
+
+ for (int i = 0; i < 5; ++i) {
+ detector.Iterate(encoder_position, falcon_positions, t);
+ encoder_position++;
+ t += std::chrono::milliseconds(5);
+ }
+
+ EXPECT_TRUE(detector.isfaulted());
+}
+
+// Test for simulating if only one falcon value is increasing at a time.
+TEST(EncoderFaultDetector, OnlyOneFalconIncreases) {
+ EncoderFaultDetector<2> detector;
+ aos::monotonic_clock::time_point t;
+
+ double encoder_position = 0.0;
+ aos::SizedArray<double, 2> falcon_positions = {0.0, 0.0};
+
+ for (int i = 0; i < 5; ++i) {
+ detector.Iterate(encoder_position, falcon_positions, t);
+ falcon_positions[0] += 0.1;
+ t += std::chrono::milliseconds(5);
+ }
+
+ for (int i = 0; i < 5; ++i) {
+ detector.Iterate(encoder_position, falcon_positions, t);
+ falcon_positions[1] += 0.1;
+ t += std::chrono::milliseconds(5);
+ }
+
+ EXPECT_TRUE(detector.isfaulted());
+}
+
+// Test checks that the detector stays faulted after a fault if the encoder
+// positions align again
+TEST(EncoderFaultDetector, StaysFaulted) {
+ EncoderFaultDetector<2> detector;
+ aos::monotonic_clock::time_point t;
+
+ double encoder_position = 0.0;
+ aos::SizedArray<double, 2> falcon_positions = {0.0, 0.0};
+
+ for (int i = 0; i < 5; ++i) {
+ detector.Iterate(encoder_position, falcon_positions, t);
+ encoder_position += 0.1;
+ t += std::chrono::milliseconds(5);
+ }
+
+ EXPECT_TRUE(detector.isfaulted());
+
+ for (int i = 0; i < 5; ++i) {
+ detector.Iterate(encoder_position, falcon_positions, t);
+ encoder_position += 0.1;
+ for (double &falcon : falcon_positions) {
+ falcon += 0.1;
+ }
+ t += std::chrono::milliseconds(5);
+ }
+
+ EXPECT_TRUE(detector.isfaulted());
+}
+
+// Tests that after 10 milliseconds updates will not register
+TEST(EncoderFaultDetector, NoUpdateForTooLong) {
+ EncoderFaultDetector<2> detector;
+ aos::monotonic_clock::time_point t;
+
+ double encoder_position = 0.0;
+ aos::SizedArray<double, 2> falcon_positions = {0.0, 0.0};
+
+ for (int i = 0; i < 5; ++i) {
+ detector.Iterate(encoder_position, falcon_positions, t);
+ encoder_position += 0.1;
+ t += std::chrono::milliseconds(11);
+ }
+
+ EXPECT_FALSE(detector.isfaulted());
+}
+
+// Tests if populate status function is working as expected
+TEST(EncoderFaultDetector, PopulateStatus) {
+ EncoderFaultDetector<2> detector;
+ aos::monotonic_clock::time_point t;
+
+ double encoder_position = 0.0;
+ aos::SizedArray<double, 2> falcon_positions = {0.0, 0.0};
+
+ for (int i = 0; i < 10; ++i) {
+ detector.Iterate(encoder_position, falcon_positions, t);
+ encoder_position++;
+ for (double &falcon : falcon_positions) {
+ falcon++;
+ }
+ t += std::chrono::milliseconds(5);
+ }
+
+ flatbuffers::FlatBufferBuilder fbb;
+ fbb.Finish(detector.PopulateStatus(&fbb));
+ aos::FlatbufferDetachedBuffer<EncoderFaultStatus> result = fbb.Release();
+
+ EXPECT_EQ("{ \"faulted\": false }", aos::FlatbufferToJson(result));
+
+ for (int i = 0; i < 5; ++i) {
+ detector.Iterate(encoder_position, falcon_positions, t);
+ encoder_position++;
+ t += std::chrono::milliseconds(5);
+ }
+
+ fbb.Finish(detector.PopulateStatus(&fbb));
+ result = fbb.Release();
+
+ EXPECT_EQ("{ \"faulted\": true }", aos::FlatbufferToJson(result));
+}
+
+} // namespace testing
+} // namespace control_loops
+} // namespace frc971
\ No newline at end of file
diff --git a/frc971/control_loops/encoder_fault_status.fbs b/frc971/control_loops/encoder_fault_status.fbs
new file mode 100644
index 0000000..ad3d360
--- /dev/null
+++ b/frc971/control_loops/encoder_fault_status.fbs
@@ -0,0 +1,11 @@
+namespace frc971.control_loops;
+
+// EncoderFaultStatus table contains boolean for when subsystem is faulted
+
+// TODO (niko): Add a boolean representing whether new date is "stale"
+// meaning that it is currently being ignored due to it
+// coming in slower than the 10 millisecond timeframe
+
+table EncoderFaultStatus {
+ faulted:bool (id : 0);
+}
\ No newline at end of file
diff --git a/frc971/control_loops/fixed_quadrature.h b/frc971/control_loops/fixed_quadrature.h
index 53bb0dc..88d52e8 100644
--- a/frc971/control_loops/fixed_quadrature.h
+++ b/frc971/control_loops/fixed_quadrature.h
@@ -5,8 +5,7 @@
#include <Eigen/Dense>
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// Implements Gaussian Quadrature integration (5th order). fn is the function
// to integrate. It must take 1 argument of type T. The integration is between
@@ -57,7 +56,6 @@
return answer;
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_FIXED_QUADRATURE_H_
diff --git a/frc971/control_loops/flywheel/flywheel_controller.h b/frc971/control_loops/flywheel/flywheel_controller.h
index db8baeb..49a4385 100644
--- a/frc971/control_loops/flywheel/flywheel_controller.h
+++ b/frc971/control_loops/flywheel/flywheel_controller.h
@@ -9,9 +9,7 @@
#include "frc971/control_loops/hybrid_state_feedback_loop.h"
#include "frc971/control_loops/state_feedback_loop.h"
-namespace frc971 {
-namespace control_loops {
-namespace flywheel {
+namespace frc971::control_loops::flywheel {
class CurrentLimitedStateFeedbackController;
@@ -73,8 +71,6 @@
DISALLOW_COPY_AND_ASSIGN(FlywheelController);
};
-} // namespace flywheel
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::flywheel
#endif // FRC971_CONTROL_LOOPS_SHOOTER_FLYWHEEL_CONTROLLER_H_
diff --git a/frc971/control_loops/flywheel/flywheel_controller_test.cc b/frc971/control_loops/flywheel/flywheel_controller_test.cc
index 26aabc9..eaac6e6 100644
--- a/frc971/control_loops/flywheel/flywheel_controller_test.cc
+++ b/frc971/control_loops/flywheel/flywheel_controller_test.cc
@@ -9,10 +9,7 @@
#include "frc971/control_loops/flywheel/flywheel_test_plant.h"
#include "frc971/control_loops/flywheel/integral_flywheel_controller_test_plant.h"
-namespace frc971 {
-namespace control_loops {
-namespace flywheel {
-namespace testing {
+namespace frc971::control_loops::flywheel::testing {
class FlywheelTest : public ::frc971::testing::ControlLoopTest {
public:
FlywheelTest()
@@ -97,7 +94,4 @@
RunFor(std::chrono::seconds(8));
VerifyNearGoal();
}
-} // namespace testing
-} // namespace flywheel
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::flywheel::testing
diff --git a/frc971/control_loops/flywheel/flywheel_test_plant.h b/frc971/control_loops/flywheel/flywheel_test_plant.h
index 01e347d..269e147 100644
--- a/frc971/control_loops/flywheel/flywheel_test_plant.h
+++ b/frc971/control_loops/flywheel/flywheel_test_plant.h
@@ -3,9 +3,7 @@
#include "frc971/control_loops/flywheel/flywheel_controller.h"
-namespace frc971 {
-namespace control_loops {
-namespace flywheel {
+namespace frc971::control_loops::flywheel {
class FlywheelPlant : public StateFeedbackPlant<2, 1, 1> {
public:
@@ -40,8 +38,6 @@
double resistance_;
};
-} // namespace flywheel
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::flywheel
#endif // FRC971_CONTROL_LOOPS_FLYWHEEL_FLYWHEEL_TEST_PLANT_H_
diff --git a/frc971/control_loops/gaussian_noise.h b/frc971/control_loops/gaussian_noise.h
index dce60fb..a784df0 100644
--- a/frc971/control_loops/gaussian_noise.h
+++ b/frc971/control_loops/gaussian_noise.h
@@ -6,8 +6,7 @@
#include <memory>
#include <random>
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
class GaussianNoise {
public:
@@ -28,7 +27,6 @@
std::normal_distribution<double> distribution_;
};
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_GAUSSIAN_NOISE_H_
diff --git a/frc971/control_loops/jacobian.h b/frc971/control_loops/jacobian.h
index 0940c6c..5442ec8 100644
--- a/frc971/control_loops/jacobian.h
+++ b/frc971/control_loops/jacobian.h
@@ -3,8 +3,7 @@
#include <Eigen/Dense>
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
template <int num_states, int num_inputs, typename F>
::Eigen::Matrix<double, num_states, num_inputs> NumericalJacobian(
@@ -46,7 +45,6 @@
U);
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_JACOBIAN_H_
diff --git a/frc971/control_loops/polytope.h b/frc971/control_loops/polytope.h
index 794219b..cba25f6 100644
--- a/frc971/control_loops/polytope.h
+++ b/frc971/control_loops/polytope.h
@@ -14,8 +14,7 @@
#include "glog/logging.h"
#endif // __linux__
-namespace frc971 {
-namespace controls {
+namespace frc971::controls {
// A number_of_dimensions dimensional polytope.
// This represents the region consisting of all points X such that H * X <= k.
@@ -238,7 +237,6 @@
}
#endif // __linux__
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls
#endif // AOS_CONTROLS_POLYTOPE_H_
diff --git a/frc971/control_loops/pose.h b/frc971/control_loops/pose.h
index 1eccf28..6570e9c 100644
--- a/frc971/control_loops/pose.h
+++ b/frc971/control_loops/pose.h
@@ -7,8 +7,7 @@
#include "aos/util/math.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// Constructs a homogeneous transformation matrix for rotating about the Z axis.
template <typename Scalar>
@@ -231,7 +230,6 @@
typedef TypedLineSegment<double> LineSegment;
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_POSE_H_
diff --git a/frc971/control_loops/position_sensor_sim.h b/frc971/control_loops/position_sensor_sim.h
index fae0e7d..a2d765e 100644
--- a/frc971/control_loops/position_sensor_sim.h
+++ b/frc971/control_loops/position_sensor_sim.h
@@ -7,8 +7,7 @@
#include "frc971/control_loops/control_loops_generated.h"
#include "frc971/control_loops/gaussian_noise.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// NOTE: All potentiometer and encoder values in this class are assumed to be in
// translated SI units.
@@ -211,7 +210,6 @@
double negedge_value_;
};
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif /* FRC971_CONTROL_LOOPS_POSITION_SENSOR_SIM_H_ */
diff --git a/frc971/control_loops/profiled_subsystem.h b/frc971/control_loops/profiled_subsystem.h
index 2a15201..7a0b7fa 100644
--- a/frc971/control_loops/profiled_subsystem.h
+++ b/frc971/control_loops/profiled_subsystem.h
@@ -18,8 +18,7 @@
#include "frc971/zeroing/pot_and_index.h"
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// TODO(Brian): Use a tuple instead of an array to support heterogeneous zeroing
// styles.
@@ -466,7 +465,6 @@
internal::UseUnlessZero(max_angular_acceleration, default_acceleration_));
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_PROFILED_SUBSYSTEM_H_
diff --git a/frc971/control_loops/quaternion_utils.h b/frc971/control_loops/quaternion_utils.h
index e97935c..e96f5f1 100644
--- a/frc971/control_loops/quaternion_utils.h
+++ b/frc971/control_loops/quaternion_utils.h
@@ -5,8 +5,7 @@
#include "Eigen/Geometry"
#include "glog/logging.h"
-namespace frc971 {
-namespace controls {
+namespace frc971::controls {
// Function to compute the quaternion average of a bunch of quaternions. Each
// column in the input matrix is a quaternion (optionally scaled by it's
@@ -93,7 +92,6 @@
return QuaternionDerivativeDerivitive(q.coeffs());
}
-} // namespace controls
-} // namespace frc971
+} // namespace frc971::controls
#endif // AOS_CONTROLS_QUATERNION_UTILS_H_
diff --git a/frc971/control_loops/runge_kutta.h b/frc971/control_loops/runge_kutta.h
index 7fa3f3e..ed5a359 100644
--- a/frc971/control_loops/runge_kutta.h
+++ b/frc971/control_loops/runge_kutta.h
@@ -3,8 +3,7 @@
#include <Eigen/Dense>
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// Implements Runge Kutta integration (4th order). fn is the function to
// integrate. It must take 1 argument of type T. The integration starts at an
@@ -67,7 +66,6 @@
return X + dt / 6.0 * (k1 + 2.0 * k2 + 2.0 * k3 + k4);
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_RUNGE_KUTTA_H_
diff --git a/frc971/control_loops/simple_capped_state_feedback_loop.h b/frc971/control_loops/simple_capped_state_feedback_loop.h
index b2049a6..c159e15 100644
--- a/frc971/control_loops/simple_capped_state_feedback_loop.h
+++ b/frc971/control_loops/simple_capped_state_feedback_loop.h
@@ -5,8 +5,7 @@
#include "frc971/control_loops/state_feedback_loop.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// A StateFeedbackLoop which implements CapU based on a simple set of maximum
// absolute values for each element of U.
@@ -74,7 +73,6 @@
::Eigen::Array<double, number_of_inputs, 1> max_voltages_;
};
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_SIMPLE_CAPPED_STATE_FEEDBACK_LOOP_H_
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 05a011a..069914e 100644
--- a/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h
+++ b/frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h
@@ -6,8 +6,7 @@
#include "frc971/control_loops/profiled_subsystem_static.h"
#include "frc971/control_loops/state_feedback_loop_converters.h"
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
inline void PopulateStaticZeroingSingleDOFProfiledSubsystemGoal(
StaticZeroingSingleDOFProfiledSubsystemGoalStatic *goal_table,
@@ -442,7 +441,6 @@
return status_builder.Finish();
}
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_STATIC_ZEROING_SINGLE_DOF_PROFILED_SUBSYSTEM_H_
diff --git a/frc971/control_loops/team_number_test_environment.h b/frc971/control_loops/team_number_test_environment.h
index 5c95c28..6e7dea8 100644
--- a/frc971/control_loops/team_number_test_environment.h
+++ b/frc971/control_loops/team_number_test_environment.h
@@ -3,9 +3,7 @@
#include "gtest/gtest.h"
-namespace frc971 {
-namespace control_loops {
-namespace testing {
+namespace frc971::control_loops::testing {
// The team number we use for tests.
static const int kTeamNumber = 1;
@@ -23,8 +21,6 @@
__attribute__((unused)) static ::testing::Environment *const team_number_env =
::testing::AddGlobalTestEnvironment(new TeamNumberEnvironment());
-} // namespace testing
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops::testing
#endif // FRC971_CONTROL_LOOPS_TEAM_NUMBER_TEST_ENVIRONMENT_H_
diff --git a/frc971/control_loops/voltage_cap/voltage_cap.h b/frc971/control_loops/voltage_cap/voltage_cap.h
index ad4e4c6c..f30d5af 100644
--- a/frc971/control_loops/voltage_cap/voltage_cap.h
+++ b/frc971/control_loops/voltage_cap/voltage_cap.h
@@ -3,8 +3,7 @@
#include <cstdio>
-namespace frc971 {
-namespace control_loops {
+namespace frc971::control_loops {
// This function maintains the difference of power between two voltages passed
// in that are outside of our range of possible voltage output.
@@ -27,7 +26,6 @@
void VoltageCap(double voltage_one, double voltage_two, double *out_voltage_one,
double *out_voltage_two);
-} // namespace control_loops
-} // namespace frc971
+} // namespace frc971::control_loops
#endif // FRC971_CONTROL_LOOPS_VOLTAGE_CAP_VOLTAGE_CAP_H_
diff --git a/frc971/imu_fdcan/Dual_IMU/Core/BUILD b/frc971/imu_fdcan/Dual_IMU/Core/BUILD
index 1982395..9ebb287 100644
--- a/frc971/imu_fdcan/Dual_IMU/Core/BUILD
+++ b/frc971/imu_fdcan/Dual_IMU/Core/BUILD
@@ -43,6 +43,9 @@
"-Wno-unused-but-set-variable",
],
includes = ["Inc"],
+ linkopts = [
+ "-u _printf_float",
+ ],
deps = [
":startup",
"//frc971/imu_fdcan/Dual_IMU/Drivers/STM32G4xx_HAL_Driver:hal_driver",
diff --git a/frc971/imu_fdcan/README.md b/frc971/imu_fdcan/README.md
index 95db097..8e82f73 100644
--- a/frc971/imu_fdcan/README.md
+++ b/frc971/imu_fdcan/README.md
@@ -22,4 +22,9 @@
2) To change code:
* The main code lives in [`Dual_IMU/Core/Src`](/Dual_IMU/Core/Src/). Make sure your changes happen inside sections marked `/* USER CODE BEGIN ... */` `/* USER CODE END ... */`. Code outside these markers will be overwritten by CubeIDE when generating code after changes to the `.ioc` file.
3) Build + Run:
- * Open CubeIDE GUI to build, debug, or run.
\ No newline at end of file
+ * Option 1: Open CubeIDE GUI to build, debug, or run.
+ * Option 2:
+ 1) SSH onto the build server.
+ 2) Run `bazel build -c opt --config=cortex-m4f-imu //frc971/imu_fdcan/Dual_IMU/Core:main.elf`. The output .elf file should be in bazel-bin/frc971/imu_fdcan/Dual_IMU/Core.
+ 3) (If deploying code locally) Move file to local directory. For example: `scp <username>@build.frc971.org:<path/to/main.elf> <local/path/to/save/file/`. A good spot to put this locally is ./Dual_IMU/Debug/.
+ 3) Open CubeProgrammer. Click the + tab next to "Device memory". Select the generated elf file. Click "Download".
\ No newline at end of file
diff --git a/frc971/input/action_joystick_input.h b/frc971/input/action_joystick_input.h
index f77f416..ac37c2a 100644
--- a/frc971/input/action_joystick_input.h
+++ b/frc971/input/action_joystick_input.h
@@ -8,8 +8,7 @@
#include "frc971/input/drivetrain_input.h"
#include "frc971/input/joystick_input.h"
-namespace frc971 {
-namespace input {
+namespace frc971::input {
// Class to abstract out managing actions, autonomous mode, and drivetrains.
// Turns out we do the same thing every year, so let's stop copying it.
@@ -139,7 +138,6 @@
::aos::Fetcher<::frc971::autonomous::AutonomousMode> autonomous_mode_fetcher_;
};
-} // namespace input
-} // namespace frc971
+} // namespace frc971::input
#endif // AOS_INPUT_ACTION_JOYSTICK_INPUT_H_
diff --git a/frc971/input/driver_station_data.h b/frc971/input/driver_station_data.h
index 5ebf8f4..7d8dc3e 100644
--- a/frc971/input/driver_station_data.h
+++ b/frc971/input/driver_station_data.h
@@ -9,9 +9,7 @@
#include "frc971/input/joystick_state_generated.h"
-namespace frc971 {
-namespace input {
-namespace driver_station {
+namespace frc971::input::driver_station {
// Represents a feature of a joystick (a button or an axis).
// All indices are 1-based.
@@ -126,8 +124,6 @@
SavedJoystickState current_values_, old_values_;
};
-} // namespace driver_station
-} // namespace input
-} // namespace frc971
+} // namespace frc971::input::driver_station
#endif // AOS_INPUT_DRIVER_STATION_DATA_H_
diff --git a/frc971/input/drivetrain_input.h b/frc971/input/drivetrain_input.h
index 0cb724d..173c551 100644
--- a/frc971/input/drivetrain_input.h
+++ b/frc971/input/drivetrain_input.h
@@ -13,8 +13,7 @@
#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
#include "frc971/input/driver_station_data.h"
-namespace frc971 {
-namespace input {
+namespace frc971::input {
using control_loops::drivetrain::PistolBottomButtonUse;
using control_loops::drivetrain::PistolSecondButtonUse;
@@ -271,7 +270,6 @@
const ::frc971::input::driver_station::Data &data) override;
};
-} // namespace input
-} // namespace frc971
+} // namespace frc971::input
#endif // AOS_INPUT_DRIVETRAIN_INPUT_H_
diff --git a/frc971/input/joystick_input.h b/frc971/input/joystick_input.h
index 074908d..b6d0ceb 100644
--- a/frc971/input/joystick_input.h
+++ b/frc971/input/joystick_input.h
@@ -6,8 +6,7 @@
#include "aos/events/event_loop.h"
#include "frc971/input/driver_station_data.h"
-namespace frc971 {
-namespace input {
+namespace frc971::input {
// A class for handling joystick packet values.
// It will call RunIteration each time a new packet is received.
@@ -40,7 +39,6 @@
int mode_;
};
-} // namespace input
-} // namespace frc971
+} // namespace frc971::input
#endif // AOS_INPUT_JOYSTICK_INPUT_H_
diff --git a/frc971/input/redundant_joystick_data.h b/frc971/input/redundant_joystick_data.h
index c6cdb78..56fc6b5 100644
--- a/frc971/input/redundant_joystick_data.h
+++ b/frc971/input/redundant_joystick_data.h
@@ -3,9 +3,7 @@
#include "frc971/input/driver_station_data.h"
-namespace frc971 {
-namespace input {
-namespace driver_station {
+namespace frc971::input::driver_station {
// A class to wrap driver_station::Data and map logical joystick numbers to
// their actual numbers in the order they are on the driverstation.
@@ -51,8 +49,6 @@
const Data &data_;
};
-} // namespace driver_station
-} // namespace input
-} // namespace frc971
+} // namespace frc971::input::driver_station
#endif // AOS_INPUT_REDUNDANT_JOYSTICK_DATA_H_
diff --git a/frc971/orin/apriltag.h b/frc971/orin/apriltag.h
index f87e107..d3e041b 100644
--- a/frc971/orin/apriltag.h
+++ b/frc971/orin/apriltag.h
@@ -12,8 +12,7 @@
#include "frc971/orin/line_fit_filter.h"
#include "frc971/orin/points.h"
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
// Class to find the blob index of a point in a point vector.
class BlobExtentsIndexFinder {
@@ -326,7 +325,6 @@
zarray_t *detections_ = nullptr;
};
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
#endif // FRC971_ORIN_APRILTAG_H_
diff --git a/frc971/orin/cuda.h b/frc971/orin/cuda.h
index 2cc8f44..0e44fb4 100644
--- a/frc971/orin/cuda.h
+++ b/frc971/orin/cuda.h
@@ -17,8 +17,7 @@
LOG(FATAL) << "Check failed: " #condition " (" << cudaGetErrorString(c) \
<< ") "
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
// Class to manage the lifetime of a Cuda stream. This is used to provide
// relative ordering between kernels on the same stream.
@@ -205,7 +204,6 @@
void MaybeCheckAndSynchronize();
void MaybeCheckAndSynchronize(std::string_view message);
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
#endif // FRC971_ORIN_CUDA_H_
diff --git a/frc971/orin/gpu_apriltag.cc b/frc971/orin/gpu_apriltag.cc
index 1642aa3..89625b6 100644
--- a/frc971/orin/gpu_apriltag.cc
+++ b/frc971/orin/gpu_apriltag.cc
@@ -36,7 +36,7 @@
// Set max age on image for processing at 20 ms. For 60Hz, we should be
// processing at least every 16.7ms
constexpr aos::monotonic_clock::duration kMaxImageAge =
- std::chrono::milliseconds(20);
+ std::chrono::milliseconds(50);
namespace chrono = std::chrono;
@@ -57,15 +57,19 @@
},
kMaxImageAge),
target_map_sender_(
- event_loop->MakeSender<frc971::vision::TargetMap>("/camera")),
+ event_loop->MakeSender<frc971::vision::TargetMap>(channel_name)),
image_annotations_sender_(
- event_loop->MakeSender<foxglove::ImageAnnotations>("/camera")),
+ event_loop->MakeSender<foxglove::ImageAnnotations>(channel_name)),
rejections_(0) {
image_callback_.set_format(frc971::vision::ImageCallback::Format::YUYV2);
extrinsics_ = frc971::vision::CameraExtrinsics(calibration_);
intrinsics_ = frc971::vision::CameraIntrinsics(calibration_);
dist_coeffs_ = frc971::vision::CameraDistCoeffs(calibration_);
+
+ projection_matrix_ = cv::Mat::zeros(3, 4, CV_64F);
+ intrinsics_.rowRange(0, 3).colRange(0, 3).copyTo(
+ projection_matrix_.rowRange(0, 3).colRange(0, 3));
}
ApriltagDetector::~ApriltagDetector() {
diff --git a/frc971/orin/line_fit_filter.h b/frc971/orin/line_fit_filter.h
index 0c37f0b..7ecc553 100644
--- a/frc971/orin/line_fit_filter.h
+++ b/frc971/orin/line_fit_filter.h
@@ -8,8 +8,7 @@
#include "device_launch_parameters.h"
#include "frc971/orin/cuda.h"
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
// Class to hold the extents of a blob of points.
struct MinMaxExtents {
@@ -160,7 +159,6 @@
// The max number of work elements for a max maxes of 10.
constexpr size_t MaxRankedIndex() { return 210; }
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
#endif // FRC971_ORIN_LINE_FIT_FILTER_H_
diff --git a/frc971/orin/points.h b/frc971/orin/points.h
index d530a17..745e151 100644
--- a/frc971/orin/points.h
+++ b/frc971/orin/points.h
@@ -11,8 +11,7 @@
#include "cuda_runtime.h"
#include "device_launch_parameters.h"
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
// Class to hold the 2 adjacent blob IDs, a point in decimated image space, the
// half pixel offset, and the gradient.
@@ -297,7 +296,6 @@
}
};
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
#endif // FRC971_ORIN_POINTS_H_
diff --git a/frc971/orin/threshold.h b/frc971/orin/threshold.h
index 5cdc3a2..03eb59a 100644
--- a/frc971/orin/threshold.h
+++ b/frc971/orin/threshold.h
@@ -5,8 +5,7 @@
#include "frc971/orin/cuda.h"
-namespace frc971 {
-namespace apriltag {
+namespace frc971::apriltag {
// Converts to grayscale, decimates, and thresholds an image on the provided
// stream.
@@ -16,7 +15,6 @@
uint8_t *thresholded_image, size_t width, size_t height,
size_t min_white_black_diff, CudaStream *stream);
-} // namespace apriltag
-} // namespace frc971
+} // namespace frc971::apriltag
#endif // FRC971_ORIN_THRESHOLD_H_
diff --git a/frc971/shooter_interpolation/interpolation.h b/frc971/shooter_interpolation/interpolation.h
index bce532f..26b141f 100644
--- a/frc971/shooter_interpolation/interpolation.h
+++ b/frc971/shooter_interpolation/interpolation.h
@@ -5,8 +5,7 @@
#include <utility>
#include <vector>
-namespace frc971 {
-namespace shooter_interpolation {
+namespace frc971::shooter_interpolation {
double Blend(double coefficient, double a1, double a2);
@@ -79,7 +78,6 @@
}
}
-} // namespace shooter_interpolation
-} // namespace frc971
+} // namespace frc971::shooter_interpolation
#endif // FRC971_SHOOTER_INTERPOLATION_INTERPOLATION_H_
diff --git a/frc971/solvers/convex.h b/frc971/solvers/convex.h
index 3de357c..d8989d8 100644
--- a/frc971/solvers/convex.h
+++ b/frc971/solvers/convex.h
@@ -10,8 +10,7 @@
#include "glog/logging.h"
#include <Eigen/Dense>
-namespace frc971 {
-namespace solvers {
+namespace frc971::solvers {
// TODO(austin): Steal JET from Ceres to generate the derivatives easily and
// quickly?
@@ -379,7 +378,6 @@
}
}
-}; // namespace solvers
-}; // namespace frc971
+} // namespace frc971::solvers
#endif // FRC971_SOLVERS_CONVEX_H_
diff --git a/frc971/solvers/sparse_convex.h b/frc971/solvers/sparse_convex.h
index 9695431..074f2f3 100644
--- a/frc971/solvers/sparse_convex.h
+++ b/frc971/solvers/sparse_convex.h
@@ -9,8 +9,7 @@
#include "glog/logging.h"
#include <Eigen/Sparse>
-namespace frc971 {
-namespace solvers {
+namespace frc971::solvers {
// TODO(austin): Steal JET from Ceres to generate the derivatives easily and
// quickly?
@@ -118,7 +117,6 @@
std::string_view prefix, int verbosity);
};
-} // namespace solvers
-} // namespace frc971
+} // namespace frc971::solvers
#endif // FRC971_SOLVERS_SPARSE_CONVEX_H_
diff --git a/frc971/vision/BUILD b/frc971/vision/BUILD
index 5d8bf7c..6cee780 100644
--- a/frc971/vision/BUILD
+++ b/frc971/vision/BUILD
@@ -131,7 +131,6 @@
":foxglove_image_converter_lib",
"//aos:init",
"//aos/events/logging:log_reader",
- "//frc971/analysis:in_process_plotter",
"//frc971/control_loops/drivetrain:improved_down_estimator",
"//frc971/vision:visualize_robot",
"//frc971/wpilib:imu_batch_fbs",
@@ -142,6 +141,12 @@
"@com_google_absl//absl/strings:str_format",
"@com_google_ceres_solver//:ceres",
"@org_tuxfamily_eigen//:eigen",
+ ] + [
+ # TODO(Stephan): This is a whacky hack. If we include this
+ # in the proper spot above (alphabetically), then we get a
+ # linker error: duplicate symbol: crc32.
+ # It's part of both @zlib and @com_github_rawrtc_re.
+ "//aos/analysis:in_process_plotter",
],
)
diff --git a/frc971/vision/calibration_accumulator.h b/frc971/vision/calibration_accumulator.h
index 9a6f483..550b691 100644
--- a/frc971/vision/calibration_accumulator.h
+++ b/frc971/vision/calibration_accumulator.h
@@ -12,8 +12,7 @@
#include "frc971/vision/foxglove_image_converter_lib.h"
#include "frc971/wpilib/imu_batch_generated.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
// This class provides an interface for an application to be notified of all
// camera and IMU samples in order with the correct timestamps.
@@ -143,7 +142,6 @@
frc971::IMUValuesT last_value_;
};
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // FRC971_VISION_CALIBRATION_ACCUMULATOR_H_
diff --git a/frc971/vision/ceres/pose_graph_3d_error_term.h b/frc971/vision/ceres/pose_graph_3d_error_term.h
index 4dd5fbd..217b2a9 100644
--- a/frc971/vision/ceres/pose_graph_3d_error_term.h
+++ b/frc971/vision/ceres/pose_graph_3d_error_term.h
@@ -36,8 +36,7 @@
#include "types.h"
-namespace ceres {
-namespace examples {
+namespace ceres::examples {
// Computes the error term for two poses that have a relative pose measurement
// between them. Let the hat variables be the measurement. We have two poses x_a
@@ -133,7 +132,6 @@
const double weight_;
};
-} // namespace examples
-} // namespace ceres
+} // namespace ceres::examples
#endif // EXAMPLES_CERES_POSE_GRAPH_3D_ERROR_TERM_H_
diff --git a/frc971/vision/ceres/read_g2o.h b/frc971/vision/ceres/read_g2o.h
index 69fa16a..c427939 100644
--- a/frc971/vision/ceres/read_g2o.h
+++ b/frc971/vision/ceres/read_g2o.h
@@ -38,8 +38,7 @@
#include "glog/logging.h"
-namespace ceres {
-namespace examples {
+namespace ceres::examples {
// Reads a single pose from the input and inserts it into the map. Returns false
// if there is a duplicate entry.
@@ -136,7 +135,6 @@
return true;
}
-} // namespace examples
-} // namespace ceres
+} // namespace ceres::examples
#endif // EXAMPLES_CERES_READ_G2O_H_
diff --git a/frc971/vision/ceres/types.h b/frc971/vision/ceres/types.h
index 17e9bd3..9c1e495 100644
--- a/frc971/vision/ceres/types.h
+++ b/frc971/vision/ceres/types.h
@@ -39,8 +39,7 @@
#include "Eigen/Core"
#include "Eigen/Geometry"
-namespace ceres {
-namespace examples {
+namespace ceres::examples {
struct Pose3d {
Eigen::Vector3d p;
@@ -104,7 +103,6 @@
typedef std::vector<Constraint3d, Eigen::aligned_allocator<Constraint3d>>
VectorOfConstraints;
-} // namespace examples
-} // namespace ceres
+} // namespace ceres::examples
#endif // EXAMPLES_CERES_TYPES_H_
diff --git a/frc971/vision/charuco_lib.h b/frc971/vision/charuco_lib.h
index 62923db..aac25ee 100644
--- a/frc971/vision/charuco_lib.h
+++ b/frc971/vision/charuco_lib.h
@@ -17,8 +17,7 @@
DECLARE_bool(visualize);
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
// Class to find extrinsics for a specified pi's camera using the provided
// training data.
@@ -211,7 +210,6 @@
const foxglove::PointsAnnotationType line_type =
foxglove::PointsAnnotationType::POINTS);
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // Y2020_VISION_CHARUCO_LIB_H_
diff --git a/frc971/vision/extrinsics_calibration.cc b/frc971/vision/extrinsics_calibration.cc
index 6017258..619ea89 100644
--- a/frc971/vision/extrinsics_calibration.cc
+++ b/frc971/vision/extrinsics_calibration.cc
@@ -7,8 +7,8 @@
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc.hpp>
+#include "aos/analysis/in_process_plotter.h"
#include "aos/time/time.h"
-#include "frc971/analysis/in_process_plotter.h"
#include "frc971/control_loops/runge_kutta.h"
#include "frc971/vision/calibration_accumulator.h"
#include "frc971/vision/charuco_lib.h"
@@ -393,7 +393,7 @@
// TODO<Jim>: Could probably still do a bit more work on naming
// conventions and what is being shown here
- frc971::analysis::Plotter plotter;
+ aos::analysis::Plotter plotter;
plotter.AddFigure("bot (imu) position");
plotter.AddLine(times_, x, "x_hat(0)");
plotter.AddLine(times_, y, "x_hat(1)");
diff --git a/frc971/vision/extrinsics_calibration.h b/frc971/vision/extrinsics_calibration.h
index f6c3ccc..97d719f 100644
--- a/frc971/vision/extrinsics_calibration.h
+++ b/frc971/vision/extrinsics_calibration.h
@@ -6,8 +6,7 @@
#include "frc971/vision/calibration_accumulator.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
struct CalibrationParameters {
Eigen::Quaternion<double> initial_orientation =
@@ -55,7 +54,6 @@
void Visualize(const CalibrationData &data,
const CalibrationParameters &calibration_parameters);
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // FRC971_VISION_EXTRINSICS_CALIBRATION_H_
diff --git a/frc971/vision/intrinsics_calibration_lib.h b/frc971/vision/intrinsics_calibration_lib.h
index 3076ed9..7f08138 100644
--- a/frc971/vision/intrinsics_calibration_lib.h
+++ b/frc971/vision/intrinsics_calibration_lib.h
@@ -16,8 +16,7 @@
#include "aos/util/file.h"
#include "frc971/vision/charuco_lib.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
class IntrinsicsCalibration {
public:
@@ -76,6 +75,5 @@
aos::ExitHandle *exit_handle_;
};
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // FRC971_VISION_CALIBRATION_LIB_H_
diff --git a/frc971/vision/media_device.h b/frc971/vision/media_device.h
index a2a86fe..31d0882 100644
--- a/frc971/vision/media_device.h
+++ b/frc971/vision/media_device.h
@@ -16,8 +16,7 @@
#include "aos/scoped/scoped_fd.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
class MediaDevice;
class Pad;
@@ -254,7 +253,6 @@
// nullopt otherwise.
std::optional<MediaDevice> FindMediaDevice(std::string_view device);
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // FRC971_VISION_MEDIA_DEVICE_H_
diff --git a/frc971/vision/v4l2_reader.h b/frc971/vision/v4l2_reader.h
index 6338ba5..a3d6252 100644
--- a/frc971/vision/v4l2_reader.h
+++ b/frc971/vision/v4l2_reader.h
@@ -16,8 +16,7 @@
#include "aos/util/threaded_consumer.h"
#include "frc971/vision/vision_generated.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
// Reads images from a V4L2 capture device (aka camera).
class V4L2ReaderBase {
@@ -199,7 +198,6 @@
aos::util::ThreadedConsumer<int, kNumberBuffers> buffer_requeuer_;
};
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // FRC971_VISION_V4L2_READER_H_
diff --git a/frc971/vision/visualize_robot.h b/frc971/vision/visualize_robot.h
index c679dba..af2dcef 100644
--- a/frc971/vision/visualize_robot.h
+++ b/frc971/vision/visualize_robot.h
@@ -7,8 +7,7 @@
#include <opencv2/highgui.hpp>
#include <opencv2/imgproc.hpp>
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
// Helper class to visualize the coordinate frames associated with
// the robot Based on a virtual camera viewpoint, and camera model,
@@ -80,7 +79,6 @@
// DrawFrameAxes
cv::Size default_size_; // Default image size
};
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // FRC971_VISION_VISUALIZE_ROBOT_H_
diff --git a/frc971/wpilib/ADIS16448.h b/frc971/wpilib/ADIS16448.h
index 6d5eb28..ed8e091 100644
--- a/frc971/wpilib/ADIS16448.h
+++ b/frc971/wpilib/ADIS16448.h
@@ -17,8 +17,7 @@
#include "frc971/wpilib/imu_generated.h"
#include "frc971/wpilib/spi_rx_clearer.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Handles interfacing with an Analog Devices ADIS16448 Inertial Sensor over
// SPI and sending values out on a queue.
@@ -100,7 +99,6 @@
FpgaTimeConverter time_converter_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_ADIS16448_H_
diff --git a/frc971/wpilib/ADIS16470.h b/frc971/wpilib/ADIS16470.h
index 35bcb06..c15ca5b 100644
--- a/frc971/wpilib/ADIS16470.h
+++ b/frc971/wpilib/ADIS16470.h
@@ -12,8 +12,7 @@
#include "frc971/wpilib/imu_batch_generated.h"
#include "frc971/wpilib/imu_generated.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Handles interfacing with an Analog Devices ADIS16470 over SPI and sending the
// resulting values out on a channel.
@@ -93,7 +92,6 @@
FpgaTimeConverter time_converter_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_ADIS16470_H_
diff --git a/frc971/wpilib/buffered_pcm.h b/frc971/wpilib/buffered_pcm.h
index f743371..4933c25 100644
--- a/frc971/wpilib/buffered_pcm.h
+++ b/frc971/wpilib/buffered_pcm.h
@@ -7,8 +7,7 @@
#include "frc971/wpilib/buffered_solenoid.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Manages setting values for all solenoids for a single PCM in a single CAN
// message.
@@ -43,7 +42,6 @@
friend class BufferedSolenoid;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_BUFFERED_PCM_H_
diff --git a/frc971/wpilib/can_drivetrain_writer.h b/frc971/wpilib/can_drivetrain_writer.h
index 1c0ba95..987605d 100644
--- a/frc971/wpilib/can_drivetrain_writer.h
+++ b/frc971/wpilib/can_drivetrain_writer.h
@@ -3,8 +3,7 @@
#include "frc971/wpilib/loop_output_handler.h"
#include "frc971/wpilib/talonfx.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class CANDrivetrainWriter : public ::frc971::wpilib::LoopOutputHandler<
::frc971::control_loops::drivetrain::Output> {
@@ -30,5 +29,4 @@
std::vector<std::shared_ptr<TalonFX>> left_talonfxs_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/can_sensor_reader.h b/frc971/wpilib/can_sensor_reader.h
index 8ef5fd1..8eddfca 100644
--- a/frc971/wpilib/can_sensor_reader.h
+++ b/frc971/wpilib/can_sensor_reader.h
@@ -9,8 +9,7 @@
#include "aos/realtime.h"
#include "frc971/wpilib/talonfx.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class CANSensorReader {
public:
CANSensorReader(
@@ -37,6 +36,5 @@
// Callback used to send the CANPosition flatbuffer
std::function<void(ctre::phoenix::StatusCode status)> flatbuffer_callback_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_CAN_SENSOR_READER_H_
diff --git a/frc971/wpilib/dma_edge_counting.h b/frc971/wpilib/dma_edge_counting.h
index f51318d..eda77f0 100644
--- a/frc971/wpilib/dma_edge_counting.h
+++ b/frc971/wpilib/dma_edge_counting.h
@@ -14,8 +14,7 @@
#include "frc971/wpilib/dma.h"
#undef ERROR
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Generic interface for classes that do something with DMA samples and also
// poll current sensor values.
@@ -280,7 +279,6 @@
DISALLOW_COPY_AND_ASSIGN(DMASynchronizer);
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_DMA_EDGE_COUNTING_H_
diff --git a/frc971/wpilib/drivetrain_writer.h b/frc971/wpilib/drivetrain_writer.h
index 195b5a3..e83585e 100644
--- a/frc971/wpilib/drivetrain_writer.h
+++ b/frc971/wpilib/drivetrain_writer.h
@@ -6,8 +6,7 @@
#include "frc971/wpilib/ahal/PWM.h"
#include "frc971/wpilib/loop_output_handler.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class DrivetrainWriter : public ::frc971::wpilib::LoopOutputHandler<
::frc971::control_loops::drivetrain::Output> {
@@ -56,7 +55,6 @@
bool reversed_right0_, reversed_left0_, reversed_right1_, reversed_left1_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_DRIVETRAIN_WRITER_H_
diff --git a/frc971/wpilib/encoder_and_potentiometer.h b/frc971/wpilib/encoder_and_potentiometer.h
index 7ee85e1..a5eac24 100644
--- a/frc971/wpilib/encoder_and_potentiometer.h
+++ b/frc971/wpilib/encoder_and_potentiometer.h
@@ -14,8 +14,7 @@
#include "frc971/wpilib/dma.h"
#include "frc971/wpilib/dma_edge_counting.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Latches values from an encoder on positive edges from another input using
// DMA.
@@ -244,7 +243,6 @@
::std::unique_ptr<frc::Encoder> encoder_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_ENCODER_AND_POTENTIOMETER_H_
diff --git a/frc971/wpilib/fpga_time_conversion.h b/frc971/wpilib/fpga_time_conversion.h
index 51cc7a9..c279089 100644
--- a/frc971/wpilib/fpga_time_conversion.h
+++ b/frc971/wpilib/fpga_time_conversion.h
@@ -9,8 +9,7 @@
#include "aos/time/time.h"
#include "hal/cpp/fpga_clock.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Returns the offset from the monotonic clock to the FPGA time. This is defined
// as `fpga_time - monotonic_time`.
@@ -51,7 +50,6 @@
std::chrono::nanoseconds offset_ = std::chrono::nanoseconds::min();
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_FPGA_TIME_CONVERSION_H_
diff --git a/frc971/wpilib/generic_can_writer.h b/frc971/wpilib/generic_can_writer.h
index 7d6dd1a..d339324 100644
--- a/frc971/wpilib/generic_can_writer.h
+++ b/frc971/wpilib/generic_can_writer.h
@@ -5,8 +5,7 @@
#include "frc971/wpilib/loop_output_handler.h"
#include "frc971/wpilib/talonfx.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
/// This class uses a callback whenever it writes so that the caller can use any
/// flatbuffer to write to the talonfx motor.
@@ -70,5 +69,4 @@
write_callback_;
};
-} // namespace wpilib
-} // namespace frc971
\ No newline at end of file
+} // namespace frc971::wpilib
diff --git a/frc971/wpilib/gyro_interface.h b/frc971/wpilib/gyro_interface.h
index 3568a47..0c6b519 100644
--- a/frc971/wpilib/gyro_interface.h
+++ b/frc971/wpilib/gyro_interface.h
@@ -6,8 +6,7 @@
#include "frc971/wpilib/ahal/SPI.h"
#undef ERROR
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class GyroInterface {
public:
@@ -50,7 +49,6 @@
::std::unique_ptr<frc::SPI> gyro_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_GYRO_INTERFACE_H_
diff --git a/frc971/wpilib/gyro_sender.h b/frc971/wpilib/gyro_sender.h
index 4abfeaa..1c3f5d6 100644
--- a/frc971/wpilib/gyro_sender.h
+++ b/frc971/wpilib/gyro_sender.h
@@ -12,8 +12,7 @@
#include "frc971/wpilib/gyro_interface.h"
#include "frc971/zeroing/averager.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Handles reading the gyro over SPI and sending out angles on a queue.
//
@@ -56,7 +55,6 @@
bool zeroed_ = false;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_GYRO_H_
diff --git a/frc971/wpilib/interrupt_edge_counting.h b/frc971/wpilib/interrupt_edge_counting.h
index 5ea8df5..5d64582 100644
--- a/frc971/wpilib/interrupt_edge_counting.h
+++ b/frc971/wpilib/interrupt_edge_counting.h
@@ -12,8 +12,7 @@
#include "frc971/wpilib/ahal/DigitalInput.h"
#include "frc971/wpilib/ahal/Encoder.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class InterruptSynchronizer;
@@ -226,7 +225,6 @@
DISALLOW_COPY_AND_ASSIGN(InterruptSynchronizer);
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_INTERRUPT_EDGE_COUNTING_H_
diff --git a/frc971/wpilib/joystick_sender.h b/frc971/wpilib/joystick_sender.h
index c9eb4cd..0591a8e 100644
--- a/frc971/wpilib/joystick_sender.h
+++ b/frc971/wpilib/joystick_sender.h
@@ -6,8 +6,7 @@
#include "aos/events/shm_event_loop.h"
#include "frc971/input/joystick_state_generated.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class JoystickSender {
public:
@@ -19,7 +18,6 @@
const uint16_t team_id_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_JOYSTICK_SENDER_H_
diff --git a/frc971/wpilib/loop_output_handler.h b/frc971/wpilib/loop_output_handler.h
index 5f66a4c..1fb46b2 100644
--- a/frc971/wpilib/loop_output_handler.h
+++ b/frc971/wpilib/loop_output_handler.h
@@ -9,8 +9,7 @@
#include "aos/time/time.h"
#include "aos/util/log_interval.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Handles sending the output from a single control loop to the hardware.
//
@@ -64,7 +63,6 @@
::aos::TimerHandler *timer_handler_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_LOOP_OUTPUT_HANDLER_H_
diff --git a/frc971/wpilib/pdp_fetcher.h b/frc971/wpilib/pdp_fetcher.h
index 72f6745..38c4a5b 100644
--- a/frc971/wpilib/pdp_fetcher.h
+++ b/frc971/wpilib/pdp_fetcher.h
@@ -12,8 +12,7 @@
class PowerDistributionPanel;
} // namespace frc
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Handles fetching values from the PDP.
class PDPFetcher {
@@ -32,7 +31,6 @@
::std::unique_ptr<::frc::PowerDistributionPanel> pdp_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_PDP_FETCHER_H_
diff --git a/frc971/wpilib/sensor_reader.h b/frc971/wpilib/sensor_reader.h
index bf8c96a..455ed0e 100644
--- a/frc971/wpilib/sensor_reader.h
+++ b/frc971/wpilib/sensor_reader.h
@@ -21,8 +21,7 @@
using ::aos::monotonic_clock;
namespace chrono = ::std::chrono;
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class SensorReader {
public:
@@ -264,7 +263,6 @@
chrono::microseconds period_ = chrono::microseconds(5000);
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_SENSOR_READER_H_
diff --git a/frc971/wpilib/spi_rx_clearer.h b/frc971/wpilib/spi_rx_clearer.h
index e385d21..733cf6f 100644
--- a/frc971/wpilib/spi_rx_clearer.h
+++ b/frc971/wpilib/spi_rx_clearer.h
@@ -3,8 +3,7 @@
#include <cstdint>
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Allows clearing the RX FIFO of the roboRIO's SPI peripheral on demand. This
// is necessary to work around a driver bug. See
@@ -35,7 +34,6 @@
bool RxFifoIsEmpty() { return !(ReadRegister(4) & (1 << 4)); }
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_SPI_RX_CLEARER_H_
diff --git a/frc971/wpilib/swerve/swerve_drivetrain_writer.h b/frc971/wpilib/swerve/swerve_drivetrain_writer.h
index d02d4dc..8e9e616 100644
--- a/frc971/wpilib/swerve/swerve_drivetrain_writer.h
+++ b/frc971/wpilib/swerve/swerve_drivetrain_writer.h
@@ -9,9 +9,7 @@
#include "frc971/wpilib/swerve/swerve_module.h"
#include "frc971/wpilib/talonfx.h"
-namespace frc971 {
-namespace wpilib {
-namespace swerve {
+namespace frc971::wpilib::swerve {
// Reads from the swerve output flatbuffer and uses wpilib to set the current
// for each motor.
@@ -45,8 +43,6 @@
double max_voltage_;
};
-} // namespace swerve
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib::swerve
#endif // FRC971_WPILIB_SWERVE_DRIVETRAIN_WRITER_H_
diff --git a/frc971/wpilib/swerve/swerve_module.h b/frc971/wpilib/swerve/swerve_module.h
index d65547a..c373a31 100644
--- a/frc971/wpilib/swerve/swerve_module.h
+++ b/frc971/wpilib/swerve/swerve_module.h
@@ -3,9 +3,7 @@
#include "frc971/wpilib/talonfx.h"
-namespace frc971 {
-namespace wpilib {
-namespace swerve {
+namespace frc971::wpilib::swerve {
struct SwerveModule {
SwerveModule(TalonFXParams rotation_params, TalonFXParams translation_params,
@@ -39,7 +37,5 @@
std::shared_ptr<TalonFX> translation;
};
-} // namespace swerve
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib::swerve
#endif // FRC971_WPILIB_SWERVE_SWERVE_MODULE_H_
diff --git a/frc971/wpilib/talonfx.h b/frc971/wpilib/talonfx.h
index c25fa81..a3e3066 100644
--- a/frc971/wpilib/talonfx.h
+++ b/frc971/wpilib/talonfx.h
@@ -15,8 +15,7 @@
namespace control_loops = ::frc971::control_loops;
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
struct TalonFXParams {
int device_id;
@@ -100,6 +99,5 @@
double stator_current_limit_;
double supply_current_limit_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_TALONFX_MOTOR_H_
diff --git a/frc971/wpilib/wpilib_interface.h b/frc971/wpilib/wpilib_interface.h
index b992aa3..1d64d2c 100644
--- a/frc971/wpilib/wpilib_interface.h
+++ b/frc971/wpilib/wpilib_interface.h
@@ -6,14 +6,12 @@
#include "aos/events/event_loop.h"
#include "frc971/input/robot_state_generated.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Sends out a message on ::aos::robot_state.
flatbuffers::Offset<aos::RobotState> PopulateRobotState(
aos::Sender<::aos::RobotState>::Builder *builder, int32_t my_pid);
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_WPILIB_INTERFACE_H_
diff --git a/frc971/wpilib/wpilib_robot_base.h b/frc971/wpilib/wpilib_robot_base.h
index 6b9e5c5..27c1bcd 100644
--- a/frc971/wpilib/wpilib_robot_base.h
+++ b/frc971/wpilib/wpilib_robot_base.h
@@ -6,8 +6,7 @@
#include "aos/logging/logging.h"
#include "frc971/wpilib/ahal/RobotBase.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
class WPILibRobotBase {
public:
@@ -81,7 +80,6 @@
T robot_;
};
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_NEWROBOTBASE_H_
diff --git a/frc971/wpilib/wpilib_utils.h b/frc971/wpilib/wpilib_utils.h
index 78dd262..0600f66 100644
--- a/frc971/wpilib/wpilib_utils.h
+++ b/frc971/wpilib/wpilib_utils.h
@@ -5,8 +5,7 @@
#include "frc971/constants.h"
-namespace frc971 {
-namespace wpilib {
+namespace frc971::wpilib {
// Convert min and max angle positions from range to voltage and compare to
// min and max potentiometer voltage to check if in range.
@@ -22,7 +21,6 @@
::std::function<double(double)> pot_translate_inverse,
bool reverse, double limit_buffer = 0.05);
-} // namespace wpilib
-} // namespace frc971
+} // namespace frc971::wpilib
#endif // FRC971_WPILIB_WPILIB_UTILS_H_
\ No newline at end of file
diff --git a/frc971/zeroing/absolute_and_absolute_encoder.h b/frc971/zeroing/absolute_and_absolute_encoder.h
index 509d5c5..90c8468 100644
--- a/frc971/zeroing/absolute_and_absolute_encoder.h
+++ b/frc971/zeroing/absolute_and_absolute_encoder.h
@@ -8,8 +8,7 @@
#include "aos/containers/error_list.h"
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Estimates the position with an absolute encoder which also reports
// incremental counts and an absolute encoder that's not allowed to turn more
@@ -113,7 +112,6 @@
double position_ = 0.0;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_ABSOLUTE_AND_ABSOLUTE_ENCODER_H_
diff --git a/frc971/zeroing/absolute_encoder.h b/frc971/zeroing/absolute_encoder.h
index 9d730f2..b6fd579 100644
--- a/frc971/zeroing/absolute_encoder.h
+++ b/frc971/zeroing/absolute_encoder.h
@@ -8,8 +8,7 @@
#include "aos/containers/error_list.h"
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Estimates the position with an absolute encoder which also reports
// incremental counts. The absolute encoder can't spin more than one
@@ -91,7 +90,6 @@
aos::ErrorList<ZeroingError> errors_;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_ABSOLUTE_ENCODER_H_
diff --git a/frc971/zeroing/averager.h b/frc971/zeroing/averager.h
index 0e15d13..370533f 100644
--- a/frc971/zeroing/averager.h
+++ b/frc971/zeroing/averager.h
@@ -8,8 +8,7 @@
#include "Eigen/Dense"
#include "glog/logging.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Averages a set of given numbers. Numbers are given one at a time. Once full
// the average may be requested.
@@ -89,7 +88,6 @@
size_t num_data_points_ = 0;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_AVERAGER_H_
diff --git a/frc971/zeroing/continuous_absolute_encoder.h b/frc971/zeroing/continuous_absolute_encoder.h
index e11d866..4994280 100644
--- a/frc971/zeroing/continuous_absolute_encoder.h
+++ b/frc971/zeroing/continuous_absolute_encoder.h
@@ -8,8 +8,7 @@
#include "aos/containers/error_list.h"
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Estimates the position with an absolute encoder which spins continuously. The
// absolute encoder must have a 1:1 ratio to the output.
@@ -93,7 +92,6 @@
aos::ErrorList<ZeroingError> errors_;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_CONTINUOUS_ABSOLUTE_ENCODER_H_
diff --git a/frc971/zeroing/hall_effect_and_position.h b/frc971/zeroing/hall_effect_and_position.h
index f03a442..d9f743f 100644
--- a/frc971/zeroing/hall_effect_and_position.h
+++ b/frc971/zeroing/hall_effect_and_position.h
@@ -5,8 +5,7 @@
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Estimates the position with an incremental encoder and a hall effect sensor.
class HallEffectAndPositionZeroingEstimator
@@ -84,7 +83,6 @@
double first_start_pos_;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_HALL_EFFECT_AND_POSITION_H_
diff --git a/frc971/zeroing/pot_and_absolute_encoder.h b/frc971/zeroing/pot_and_absolute_encoder.h
index d250a50..f18e589 100644
--- a/frc971/zeroing/pot_and_absolute_encoder.h
+++ b/frc971/zeroing/pot_and_absolute_encoder.h
@@ -8,8 +8,7 @@
#include "aos/containers/error_list.h"
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Estimates the position with an absolute encoder which also reports
// incremental counts, and a potentiometer.
@@ -98,7 +97,6 @@
aos::ErrorList<ZeroingError> errors_;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_POT_AND_ABSOLUTE_ENCODER_H_
diff --git a/frc971/zeroing/pot_and_index.h b/frc971/zeroing/pot_and_index.h
index 473c674..cb28fe4 100644
--- a/frc971/zeroing/pot_and_index.h
+++ b/frc971/zeroing/pot_and_index.h
@@ -7,8 +7,7 @@
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Estimates the position with an incremental encoder with an index pulse and a
// potentiometer.
@@ -97,7 +96,6 @@
double first_start_pos_;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_POT_AND_INDEX_H_
diff --git a/frc971/zeroing/pulse_index.h b/frc971/zeroing/pulse_index.h
index 4bcf210..9c17371 100644
--- a/frc971/zeroing/pulse_index.h
+++ b/frc971/zeroing/pulse_index.h
@@ -5,8 +5,7 @@
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
// Zeros by seeing all the index pulses in the range of motion of the mechanism
// and using that to figure out which index pulse is which.
@@ -78,7 +77,6 @@
double position_;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_PULSE_INDEX_H_
diff --git a/frc971/zeroing/zeroing.h b/frc971/zeroing/zeroing.h
index 5d5b6eb..8fe381d 100644
--- a/frc971/zeroing/zeroing.h
+++ b/frc971/zeroing/zeroing.h
@@ -20,8 +20,7 @@
// TODO(pschrader): Watch the offset over long periods of time and flag if it
// gets too far away from the initial value.
-namespace frc971 {
-namespace zeroing {
+namespace frc971::zeroing {
template <typename TPosition, typename TZeroingConstants, typename TState>
class ZeroingEstimator {
@@ -169,7 +168,6 @@
bool error_ = false;
};
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing
#endif // FRC971_ZEROING_ZEROING_H_
diff --git a/frc971/zeroing/zeroing_test.h b/frc971/zeroing/zeroing_test.h
index cadbe6c..497f833 100644
--- a/frc971/zeroing/zeroing_test.h
+++ b/frc971/zeroing/zeroing_test.h
@@ -4,9 +4,7 @@
#include "frc971/control_loops/position_sensor_sim.h"
#include "frc971/zeroing/zeroing.h"
-namespace frc971 {
-namespace zeroing {
-namespace testing {
+namespace frc971::zeroing::testing {
using control_loops::PositionSensorSimulator;
using FBB = flatbuffers::FlatBufferBuilder;
@@ -27,6 +25,4 @@
}
};
-} // namespace testing
-} // namespace zeroing
-} // namespace frc971
+} // namespace frc971::zeroing::testing
diff --git a/motors/algorithms.h b/motors/algorithms.h
index 20dcbe8..95fa772 100644
--- a/motors/algorithms.h
+++ b/motors/algorithms.h
@@ -5,8 +5,7 @@
#include <array>
-namespace frc971 {
-namespace motors {
+namespace frc971::motors {
struct ReadingsToBalance {
// Adds a single reading at index.
@@ -57,7 +56,6 @@
return r;
}
-} // namespace motors
-} // namespace frc971
+} // namespace frc971::motors
#endif // MOTORS_ALGORITHMS_H_
diff --git a/motors/big/motor_controls.h b/motors/big/motor_controls.h
index 8aae5d1..6644ea4 100644
--- a/motors/big/motor_controls.h
+++ b/motors/big/motor_controls.h
@@ -9,8 +9,7 @@
#include "motors/math.h"
#include "motors/motor.h"
-namespace frc971 {
-namespace motors {
+namespace frc971::motors {
class MotorControlsImplementation : public MotorControls {
public:
@@ -67,7 +66,6 @@
int16_t debug_[9];
};
-} // namespace motors
-} // namespace frc971
+} // namespace frc971::motors
#endif // MOTORS_MOTOR_CONTROLS_H_
diff --git a/motors/core/semihosting.h b/motors/core/semihosting.h
index 3b7ba46..57af6e7 100644
--- a/motors/core/semihosting.h
+++ b/motors/core/semihosting.h
@@ -5,9 +5,7 @@
#include "absl/types/span.h"
-namespace frc971 {
-namespace motors {
-namespace semihosting {
+namespace frc971::motors::semihosting {
inline uint32_t integer_operation(const uint32_t operation, void *const block) {
register uint32_t operation_register asm("r0") = operation;
@@ -165,8 +163,6 @@
}
};
-} // namespace semihosting
-} // namespace motors
-} // namespace frc971
+} // namespace frc971::motors::semihosting
#endif // MOTORS_CORE_SEMIHOSTING_H_
diff --git a/motors/fet12/motor_controls.h b/motors/fet12/motor_controls.h
index 482eeaf..7f495f1 100644
--- a/motors/fet12/motor_controls.h
+++ b/motors/fet12/motor_controls.h
@@ -9,8 +9,7 @@
#include "motors/math.h"
#include "motors/motor.h"
-namespace frc971 {
-namespace motors {
+namespace frc971::motors {
class MotorControlsImplementation : public MotorControls {
public:
@@ -62,7 +61,6 @@
int16_t debug_[9];
};
-} // namespace motors
-} // namespace frc971
+} // namespace frc971::motors
#endif // MOTORS_MOTOR_CONTROLS_H_
diff --git a/motors/math.h b/motors/math.h
index 5151714..b9aba4a 100644
--- a/motors/math.h
+++ b/motors/math.h
@@ -10,8 +10,7 @@
// This file has some specialized math functions useful for implementing our
// controls in a minimal number of cycles.
-namespace frc971 {
-namespace motors {
+namespace frc971::motors {
inline constexpr unsigned int Log2RoundUp(unsigned int x) {
return (x < 2) ? x : (1 + Log2RoundUp(x / 2));
@@ -213,7 +212,6 @@
// This must be called before any of the other functions.
void MathInit();
-} // namespace motors
-} // namespace frc971
+} // namespace frc971::motors
#endif // MOTORS_MATH_H_
diff --git a/motors/motor.h b/motors/motor.h
index 3f7b132..20f60fc 100644
--- a/motors/motor.h
+++ b/motors/motor.h
@@ -13,8 +13,7 @@
#include "motors/print/print.h"
#include "motors/util.h"
-namespace frc971 {
-namespace motors {
+namespace frc971::motors {
class MotorControls {
public:
@@ -189,7 +188,6 @@
PrintingImplementation *printing_implementation_ = nullptr;
};
-} // namespace motors
-} // namespace frc971
+} // namespace frc971::motors
#endif // MOTORS_MOTOR_H_
diff --git a/motors/peripheral/adc.h b/motors/peripheral/adc.h
index c22a856..22db93a 100644
--- a/motors/peripheral/adc.h
+++ b/motors/peripheral/adc.h
@@ -5,8 +5,7 @@
#include "motors/util.h"
-namespace frc971 {
-namespace motors {
+namespace frc971::motors {
enum class AdcChannels {
kA,
@@ -15,7 +14,6 @@
void AdcInitCommon(AdcChannels adc0_channels = AdcChannels::kB,
AdcChannels adc1_channels = AdcChannels::kB);
-} // namespace motors
-} // namespace frc971
+} // namespace frc971::motors
#endif // MOTORS_PERIPHERAL_ADC_H_
diff --git a/motors/peripheral/adc_dma.h b/motors/peripheral/adc_dma.h
index a00b730..f04f5ce 100644
--- a/motors/peripheral/adc_dma.h
+++ b/motors/peripheral/adc_dma.h
@@ -9,8 +9,7 @@
#include "motors/peripheral/configuration.h"
#include "motors/util.h"
-namespace frc971 {
-namespace teensy {
+namespace frc971::teensy {
// This class manages configuring the hardware to automatically capture various
// sensor values periodically with tight timing. Currently it's only 4 samples
@@ -108,7 +107,6 @@
::std::array<volatile uint32_t *, 2> ftm_delays_{nullptr, nullptr};
};
-} // namespace teensy
-} // namespace frc971
+} // namespace frc971::teensy
#endif // MOTORS_PERIPHERAL_ADC_DMA_H_
diff --git a/motors/peripheral/spi.h b/motors/peripheral/spi.h
index f865703..c5a1b64 100644
--- a/motors/peripheral/spi.h
+++ b/motors/peripheral/spi.h
@@ -7,8 +7,7 @@
#include "motors/peripheral/uart_buffer.h"
#include "motors/util.h"
-namespace frc971 {
-namespace teensy {
+namespace frc971::teensy {
// Simple synchronous interface to a SPI peripheral.
class Spi {
@@ -112,7 +111,6 @@
int frames_to_receive_ = 0;
};
-} // namespace teensy
-} // namespace frc971
+} // namespace frc971::teensy
#endif // MOTORS_PERIPHERAL_SPI_H_
diff --git a/motors/peripheral/uart.h b/motors/peripheral/uart.h
index bfd630b..f8e7e7e 100644
--- a/motors/peripheral/uart.h
+++ b/motors/peripheral/uart.h
@@ -8,8 +8,7 @@
#include "motors/peripheral/uart_buffer.h"
#include "motors/util.h"
-namespace frc971 {
-namespace teensy {
+namespace frc971::teensy {
// Simple synchronous interface to a UART.
class Uart {
@@ -121,7 +120,6 @@
UartBuffer<1024> transmit_buffer_, receive_buffer_;
};
-} // namespace teensy
-} // namespace frc971
+} // namespace frc971::teensy
#endif // MOTORS_PERIPHERAL_UART_H_
diff --git a/motors/peripheral/uart_buffer.h b/motors/peripheral/uart_buffer.h
index 9266465..714cfe8 100644
--- a/motors/peripheral/uart_buffer.h
+++ b/motors/peripheral/uart_buffer.h
@@ -6,8 +6,7 @@
#include "absl/types/span.h"
-namespace frc971 {
-namespace teensy {
+namespace frc971::teensy {
// Manages a circular buffer of data to send out.
template <int kSize>
@@ -90,7 +89,6 @@
++size_;
}
-} // namespace teensy
-} // namespace frc971
+} // namespace frc971::teensy
#endif // MOTORS_PERIPHERAL_UART_BUFFER_H_
diff --git a/motors/pistol_grip/controller_adc.h b/motors/pistol_grip/controller_adc.h
index 867807c..b29bbcf 100644
--- a/motors/pistol_grip/controller_adc.h
+++ b/motors/pistol_grip/controller_adc.h
@@ -3,8 +3,7 @@
#include "motors/util.h"
-namespace frc971 {
-namespace motors {
+namespace frc971::motors {
struct SmallAdcReadings {
uint16_t currents[3];
@@ -28,7 +27,6 @@
// Reads the absolute encoder values for initialization.
SmallInitReadings AdcReadSmallInit(const DisableInterrupts &);
-} // namespace motors
-} // namespace frc971
+} // namespace frc971::motors
#endif // MOTORS_PISTOL_GRIP_CONTROLLER_ADC_H_
diff --git a/motors/pistol_grip/motor_controls.h b/motors/pistol_grip/motor_controls.h
index 253da4b..63d2c12 100644
--- a/motors/pistol_grip/motor_controls.h
+++ b/motors/pistol_grip/motor_controls.h
@@ -9,8 +9,7 @@
#include "motors/math.h"
#include "motors/motor.h"
-namespace frc971 {
-namespace motors {
+namespace frc971::motors {
class LittleMotorControlsImplementation : public MotorControls {
public:
@@ -68,7 +67,6 @@
int16_t debug_[9];
};
-} // namespace motors
-} // namespace frc971
+} // namespace frc971::motors
#endif // MOTORS_PISTOL_GRIP_MOTOR_CONTROLS_H_
diff --git a/motors/print/itm.h b/motors/print/itm.h
index 64e3092..05ffb2c 100644
--- a/motors/print/itm.h
+++ b/motors/print/itm.h
@@ -5,8 +5,7 @@
#include "motors/print/print.h"
-namespace frc971 {
-namespace motors {
+namespace frc971::motors {
// A printing implementation via the SWO (trace output) pin. This requires an
// attached debugger which is in SWD (Single Wire Debug) mode, has the SWO
@@ -28,7 +27,6 @@
int WriteDebug(absl::Span<const char> buffer) override;
};
-} // namespace motors
-} // namespace frc971
+} // namespace frc971::motors
#endif // MOTORS_PRINT_ITM_
diff --git a/motors/print/semihosting.h b/motors/print/semihosting.h
index 6094a67..e04a4e5 100644
--- a/motors/print/semihosting.h
+++ b/motors/print/semihosting.h
@@ -5,8 +5,7 @@
#include "motors/print/print.h"
-namespace frc971 {
-namespace motors {
+namespace frc971::motors {
// A printing implementation which uses the ARM semihosting interface. This
// requries an attached debugger with software support.
@@ -31,7 +30,6 @@
// file if the name is filled out in the parameters.
};
-} // namespace motors
-} // namespace frc971
+} // namespace frc971::motors
#endif // MOTORS_PRINT_SEMIHOSTING_H_
diff --git a/motors/print/uart.h b/motors/print/uart.h
index 7d81577..e223ae7 100644
--- a/motors/print/uart.h
+++ b/motors/print/uart.h
@@ -4,8 +4,7 @@
#include "motors/peripheral/uart.h"
#include "motors/print/print.h"
-namespace frc971 {
-namespace motors {
+namespace frc971::motors {
// A printing implementation using a hardware UART. This has a reasonably sized
// buffer in memory and uses interrupts to keep the hardware busy. It could
@@ -28,7 +27,6 @@
// Could easily create a subclass of UartPrinting that also implements
// WriteDebug on a second UART, and conditionally instantiate that.
-} // namespace motors
-} // namespace frc971
+} // namespace frc971::motors
#endif // MOTORS_PRINT_UART_H_
diff --git a/motors/print/usb.h b/motors/print/usb.h
index c2224d2..5e811b3 100644
--- a/motors/print/usb.h
+++ b/motors/print/usb.h
@@ -5,8 +5,7 @@
#include "motors/usb/cdc.h"
#include "motors/usb/usb.h"
-namespace frc971 {
-namespace motors {
+namespace frc971::motors {
// A printing implementation which uses externally-created functions. The stdout
// one is required, while the debug one is optional.
@@ -68,7 +67,6 @@
teensy::AcmTty debug_tty_;
};
-} // namespace motors
-} // namespace frc971
+} // namespace frc971::motors
#endif // MOTORS_PRINT_USB_H_
diff --git a/motors/seems_reasonable/spring.h b/motors/seems_reasonable/spring.h
index 90c9cd1..0847b3c 100644
--- a/motors/seems_reasonable/spring.h
+++ b/motors/seems_reasonable/spring.h
@@ -3,8 +3,7 @@
#include <cmath>
-namespace motors {
-namespace seems_reasonable {
+namespace motors::seems_reasonable {
float NextGoal(float current_goal, float goal);
float PreviousGoal(float current_goal, float goal);
@@ -104,7 +103,6 @@
float last_error_ = 0.0f;
};
-} // namespace seems_reasonable
-} // namespace motors
+} // namespace motors::seems_reasonable
#endif // MOTORS_SEEMS_REASONABLE_SPRING_H_
diff --git a/motors/usb/cdc.h b/motors/usb/cdc.h
index f8f084b..e10dbf0 100644
--- a/motors/usb/cdc.h
+++ b/motors/usb/cdc.h
@@ -13,8 +13,7 @@
// lot of formats. The only commonality across the "class" seems to be some
// constants and a few descriptors.
-namespace frc971 {
-namespace teensy {
+namespace frc971::teensy {
struct CdcLineCoding {
static constexpr uint8_t stop_bits_1() { return 0; }
@@ -129,7 +128,6 @@
uint16_t control_line_state_ = 0;
};
-} // namespace teensy
-} // namespace frc971
+} // namespace frc971::teensy
#endif // MOTORS_USB_CDC_H_
diff --git a/motors/usb/hid.h b/motors/usb/hid.h
index 924cf37..b1d843c 100644
--- a/motors/usb/hid.h
+++ b/motors/usb/hid.h
@@ -9,8 +9,7 @@
#include "motors/usb/usb.h"
#include "motors/util.h"
-namespace frc971 {
-namespace teensy {
+namespace frc971::teensy {
// Implements an HID class device.
// TODO(Brian): Make this way more generic.
@@ -95,7 +94,6 @@
UsbDescriptorList hid_descriptor_list_;
};
-} // namespace teensy
-} // namespace frc971
+} // namespace frc971::teensy
#endif // MOTORS_USB_HID_H_
diff --git a/motors/usb/interrupt_out.h b/motors/usb/interrupt_out.h
index 31852f9..96409b0 100644
--- a/motors/usb/interrupt_out.h
+++ b/motors/usb/interrupt_out.h
@@ -7,8 +7,7 @@
#include "motors/usb/usb.h"
#include "motors/util.h"
-namespace frc971 {
-namespace teensy {
+namespace frc971::teensy {
// A simple function that just has an interrupt out endpoint and exposes the
// data received.
@@ -58,7 +57,6 @@
const ::std::string name_;
};
-} // namespace teensy
-} // namespace frc971
+} // namespace frc971::teensy
#endif // MOTORS_USB_INTERRUPT_OUT_H_
diff --git a/motors/usb/queue.h b/motors/usb/queue.h
index f7a7e77..2142213 100644
--- a/motors/usb/queue.h
+++ b/motors/usb/queue.h
@@ -4,8 +4,7 @@
#include <atomic>
#include <memory>
-namespace frc971 {
-namespace teensy {
+namespace frc971::teensy {
// A FIFO queue which reads/writes variable-sized chunks.
//
@@ -61,7 +60,6 @@
::std::atomic<size_t> write_cursor_{0};
};
-} // namespace teensy
-} // namespace frc971
+} // namespace frc971::teensy
#endif // MOTORS_USB_QUEUE_H_
diff --git a/motors/usb/usb.h b/motors/usb/usb.h
index 2475220..2b0cf17 100644
--- a/motors/usb/usb.h
+++ b/motors/usb/usb.h
@@ -13,8 +13,7 @@
#include "motors/usb/constants.h"
#include "motors/util.h"
-namespace frc971 {
-namespace teensy {
+namespace frc971::teensy {
// A sufficient memory barrier between writing some data and telling the USB
// hardware to read it or having the USB hardware say some data is readable and
@@ -584,7 +583,6 @@
friend class UsbDevice;
};
-} // namespace teensy
-} // namespace frc971
+} // namespace frc971::teensy
#endif // MOTORS_USB_USB_H_
diff --git a/scouting/db/db.go b/scouting/db/db.go
index cf1c823..759f7e1 100644
--- a/scouting/db/db.go
+++ b/scouting/db/db.go
@@ -68,6 +68,32 @@
CollectedBy string
}
+type Stats2024 struct {
+ // This is set to `true` for "pre-scouted" matches. This means that the
+ // match information is unlikely to correspond with an entry in the
+ // `TeamMatch` table.
+ PreScouting bool `gorm:"primaryKey"`
+
+ TeamNumber string `gorm:"primaryKey"`
+ MatchNumber int32 `gorm:"primaryKey"`
+ SetNumber int32 `gorm:"primaryKey"`
+ CompLevel string `gorm:"primaryKey"`
+ StartingQuadrant int32
+ SpeakerAuto, AmpAuto int32
+ NotesDroppedAuto int32
+ MobilityAuto bool
+ Speaker, Amp, SpeakerAmplified, AmpAmplified int32
+ NotesDropped int32
+ Penalties int32
+ AvgCycle int64
+ Park, OnStage, Harmony, TrapNote bool
+
+ // The username of the person who collected these statistics.
+ // "unknown" if submitted without logging in.
+ // Empty if the stats have not yet been collected.
+ CollectedBy string
+}
+
type Action struct {
PreScouting bool `gorm:"primaryKey"`
TeamNumber string `gorm:"primaryKey"`
@@ -139,7 +165,7 @@
return nil, errors.New(fmt.Sprint("Failed to connect to postgres: ", err))
}
- err = database.AutoMigrate(&TeamMatch{}, &Shift{}, &Stats2023{}, &Action{}, &PitImage{}, &NotesData{}, &Ranking{}, &DriverRankingData{}, &ParsedDriverRankingData{})
+ err = database.AutoMigrate(&TeamMatch{}, &Shift{}, &Stats2023{}, &Stats2024{}, &Action{}, &PitImage{}, &NotesData{}, &Ranking{}, &DriverRankingData{}, &ParsedDriverRankingData{})
if err != nil {
database.Delete()
return nil, errors.New(fmt.Sprint("Failed to create/migrate tables: ", err))
@@ -210,6 +236,30 @@
return result.Error
}
+func (database *Database) AddToStats2024(s Stats2024) error {
+ if !s.PreScouting {
+ matches, err := database.QueryMatchesString(s.TeamNumber)
+ if err != nil {
+ return err
+ }
+ foundMatch := false
+ for _, match := range matches {
+ if match.MatchNumber == s.MatchNumber {
+ foundMatch = true
+ break
+ }
+ }
+ if !foundMatch {
+ return errors.New(fmt.Sprint(
+ "Failed to find team ", s.TeamNumber,
+ " in match ", s.MatchNumber, " in the schedule."))
+ }
+ }
+
+ result := database.Create(&s)
+ return result.Error
+}
+
func (database *Database) DeleteFromStats(compLevel_ string, matchNumber_ int32, setNumber_ int32, teamNumber_ string) error {
var stats2023 []Stats2023
result := database.
@@ -218,6 +268,14 @@
return result.Error
}
+func (database *Database) DeleteFromStats2024(compLevel_ string, matchNumber_ int32, setNumber_ int32, teamNumber_ string) error {
+ var stats2024 []Stats2024
+ result := database.
+ Where("comp_level = ? AND match_number = ? AND set_number = ? AND team_number = ?", compLevel_, matchNumber_, setNumber_, teamNumber_).
+ Delete(&stats2024)
+ return result.Error
+}
+
func (database *Database) DeleteFromActions(compLevel_ string, matchNumber_ int32, setNumber_ int32, teamNumber_ string) error {
var actions []Action
result := database.
@@ -281,6 +339,12 @@
return stats2023, result.Error
}
+func (database *Database) ReturnStats2024() ([]Stats2024, error) {
+ var stats2024 []Stats2024
+ result := database.Find(&stats2024)
+ return stats2024, result.Error
+}
+
func (database *Database) ReturnStats2023ForTeam(teamNumber string, matchNumber int32, setNumber int32, compLevel string, preScouting bool) ([]Stats2023, error) {
var stats2023 []Stats2023
result := database.
@@ -290,6 +354,15 @@
return stats2023, result.Error
}
+func (database *Database) ReturnStats2024ForTeam(teamNumber string, matchNumber int32, setNumber int32, compLevel string, preScouting bool) ([]Stats2024, error) {
+ var stats2024 []Stats2024
+ result := database.
+ Where("team_number = ? AND match_number = ? AND set_number = ? AND comp_level = ? AND pre_scouting = ?",
+ teamNumber, matchNumber, setNumber, compLevel, preScouting).
+ Find(&stats2024)
+ return stats2024, result.Error
+}
+
func (database *Database) ReturnRankings() ([]Ranking, error) {
var rankins []Ranking
result := database.Find(&rankins)
diff --git a/scouting/db/db_test.go b/scouting/db/db_test.go
index d7001b8..4acbe12 100644
--- a/scouting/db/db_test.go
+++ b/scouting/db/db_test.go
@@ -138,6 +138,190 @@
}
}
+func TestAddToStats2024DB(t *testing.T) {
+ fixture := createDatabase(t)
+ defer fixture.TearDown()
+
+ correct := []Stats2024{
+ Stats2024{
+ PreScouting: false, TeamNumber: "894",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 4,
+ SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
+ Speaker: 0, Amp: 5, SpeakerAmplified: 1, AmpAmplified: 0,
+ NotesDropped: 0, Penalties: 2, TrapNote: true, AvgCycle: 0,
+ Park: true, OnStage: false, Harmony: false, CollectedBy: "emma",
+ },
+ Stats2024{
+ PreScouting: false, TeamNumber: "942",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 2,
+ SpeakerAuto: 2, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
+ Speaker: 0, Amp: 5, SpeakerAmplified: 1, AmpAmplified: 0,
+ NotesDropped: 0, Penalties: 2, TrapNote: true, AvgCycle: 0,
+ Park: true, OnStage: false, Harmony: false, CollectedBy: "harry",
+ },
+ Stats2024{
+ PreScouting: false, TeamNumber: "432",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 3,
+ SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
+ Speaker: 2, Amp: 1, SpeakerAmplified: 3, AmpAmplified: 0,
+ NotesDropped: 0, Penalties: 0, TrapNote: false, AvgCycle: 0,
+ Park: false, OnStage: true, Harmony: false, CollectedBy: "henry",
+ },
+ Stats2024{
+ PreScouting: false, TeamNumber: "52A",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 1,
+ SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
+ Speaker: 0, Amp: 1, SpeakerAmplified: 2, AmpAmplified: 3,
+ NotesDropped: 2, Penalties: 0, TrapNote: true, AvgCycle: 0,
+ Park: true, OnStage: false, Harmony: false, CollectedBy: "jordan",
+ },
+ Stats2024{
+ PreScouting: false, TeamNumber: "745",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 2,
+ SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
+ Speaker: 5, Amp: 0, SpeakerAmplified: 2, AmpAmplified: 1,
+ NotesDropped: 1, Penalties: 1, TrapNote: true, AvgCycle: 0,
+ Park: true, OnStage: false, Harmony: false, CollectedBy: "taylor",
+ },
+ Stats2024{
+ PreScouting: false, TeamNumber: "934",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 3,
+ SpeakerAuto: 1, AmpAuto: 3, NotesDroppedAuto: 0, MobilityAuto: true,
+ Speaker: 0, Amp: 3, SpeakerAmplified: 2, AmpAmplified: 2,
+ NotesDropped: 0, Penalties: 3, TrapNote: true, AvgCycle: 0,
+ Park: false, OnStage: false, Harmony: true, CollectedBy: "katie",
+ },
+ }
+
+ matches := []TeamMatch{
+ TeamMatch{MatchNumber: 3, SetNumber: 1, CompLevel: "quals",
+ Alliance: "R", AlliancePosition: 1, TeamNumber: "894"},
+ TeamMatch{MatchNumber: 3, SetNumber: 1, CompLevel: "quals",
+ Alliance: "R", AlliancePosition: 2, TeamNumber: "942"},
+ TeamMatch{MatchNumber: 3, SetNumber: 1, CompLevel: "quals",
+ Alliance: "R", AlliancePosition: 3, TeamNumber: "432"},
+ TeamMatch{MatchNumber: 3, SetNumber: 1, CompLevel: "quals",
+ Alliance: "B", AlliancePosition: 1, TeamNumber: "52A"},
+ TeamMatch{MatchNumber: 3, SetNumber: 1, CompLevel: "quals",
+ Alliance: "B", AlliancePosition: 2, TeamNumber: "745"},
+ TeamMatch{MatchNumber: 3, SetNumber: 1, CompLevel: "quals",
+ Alliance: "B", AlliancePosition: 3, TeamNumber: "934"},
+ }
+
+ for _, match := range matches {
+ err := fixture.db.AddToMatch(match)
+ check(t, err, "Failed to add match")
+ }
+
+ for i := 0; i < len(correct); i++ {
+ err := fixture.db.AddToStats2024(correct[i])
+ check(t, err, "Failed to add 2024stats to DB")
+ }
+
+ got, err := fixture.db.ReturnStats2024()
+ check(t, err, "Failed ReturnStats2024()")
+
+ if !reflect.DeepEqual(correct, got) {
+ t.Errorf("Got %#v,\nbut expected %#v.", got, correct)
+ }
+}
+
+func TestInsertPreScoutedStats2024(t *testing.T) {
+ fixture := createDatabase(t)
+ defer fixture.TearDown()
+
+ stats := Stats2024{
+ PreScouting: false, TeamNumber: "6344",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 4,
+ SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
+ Speaker: 0, Amp: 5, SpeakerAmplified: 1, AmpAmplified: 0,
+ NotesDropped: 0, Penalties: 2, TrapNote: true, AvgCycle: 0,
+ Park: true, OnStage: false, Harmony: false, CollectedBy: "emma",
+ }
+
+ // Attempt to insert the non-pre-scouted data and make sure it fails.
+ err := fixture.db.AddToStats2024(stats)
+ if err == nil {
+ t.Fatal("Expected error from inserting the stats.")
+ }
+ if err.Error() != "Failed to find team 6344 in match 3 in the schedule." {
+ t.Fatal("Got:", err.Error())
+ }
+
+ // Mark the data as pre-scouting data. It should now succeed.
+ stats.PreScouting = true
+ err = fixture.db.AddToStats2024(stats)
+ check(t, err, "Failed to add prescouted stats to DB")
+}
+
+func TestQueryingStats2024ByTeam(t *testing.T) {
+ fixture := createDatabase(t)
+ defer fixture.TearDown()
+
+ stats := []Stats2024{
+ Stats2024{
+ PreScouting: false, TeamNumber: "328A",
+ MatchNumber: 7, SetNumber: 1, CompLevel: "qm", StartingQuadrant: 1,
+ SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
+ Speaker: 0, Amp: 5, SpeakerAmplified: 1, AmpAmplified: 0,
+ NotesDropped: 0, Penalties: 2, TrapNote: true, AvgCycle: 0,
+ Park: false, OnStage: true, Harmony: false, CollectedBy: "emma",
+ },
+ Stats2024{
+ PreScouting: false, TeamNumber: "978",
+ MatchNumber: 2, SetNumber: 2, CompLevel: "qm", StartingQuadrant: 4,
+ SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
+ Speaker: 1, Amp: 2, SpeakerAmplified: 0, AmpAmplified: 2,
+ NotesDropped: 0, Penalties: 2, TrapNote: true, AvgCycle: 0,
+ Park: true, OnStage: false, Harmony: false, CollectedBy: "emma",
+ },
+ Stats2024{
+ PreScouting: false, TeamNumber: "328A",
+ MatchNumber: 4, SetNumber: 1, CompLevel: "qm", StartingQuadrant: 2,
+ SpeakerAuto: 1, AmpAuto: 1, NotesDroppedAuto: 1, MobilityAuto: true,
+ Speaker: 0, Amp: 1, SpeakerAmplified: 1, AmpAmplified: 5,
+ NotesDropped: 1, Penalties: 0, TrapNote: false, AvgCycle: 0,
+ Park: false, OnStage: false, Harmony: true, CollectedBy: "emma",
+ },
+ }
+
+ matches := []TeamMatch{
+ TeamMatch{MatchNumber: 7, SetNumber: 1, CompLevel: "qm",
+ Alliance: "R", AlliancePosition: 1, TeamNumber: "328A"},
+ TeamMatch{MatchNumber: 2, SetNumber: 2, CompLevel: "qm",
+ Alliance: "R", AlliancePosition: 1, TeamNumber: "978"},
+ TeamMatch{MatchNumber: 4, SetNumber: 1, CompLevel: "qm",
+ Alliance: "R", AlliancePosition: 1, TeamNumber: "328A"},
+ }
+
+ for _, match := range matches {
+ err := fixture.db.AddToMatch(match)
+ check(t, err, "Failed to add match")
+ }
+
+ for i := range stats {
+ err := fixture.db.AddToStats2024(stats[i])
+ check(t, err, "Failed to add 2024stats to DB")
+ }
+
+ // Validate that requesting status for a single team gets us the
+ // expected data.
+ statsFor328A, err := fixture.db.ReturnStats2024ForTeam("328A", 7, 1, "qm", false)
+ check(t, err, "Failed ReturnStats2024()")
+
+ if !reflect.DeepEqual([]Stats2024{stats[0]}, statsFor328A) {
+ t.Errorf("Got %#v,\nbut expected %#v.", statsFor328A, stats[0])
+ }
+ // Validate that requesting team data for a non-existent match returns
+ // nothing.
+ statsForMissing, err := fixture.db.ReturnStats2024ForTeam("6344", 9, 1, "qm", false)
+ check(t, err, "Failed ReturnStats2024()")
+
+ if !reflect.DeepEqual([]Stats2024{}, statsForMissing) {
+ t.Errorf("Got %#v,\nbut expected %#v.", statsForMissing, []Stats2024{})
+ }
+}
+
func TestAddToStats2023DB(t *testing.T) {
fixture := createDatabase(t)
defer fixture.TearDown()
@@ -505,6 +689,101 @@
}
}
+func TestDeleteFromStats2024(t *testing.T) {
+ fixture := createDatabase(t)
+ defer fixture.TearDown()
+
+ startingStats := []Stats2024{
+ Stats2024{
+ PreScouting: false, TeamNumber: "345",
+ MatchNumber: 5, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 1,
+ SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
+ Speaker: 1, Amp: 3, SpeakerAmplified: 1, AmpAmplified: 3,
+ NotesDropped: 0, Penalties: 0, TrapNote: false, AvgCycle: 0,
+ Park: false, OnStage: true, Harmony: false, CollectedBy: "bailey",
+ },
+ Stats2024{
+ PreScouting: false, TeamNumber: "645",
+ MatchNumber: 5, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 4,
+ SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
+ Speaker: 1, Amp: 2, SpeakerAmplified: 0, AmpAmplified: 1,
+ NotesDropped: 0, Penalties: 2, TrapNote: true, AvgCycle: 0,
+ Park: true, OnStage: false, Harmony: false, CollectedBy: "kate",
+ },
+ Stats2024{
+ PreScouting: false, TeamNumber: "323",
+ MatchNumber: 5, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 2,
+ SpeakerAuto: 1, AmpAuto: 1, NotesDroppedAuto: 1, MobilityAuto: true,
+ Speaker: 0, Amp: 0, SpeakerAmplified: 2, AmpAmplified: 1,
+ NotesDropped: 1, Penalties: 0, TrapNote: false, AvgCycle: 0,
+ Park: true, OnStage: false, Harmony: false, CollectedBy: "tyler",
+ },
+ Stats2024{
+ PreScouting: false, TeamNumber: "542",
+ MatchNumber: 5, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 1,
+ SpeakerAuto: 1, AmpAuto: 1, NotesDroppedAuto: 0, MobilityAuto: false,
+ Speaker: 1, Amp: 2, SpeakerAmplified: 2, AmpAmplified: 1,
+ NotesDropped: 1, Penalties: 0, TrapNote: false, AvgCycle: 0,
+ Park: false, OnStage: false, Harmony: true, CollectedBy: "max",
+ },
+ }
+
+ correct := []Stats2024{
+ Stats2024{
+ PreScouting: false, TeamNumber: "345",
+ MatchNumber: 5, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 1,
+ SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
+ Speaker: 1, Amp: 3, SpeakerAmplified: 1, AmpAmplified: 3,
+ NotesDropped: 0, Penalties: 0, TrapNote: false, AvgCycle: 0,
+ Park: false, OnStage: true, Harmony: false, CollectedBy: "bailey",
+ },
+ }
+
+ originalMatches := []TeamMatch{
+ TeamMatch{MatchNumber: 5, SetNumber: 1, CompLevel: "quals",
+ Alliance: "R", AlliancePosition: 1, TeamNumber: "345"},
+ TeamMatch{MatchNumber: 5, SetNumber: 1, CompLevel: "quals",
+ Alliance: "B", AlliancePosition: 1, TeamNumber: "645"},
+ TeamMatch{MatchNumber: 5, SetNumber: 1, CompLevel: "quals",
+ Alliance: "R", AlliancePosition: 3, TeamNumber: "323"},
+ TeamMatch{MatchNumber: 5, SetNumber: 1, CompLevel: "quals",
+ Alliance: "B", AlliancePosition: 2, TeamNumber: "542"},
+ }
+
+ // Matches for which we want to delete the stats.
+ matches := []TeamMatch{
+ TeamMatch{MatchNumber: 5, SetNumber: 1, CompLevel: "quals",
+ TeamNumber: "645"},
+ TeamMatch{MatchNumber: 5, SetNumber: 1, CompLevel: "quals",
+ TeamNumber: "323"},
+ TeamMatch{MatchNumber: 5, SetNumber: 1, CompLevel: "quals",
+ TeamNumber: "542"},
+ }
+
+ for _, match := range originalMatches {
+ err := fixture.db.AddToMatch(match)
+ check(t, err, "Failed to add match")
+ fmt.Println("Match has been added : ", match.TeamNumber)
+ }
+
+ for _, stat := range startingStats {
+ err := fixture.db.AddToStats2024(stat)
+ check(t, err, "Failed to add stat")
+ }
+
+ for _, match := range matches {
+ err := fixture.db.DeleteFromStats2024(match.CompLevel, match.MatchNumber, match.SetNumber, match.TeamNumber)
+ check(t, err, "Failed to delete stat2024")
+ }
+
+ got, err := fixture.db.ReturnStats2024()
+ check(t, err, "Failed ReturnStats2024()")
+
+ if !reflect.DeepEqual(correct, got) {
+ t.Errorf("Got %#v,\nbut expected %#v.", got, correct)
+ }
+}
+
func TestDeleteFromActions(t *testing.T) {
fixture := createDatabase(t)
defer fixture.TearDown()
@@ -864,6 +1143,74 @@
}
}
+func TestReturnStats2024DB(t *testing.T) {
+ fixture := createDatabase(t)
+ defer fixture.TearDown()
+
+ correct := []Stats2024{
+ Stats2024{
+ PreScouting: false, TeamNumber: "894",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 4,
+ SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
+ Speaker: 0, Amp: 5, SpeakerAmplified: 1, AmpAmplified: 0,
+ NotesDropped: 0, Penalties: 2, TrapNote: true, AvgCycle: 0,
+ Park: true, OnStage: false, Harmony: false, CollectedBy: "emma",
+ },
+ Stats2024{
+ PreScouting: false, TeamNumber: "942",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 2,
+ SpeakerAuto: 2, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
+ Speaker: 0, Amp: 5, SpeakerAmplified: 1, AmpAmplified: 0,
+ NotesDropped: 0, Penalties: 2, TrapNote: true, AvgCycle: 0,
+ Park: true, OnStage: false, Harmony: false, CollectedBy: "harry",
+ },
+ Stats2024{
+ PreScouting: false, TeamNumber: "432",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 3,
+ SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 2, MobilityAuto: true,
+ Speaker: 2, Amp: 1, SpeakerAmplified: 3, AmpAmplified: 0,
+ NotesDropped: 0, Penalties: 0, TrapNote: false, AvgCycle: 0,
+ Park: false, OnStage: true, Harmony: false, CollectedBy: "henry",
+ },
+ Stats2024{
+ PreScouting: false, TeamNumber: "52A",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 1,
+ SpeakerAuto: 1, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
+ Speaker: 0, Amp: 1, SpeakerAmplified: 2, AmpAmplified: 3,
+ NotesDropped: 2, Penalties: 0, TrapNote: true, AvgCycle: 0,
+ Park: true, OnStage: false, Harmony: false, CollectedBy: "jordan",
+ },
+ }
+
+ matches := []TeamMatch{
+ TeamMatch{MatchNumber: 3, SetNumber: 1, CompLevel: "quals",
+ Alliance: "R", AlliancePosition: 1, TeamNumber: "894"},
+ TeamMatch{MatchNumber: 3, SetNumber: 1, CompLevel: "quals",
+ Alliance: "R", AlliancePosition: 2, TeamNumber: "942"},
+ TeamMatch{MatchNumber: 3, SetNumber: 1, CompLevel: "quals",
+ Alliance: "R", AlliancePosition: 3, TeamNumber: "432"},
+ TeamMatch{MatchNumber: 3, SetNumber: 1, CompLevel: "quals",
+ Alliance: "B", AlliancePosition: 1, TeamNumber: "52A"},
+ }
+
+ for _, match := range matches {
+ err := fixture.db.AddToMatch(match)
+ check(t, err, "Failed to add match")
+ }
+
+ for i := 0; i < len(correct); i++ {
+ err := fixture.db.AddToStats2024(correct[i])
+ check(t, err, fmt.Sprint("Failed to add stats ", i))
+ }
+
+ got, err := fixture.db.ReturnStats2024()
+ check(t, err, "Failed ReturnStats2024()")
+
+ if !reflect.DeepEqual(correct, got) {
+ t.Errorf("Got %#v,\nbut expected %#v.", got, correct)
+ }
+}
+
func TestReturnStats2023DB(t *testing.T) {
fixture := createDatabase(t)
defer fixture.TearDown()
diff --git a/scouting/webserver/requests/BUILD b/scouting/webserver/requests/BUILD
index 7be151e..846414c 100644
--- a/scouting/webserver/requests/BUILD
+++ b/scouting/webserver/requests/BUILD
@@ -10,9 +10,13 @@
"//scouting/db",
"//scouting/webserver/requests/messages:delete_2023_data_scouting_go_fbs",
"//scouting/webserver/requests/messages:delete_2023_data_scouting_response_go_fbs",
+ "//scouting/webserver/requests/messages:delete_2024_data_scouting_go_fbs",
+ "//scouting/webserver/requests/messages:delete_2024_data_scouting_response_go_fbs",
"//scouting/webserver/requests/messages:error_response_go_fbs",
"//scouting/webserver/requests/messages:request_2023_data_scouting_go_fbs",
"//scouting/webserver/requests/messages:request_2023_data_scouting_response_go_fbs",
+ "//scouting/webserver/requests/messages:request_2024_data_scouting_go_fbs",
+ "//scouting/webserver/requests/messages:request_2024_data_scouting_response_go_fbs",
"//scouting/webserver/requests/messages:request_all_driver_rankings_go_fbs",
"//scouting/webserver/requests/messages:request_all_driver_rankings_response_go_fbs",
"//scouting/webserver/requests/messages:request_all_matches_go_fbs",
@@ -27,6 +31,8 @@
"//scouting/webserver/requests/messages:request_pit_images_response_go_fbs",
"//scouting/webserver/requests/messages:request_shift_schedule_go_fbs",
"//scouting/webserver/requests/messages:request_shift_schedule_response_go_fbs",
+ "//scouting/webserver/requests/messages:submit_2024_actions_go_fbs",
+ "//scouting/webserver/requests/messages:submit_2024_actions_response_go_fbs",
"//scouting/webserver/requests/messages:submit_actions_go_fbs",
"//scouting/webserver/requests/messages:submit_actions_response_go_fbs",
"//scouting/webserver/requests/messages:submit_driver_ranking_go_fbs",
@@ -51,8 +57,11 @@
"//scouting/db",
"//scouting/webserver/requests/debug",
"//scouting/webserver/requests/messages:delete_2023_data_scouting_go_fbs",
+ "//scouting/webserver/requests/messages:delete_2024_data_scouting_go_fbs",
"//scouting/webserver/requests/messages:request_2023_data_scouting_go_fbs",
"//scouting/webserver/requests/messages:request_2023_data_scouting_response_go_fbs",
+ "//scouting/webserver/requests/messages:request_2024_data_scouting_go_fbs",
+ "//scouting/webserver/requests/messages:request_2024_data_scouting_response_go_fbs",
"//scouting/webserver/requests/messages:request_all_driver_rankings_go_fbs",
"//scouting/webserver/requests/messages:request_all_driver_rankings_response_go_fbs",
"//scouting/webserver/requests/messages:request_all_matches_go_fbs",
@@ -66,6 +75,7 @@
"//scouting/webserver/requests/messages:request_pit_images_response_go_fbs",
"//scouting/webserver/requests/messages:request_shift_schedule_go_fbs",
"//scouting/webserver/requests/messages:request_shift_schedule_response_go_fbs",
+ "//scouting/webserver/requests/messages:submit_2024_actions_go_fbs",
"//scouting/webserver/requests/messages:submit_actions_go_fbs",
"//scouting/webserver/requests/messages:submit_driver_ranking_go_fbs",
"//scouting/webserver/requests/messages:submit_notes_go_fbs",
diff --git a/scouting/webserver/requests/debug/BUILD b/scouting/webserver/requests/debug/BUILD
index 1224710..ff85206 100644
--- a/scouting/webserver/requests/debug/BUILD
+++ b/scouting/webserver/requests/debug/BUILD
@@ -8,8 +8,10 @@
visibility = ["//visibility:public"],
deps = [
"//scouting/webserver/requests/messages:delete_2023_data_scouting_response_go_fbs",
+ "//scouting/webserver/requests/messages:delete_2024_data_scouting_response_go_fbs",
"//scouting/webserver/requests/messages:error_response_go_fbs",
"//scouting/webserver/requests/messages:request_2023_data_scouting_response_go_fbs",
+ "//scouting/webserver/requests/messages:request_2024_data_scouting_response_go_fbs",
"//scouting/webserver/requests/messages:request_all_driver_rankings_response_go_fbs",
"//scouting/webserver/requests/messages:request_all_matches_response_go_fbs",
"//scouting/webserver/requests/messages:request_all_notes_response_go_fbs",
@@ -17,6 +19,7 @@
"//scouting/webserver/requests/messages:request_notes_for_team_response_go_fbs",
"//scouting/webserver/requests/messages:request_pit_images_response_go_fbs",
"//scouting/webserver/requests/messages:request_shift_schedule_response_go_fbs",
+ "//scouting/webserver/requests/messages:submit_2024_actions_response_go_fbs",
"//scouting/webserver/requests/messages:submit_actions_response_go_fbs",
"//scouting/webserver/requests/messages:submit_driver_ranking_response_go_fbs",
"//scouting/webserver/requests/messages:submit_notes_response_go_fbs",
diff --git a/scouting/webserver/requests/debug/debug.go b/scouting/webserver/requests/debug/debug.go
index faf4a9d..ed8a1b7 100644
--- a/scouting/webserver/requests/debug/debug.go
+++ b/scouting/webserver/requests/debug/debug.go
@@ -10,8 +10,10 @@
"net/http"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/delete_2023_data_scouting_response"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/delete_2024_data_scouting_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/error_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_2023_data_scouting_response"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_2024_data_scouting_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_all_driver_rankings_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_all_notes_response"
@@ -19,6 +21,7 @@
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_notes_for_team_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_pit_images_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_shift_schedule_response"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_2024_actions_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_actions_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_driver_ranking_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_notes_response"
@@ -127,6 +130,12 @@
request_2023_data_scouting_response.GetRootAsRequest2023DataScoutingResponse)
}
+func Request2024DataScouting(server string, requestBytes []byte) (*request_2024_data_scouting_response.Request2024DataScoutingResponseT, error) {
+ return sendMessage[request_2024_data_scouting_response.Request2024DataScoutingResponseT](
+ server+"/requests/request/2024_data_scouting", requestBytes,
+ request_2024_data_scouting_response.GetRootAsRequest2024DataScoutingResponse)
+}
+
func SubmitNotes(server string, requestBytes []byte) (*submit_notes_response.SubmitNotesResponseT, error) {
return sendMessage[submit_notes_response.SubmitNotesResponseT](
server+"/requests/submit/submit_notes", requestBytes,
@@ -175,6 +184,12 @@
submit_driver_ranking_response.GetRootAsSubmitDriverRankingResponse)
}
+func Submit2024Actions(server string, requestBytes []byte) (*submit_2024_actions_response.Submit2024ActionsResponseT, error) {
+ return sendMessage[submit_2024_actions_response.Submit2024ActionsResponseT](
+ server+"/requests/submit/submit_2024_actions", requestBytes,
+ submit_2024_actions_response.GetRootAsSubmit2024ActionsResponse)
+}
+
func SubmitActions(server string, requestBytes []byte) (*submit_actions_response.SubmitActionsResponseT, error) {
return sendMessage[submit_actions_response.SubmitActionsResponseT](
server+"/requests/submit/submit_actions", requestBytes,
@@ -192,3 +207,9 @@
server+"/requests/delete/delete_2023_data_scouting", requestBytes,
delete_2023_data_scouting_response.GetRootAsDelete2023DataScoutingResponse)
}
+
+func Delete2024DataScouting(server string, requestBytes []byte) (*delete_2024_data_scouting_response.Delete2024DataScoutingResponseT, error) {
+ return sendMessage[delete_2024_data_scouting_response.Delete2024DataScoutingResponseT](
+ server+"/requests/delete/delete_2024_data_scouting", requestBytes,
+ delete_2024_data_scouting_response.GetRootAsDelete2024DataScoutingResponse)
+}
diff --git a/scouting/webserver/requests/messages/BUILD b/scouting/webserver/requests/messages/BUILD
index 735caab..d0534a51 100644
--- a/scouting/webserver/requests/messages/BUILD
+++ b/scouting/webserver/requests/messages/BUILD
@@ -11,6 +11,8 @@
"request_all_notes_response",
"request_2023_data_scouting",
"request_2023_data_scouting_response",
+ "request_2024_data_scouting",
+ "request_2024_data_scouting_response",
"submit_notes",
"submit_notes_response",
"request_notes_for_team",
@@ -29,8 +31,12 @@
"submit_driver_ranking_response",
"submit_actions",
"submit_actions_response",
+ "submit_2024_actions",
+ "submit_2024_actions_response",
"delete_2023_data_scouting",
"delete_2023_data_scouting_response",
+ "delete_2024_data_scouting",
+ "delete_2024_data_scouting_response",
)
filegroup(
diff --git a/scouting/webserver/requests/messages/delete_2024_data_scouting.fbs b/scouting/webserver/requests/messages/delete_2024_data_scouting.fbs
new file mode 100644
index 0000000..827aa98
--- /dev/null
+++ b/scouting/webserver/requests/messages/delete_2024_data_scouting.fbs
@@ -0,0 +1,10 @@
+namespace scouting.webserver.requests;
+
+table Delete2024DataScouting {
+ comp_level:string (id: 0);
+ match_number:int (id: 1);
+ set_number:int (id: 2);
+ team_number:string (id: 3);
+}
+
+root_type Delete2024DataScouting;
diff --git a/scouting/webserver/requests/messages/delete_2024_data_scouting_response.fbs b/scouting/webserver/requests/messages/delete_2024_data_scouting_response.fbs
new file mode 100644
index 0000000..2dbb81f
--- /dev/null
+++ b/scouting/webserver/requests/messages/delete_2024_data_scouting_response.fbs
@@ -0,0 +1,7 @@
+namespace scouting.webserver.requests;
+
+table Delete2024DataScoutingResponse {
+ // empty response
+}
+
+root_type Delete2024DataScoutingResponse;
diff --git a/scouting/webserver/requests/messages/request_2024_data_scouting.fbs b/scouting/webserver/requests/messages/request_2024_data_scouting.fbs
new file mode 100644
index 0000000..738aade
--- /dev/null
+++ b/scouting/webserver/requests/messages/request_2024_data_scouting.fbs
@@ -0,0 +1,7 @@
+namespace scouting.webserver.requests;
+
+table Request2024DataScouting {
+
+}
+
+root_type Request2024DataScouting;
diff --git a/scouting/webserver/requests/messages/request_2024_data_scouting_response.fbs b/scouting/webserver/requests/messages/request_2024_data_scouting_response.fbs
new file mode 100644
index 0000000..d653f04
--- /dev/null
+++ b/scouting/webserver/requests/messages/request_2024_data_scouting_response.fbs
@@ -0,0 +1,37 @@
+namespace scouting.webserver.requests;
+
+table Stats2024 {
+ team_number:string (id: 0);
+ match_number:int (id: 1);
+ set_number:int (id: 18);
+ comp_level:string (id: 19);
+
+ starting_quadrant:int (id: 2);
+ speaker_auto:int (id:3);
+ amp_auto:int (id:4);
+ notes_dropped_auto:int (id: 5);
+ mobility_auto: bool (id: 6);
+
+ speaker:int (id:7);
+ amp:int (id:8);
+ speaker_amplified:int (id:9);
+ amp_amplified:int (id:10);
+ notes_dropped:int (id:11);
+
+ penalties:int (id:12);
+ trap_note:bool (id:13);
+ // Time in nanoseconds.
+ avg_cycle: int64 (id:14);
+ park: bool (id:15);
+ on_stage: bool (id:16);
+ harmony: bool (id:17);
+
+ pre_scouting:bool (id:20);
+ collected_by:string (id:21);
+}
+
+table Request2024DataScoutingResponse {
+ stats_list:[Stats2024] (id:0);
+}
+
+root_type Request2024DataScoutingResponse;
diff --git a/scouting/webserver/requests/messages/submit_2024_actions.fbs b/scouting/webserver/requests/messages/submit_2024_actions.fbs
new file mode 100644
index 0000000..5cb3cbe
--- /dev/null
+++ b/scouting/webserver/requests/messages/submit_2024_actions.fbs
@@ -0,0 +1,71 @@
+namespace scouting.webserver.requests;
+
+table StartMatchAction {
+ position:int (id:0);
+}
+
+enum ScoreType: short {
+ kAMP,
+ kAMP_AMPLIFIED,
+ kSPEAKER,
+ kSPEAKER_AMPLIFIED,
+}
+
+table MobilityAction {
+ mobility:bool (id:0);
+}
+
+table PenaltyAction {}
+
+table PickupNoteAction {
+ auto:bool (id:0);
+}
+
+table PlaceNoteAction {
+ score_type:ScoreType (id:0);
+ auto:bool (id:1);
+}
+
+table RobotDeathAction {
+ robot_dead:bool (id:0);
+}
+
+enum StageType: short {
+ kON_STAGE,
+ kPARK,
+ kHARMONY,
+ kMISSING,
+}
+
+table EndMatchAction {
+ stage_type:StageType (id:0);
+ trap_note:bool (id:1);
+}
+
+union ActionType {
+ MobilityAction,
+ StartMatchAction,
+ PickupNoteAction,
+ PlaceNoteAction,
+ PenaltyAction,
+ RobotDeathAction,
+ EndMatchAction
+}
+
+table Action {
+ timestamp:int64 (id:0);
+ action_taken:ActionType (id:2);
+}
+
+table Submit2024Actions {
+ team_number:string (id: 0);
+ match_number:int (id: 1);
+ set_number:int (id: 2);
+ comp_level:string (id: 3);
+ actions_list:[Action] (id:4);
+
+ // If this is for pre-scouting, then the server should accept this
+ // submission. I.e. checking that the match information exists in the match
+ // list should be skipped.
+ pre_scouting:bool (id: 5);
+}
\ No newline at end of file
diff --git a/scouting/webserver/requests/messages/submit_2024_actions_response.fbs b/scouting/webserver/requests/messages/submit_2024_actions_response.fbs
new file mode 100644
index 0000000..100172b
--- /dev/null
+++ b/scouting/webserver/requests/messages/submit_2024_actions_response.fbs
@@ -0,0 +1,7 @@
+namespace scouting.webserver.requests;
+
+table Submit2024ActionsResponse {
+ // empty response
+}
+
+root_type Submit2024ActionsResponse;
\ No newline at end of file
diff --git a/scouting/webserver/requests/requests.go b/scouting/webserver/requests/requests.go
index 9628c0d..75b438b 100644
--- a/scouting/webserver/requests/requests.go
+++ b/scouting/webserver/requests/requests.go
@@ -14,9 +14,13 @@
"github.com/frc971/971-Robot-Code/scouting/db"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/delete_2023_data_scouting"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/delete_2023_data_scouting_response"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/delete_2024_data_scouting"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/delete_2024_data_scouting_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/error_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_2023_data_scouting"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_2023_data_scouting_response"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_2024_data_scouting"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_2024_data_scouting_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_all_driver_rankings"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_all_driver_rankings_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_all_matches"
@@ -31,6 +35,8 @@
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_pit_images_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_shift_schedule"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_shift_schedule_response"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_2024_actions"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_2024_actions_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_actions"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_actions_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_driver_ranking"
@@ -53,6 +59,8 @@
type RequestAllNotesResponseT = request_all_notes_response.RequestAllNotesResponseT
type Request2023DataScouting = request_2023_data_scouting.Request2023DataScouting
type Request2023DataScoutingResponseT = request_2023_data_scouting_response.Request2023DataScoutingResponseT
+type Request2024DataScouting = request_2024_data_scouting.Request2024DataScouting
+type Request2024DataScoutingResponseT = request_2024_data_scouting_response.Request2024DataScoutingResponseT
type SubmitNotes = submit_notes.SubmitNotes
type SubmitNotesResponseT = submit_notes_response.SubmitNotesResponseT
type SubmitPitImage = submit_pit_image.SubmitPitImage
@@ -71,9 +79,14 @@
type SubmitDriverRankingResponseT = submit_driver_ranking_response.SubmitDriverRankingResponseT
type SubmitActions = submit_actions.SubmitActions
type Action = submit_actions.Action
+type Action2024 = submit_2024_actions.Action
type SubmitActionsResponseT = submit_actions_response.SubmitActionsResponseT
+type Submit2024Actions = submit_2024_actions.Submit2024Actions
+type Submit2024ActionsResponseT = submit_2024_actions_response.Submit2024ActionsResponseT
type Delete2023DataScouting = delete_2023_data_scouting.Delete2023DataScouting
type Delete2023DataScoutingResponseT = delete_2023_data_scouting_response.Delete2023DataScoutingResponseT
+type Delete2024DataScouting = delete_2024_data_scouting.Delete2024DataScouting
+type Delete2024DataScoutingResponseT = delete_2024_data_scouting_response.Delete2024DataScoutingResponseT
// The interface we expect the database abstraction to conform to.
// We use an interface here because it makes unit testing easier.
@@ -81,12 +94,15 @@
AddToMatch(db.TeamMatch) error
AddToShift(db.Shift) error
AddToStats2023(db.Stats2023) error
+ AddToStats2024(db.Stats2024) error
ReturnMatches() ([]db.TeamMatch, error)
ReturnAllNotes() ([]db.NotesData, error)
ReturnAllDriverRankings() ([]db.DriverRankingData, error)
ReturnAllShifts() ([]db.Shift, error)
ReturnStats2023() ([]db.Stats2023, error)
ReturnStats2023ForTeam(teamNumber string, matchNumber int32, setNumber int32, compLevel string, preScouting bool) ([]db.Stats2023, error)
+ ReturnStats2024() ([]db.Stats2024, error)
+ ReturnStats2024ForTeam(teamNumber string, matchNumber int32, setNumber int32, compLevel string, preScouting bool) ([]db.Stats2024, error)
QueryAllShifts(int) ([]db.Shift, error)
QueryNotes(string) ([]string, error)
QueryPitImages(string) ([]db.RequestedPitImage, error)
@@ -96,6 +112,7 @@
AddDriverRanking(db.DriverRankingData) error
AddAction(db.Action) error
DeleteFromStats(string, int32, int32, string) error
+ DeleteFromStats2024(string, int32, int32, string) error
DeleteFromActions(string, int32, int32, string) error
}
@@ -182,6 +199,7 @@
}
func (handler requestAllMatchesHandler) teamHasBeenDataScouted(key MatchAssemblyKey, teamNumber string) (bool, error) {
+ // TODO change this to reference 2024 stats
stats, err := handler.db.ReturnStats2023ForTeam(
teamNumber, key.MatchNumber, key.SetNumber, key.CompLevel, false)
if err != nil {
@@ -426,6 +444,165 @@
w.Write(builder.FinishedBytes())
}
+func ConvertActionsToStat2024(submit2024Actions *submit_2024_actions.Submit2024Actions) (db.Stats2024, error) {
+ overall_time := int64(0)
+ cycles := int64(0)
+ picked_up := false
+ lastPlacedTime := int64(0)
+ stat := db.Stats2024{
+ PreScouting: submit2024Actions.PreScouting(), TeamNumber: string(submit2024Actions.TeamNumber()), MatchNumber: submit2024Actions.MatchNumber(), SetNumber: submit2024Actions.SetNumber(), CompLevel: string(submit2024Actions.CompLevel()),
+ StartingQuadrant: 0, SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
+ Speaker: 0, Amp: 0, SpeakerAmplified: 0, AmpAmplified: 0, NotesDropped: 0, Penalties: 0,
+ TrapNote: false, AvgCycle: 0, Park: false, OnStage: false, Harmony: false, CollectedBy: "",
+ }
+ // Loop over all actions.
+ for i := 0; i < submit2024Actions.ActionsListLength(); i++ {
+ var action submit_2024_actions.Action
+ if !submit2024Actions.ActionsList(&action, i) {
+ return db.Stats2024{}, errors.New(fmt.Sprintf("Failed to parse submit_2024_actions.Action"))
+ }
+ actionTable := new(flatbuffers.Table)
+ action_type := action.ActionTakenType()
+ if !action.ActionTaken(actionTable) {
+ return db.Stats2024{}, errors.New(fmt.Sprint("Failed to parse sub-action or sub-action was missing"))
+ }
+ if action_type == submit_2024_actions.ActionTypeStartMatchAction {
+ var startMatchAction submit_2024_actions.StartMatchAction
+ startMatchAction.Init(actionTable.Bytes, actionTable.Pos)
+ stat.StartingQuadrant = startMatchAction.Position()
+ } else if action_type == submit_2024_actions.ActionTypeMobilityAction {
+ var mobilityAction submit_2024_actions.MobilityAction
+ mobilityAction.Init(actionTable.Bytes, actionTable.Pos)
+ if mobilityAction.Mobility() {
+ stat.MobilityAuto = true
+ }
+
+ } else if action_type == submit_2024_actions.ActionTypePenaltyAction {
+ var penaltyAction submit_2024_actions.PenaltyAction
+ penaltyAction.Init(actionTable.Bytes, actionTable.Pos)
+ stat.Penalties += 1
+
+ } else if action_type == submit_2024_actions.ActionTypePickupNoteAction {
+ var pick_up_action submit_2024_actions.PickupNoteAction
+ pick_up_action.Init(actionTable.Bytes, actionTable.Pos)
+ if picked_up == true {
+ auto := pick_up_action.Auto()
+ if auto == false {
+ stat.NotesDropped += 1
+ } else {
+ stat.NotesDroppedAuto += 1
+ }
+ } else {
+ picked_up = true
+ }
+ } else if action_type == submit_2024_actions.ActionTypePlaceNoteAction {
+ var place_action submit_2024_actions.PlaceNoteAction
+ place_action.Init(actionTable.Bytes, actionTable.Pos)
+ if !picked_up {
+ return db.Stats2024{}, errors.New(fmt.Sprintf("Got PlaceNoteAction without corresponding PickupObjectAction"))
+ }
+ score_type := place_action.ScoreType()
+ auto := place_action.Auto()
+ if score_type == submit_2024_actions.ScoreTypekAMP && auto {
+ stat.AmpAuto += 1
+ } else if score_type == submit_2024_actions.ScoreTypekAMP && !auto {
+ stat.Amp += 1
+ } else if score_type == submit_2024_actions.ScoreTypekAMP_AMPLIFIED && !auto {
+ stat.AmpAmplified += 1
+ } else if score_type == submit_2024_actions.ScoreTypekSPEAKER && !auto {
+ stat.Speaker += 1
+ } else if score_type == submit_2024_actions.ScoreTypekSPEAKER && auto {
+ stat.SpeakerAuto += 1
+ } else if score_type == submit_2024_actions.ScoreTypekSPEAKER_AMPLIFIED && !auto {
+ stat.SpeakerAmplified += 1
+ } else {
+ return db.Stats2024{}, errors.New(fmt.Sprintf("Got unknown ObjectType/ScoreLevel/Auto combination"))
+ }
+ picked_up = false
+ if lastPlacedTime != int64(0) {
+ // If this is not the first time we place,
+ // start counting cycle time. We define cycle
+ // time as the time between placements.
+ overall_time += int64(action.Timestamp()) - lastPlacedTime
+ cycles += 1
+ }
+ lastPlacedTime = int64(action.Timestamp())
+ } else if action_type == submit_2024_actions.ActionTypeEndMatchAction {
+ var endMatchAction submit_2024_actions.EndMatchAction
+ endMatchAction.Init(actionTable.Bytes, actionTable.Pos)
+ if endMatchAction.StageType() == submit_2024_actions.StageTypekON_STAGE {
+ stat.OnStage = true
+ } else if endMatchAction.StageType() == submit_2024_actions.StageTypekPARK {
+ stat.Park = true
+ } else if endMatchAction.StageType() == submit_2024_actions.StageTypekHARMONY {
+ stat.Harmony = true
+ }
+ stat.TrapNote = endMatchAction.TrapNote()
+ }
+ }
+ if cycles != 0 {
+ stat.AvgCycle = overall_time / cycles
+ } else {
+ stat.AvgCycle = 0
+ }
+ return stat, nil
+}
+
+// Handles a Request2024DataScouting request.
+type request2024DataScoutingHandler struct {
+ db Database
+}
+
+func (handler request2024DataScoutingHandler) 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
+ }
+
+ _, success := parseRequest(w, requestBytes, "Request2024DataScouting", request_2024_data_scouting.GetRootAsRequest2024DataScouting)
+ if !success {
+ return
+ }
+
+ stats, err := handler.db.ReturnStats2024()
+ if err != nil {
+ respondWithError(w, http.StatusInternalServerError, fmt.Sprint("Failed to query database: ", err))
+ return
+ }
+
+ var response Request2024DataScoutingResponseT
+ for _, stat := range stats {
+ response.StatsList = append(response.StatsList, &request_2024_data_scouting_response.Stats2024T{
+ TeamNumber: stat.TeamNumber,
+ MatchNumber: stat.MatchNumber,
+ SetNumber: stat.SetNumber,
+ CompLevel: stat.CompLevel,
+ StartingQuadrant: stat.StartingQuadrant,
+ SpeakerAuto: stat.SpeakerAuto,
+ AmpAuto: stat.AmpAuto,
+ NotesDroppedAuto: stat.NotesDroppedAuto,
+ MobilityAuto: stat.MobilityAuto,
+ Speaker: stat.Speaker,
+ Amp: stat.Amp,
+ SpeakerAmplified: stat.SpeakerAmplified,
+ AmpAmplified: stat.AmpAmplified,
+ NotesDropped: stat.NotesDropped,
+ Penalties: stat.Penalties,
+ TrapNote: stat.TrapNote,
+ AvgCycle: stat.AvgCycle,
+ Park: stat.Park,
+ OnStage: stat.OnStage,
+ Harmony: stat.Harmony,
+ CollectedBy: stat.CollectedBy,
+ })
+ }
+
+ builder := flatbuffers.NewBuilder(50 * 1024)
+ builder.Finish((&response).Pack(builder))
+ w.Write(builder.FinishedBytes())
+}
+
func ConvertActionsToStat(submitActions *submit_actions.SubmitActions) (db.Stats2023, error) {
overall_time := int64(0)
cycles := int64(0)
@@ -926,6 +1103,77 @@
w.Write(builder.FinishedBytes())
}
+type submit2024ActionsHandler struct {
+ db Database
+}
+
+func (handler submit2024ActionsHandler) ServeHTTP(w http.ResponseWriter, req *http.Request) {
+ // Get the username of the person submitting the data.
+ username := parseUsername(req)
+
+ requestBytes, err := io.ReadAll(req.Body)
+ if err != nil {
+ respondWithError(w, http.StatusBadRequest, fmt.Sprint("Failed to read request bytes:", err))
+ return
+ }
+
+ request, success := parseRequest(w, requestBytes, "Submit2024Actions", submit_2024_actions.GetRootAsSubmit2024Actions)
+ if !success {
+ return
+ }
+
+ log.Println("Got actions for match", request.MatchNumber(), "team", request.TeamNumber(), "from", username)
+
+ for i := 0; i < request.ActionsListLength(); i++ {
+
+ var action Action2024
+ request.ActionsList(&action, i)
+
+ dbAction := db.Action{
+ PreScouting: request.PreScouting(),
+ TeamNumber: string(request.TeamNumber()),
+ MatchNumber: request.MatchNumber(),
+ SetNumber: request.SetNumber(),
+ CompLevel: string(request.CompLevel()),
+ //TODO: Serialize CompletedAction
+ CompletedAction: []byte{},
+ Timestamp: action.Timestamp(),
+ CollectedBy: username,
+ }
+
+ // Do some error checking.
+ if action.Timestamp() < 0 {
+ respondWithError(w, http.StatusBadRequest, fmt.Sprint(
+ "Invalid timestamp field value of ", action.Timestamp()))
+ return
+ }
+
+ err = handler.db.AddAction(dbAction)
+ if err != nil {
+ respondWithError(w, http.StatusInternalServerError, fmt.Sprint("Failed to add action to database: ", err))
+ return
+ }
+ }
+
+ stats, err := ConvertActionsToStat2024(request)
+ if err != nil {
+ respondWithError(w, http.StatusInternalServerError, fmt.Sprint("Failed to convert actions to stats: ", err))
+ return
+ }
+
+ stats.CollectedBy = username
+
+ err = handler.db.AddToStats2024(stats)
+ if err != nil {
+ respondWithError(w, http.StatusInternalServerError, fmt.Sprint("Failed to submit stats: ", stats, ": ", err))
+ return
+ }
+
+ builder := flatbuffers.NewBuilder(50 * 1024)
+ builder.Finish((&SubmitActionsResponseT{}).Pack(builder))
+ w.Write(builder.FinishedBytes())
+}
+
type submitActionsHandler struct {
db Database
}
@@ -997,6 +1245,50 @@
w.Write(builder.FinishedBytes())
}
+type Delete2024DataScoutingHandler struct {
+ db Database
+}
+
+func (handler Delete2024DataScoutingHandler) 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 := parseRequest(w, requestBytes, "Delete2024DataScouting", delete_2024_data_scouting.GetRootAsDelete2024DataScouting)
+ if !success {
+ return
+ }
+
+ err = handler.db.DeleteFromStats2024(
+ string(request.CompLevel()),
+ request.MatchNumber(),
+ request.SetNumber(),
+ string(request.TeamNumber()))
+
+ if err != nil {
+ respondWithError(w, http.StatusInternalServerError, fmt.Sprintf("Failed to delete from stats2024: %v", err))
+ return
+ }
+
+ err = handler.db.DeleteFromActions(
+ string(request.CompLevel()),
+ request.MatchNumber(),
+ request.SetNumber(),
+ string(request.TeamNumber()))
+
+ if err != nil {
+ respondWithError(w, http.StatusInternalServerError, fmt.Sprintf("Failed to delete from actions: %v", err))
+ return
+ }
+
+ var response Delete2024DataScoutingResponseT
+ builder := flatbuffers.NewBuilder(10)
+ builder.Finish((&response).Pack(builder))
+ w.Write(builder.FinishedBytes())
+}
+
type Delete2023DataScoutingHandler struct {
db Database
}
@@ -1047,6 +1339,7 @@
scoutingServer.Handle("/requests/request/all_notes", requestAllNotesHandler{db})
scoutingServer.Handle("/requests/request/all_driver_rankings", requestAllDriverRankingsHandler{db})
scoutingServer.Handle("/requests/request/2023_data_scouting", request2023DataScoutingHandler{db})
+ scoutingServer.Handle("/requests/request/2024_data_scouting", request2024DataScoutingHandler{db})
scoutingServer.Handle("/requests/submit/submit_notes", submitNoteScoutingHandler{db})
scoutingServer.Handle("/requests/submit/submit_pit_image", submitPitImageScoutingHandler{db})
scoutingServer.Handle("/requests/request/pit_images", requestPitImagesHandler{db})
@@ -1056,5 +1349,7 @@
scoutingServer.Handle("/requests/request/shift_schedule", requestShiftScheduleHandler{db})
scoutingServer.Handle("/requests/submit/submit_driver_ranking", SubmitDriverRankingHandler{db})
scoutingServer.Handle("/requests/submit/submit_actions", submitActionsHandler{db})
+ scoutingServer.Handle("/requests/submit/submit_2024_actions", submit2024ActionsHandler{db})
scoutingServer.Handle("/requests/delete/delete_2023_data_scouting", Delete2023DataScoutingHandler{db})
+ scoutingServer.Handle("/requests/delete/delete_2024_data_scouting", Delete2024DataScoutingHandler{db})
}
diff --git a/scouting/webserver/requests/requests_test.go b/scouting/webserver/requests/requests_test.go
index d81b659..67244d3 100644
--- a/scouting/webserver/requests/requests_test.go
+++ b/scouting/webserver/requests/requests_test.go
@@ -8,8 +8,11 @@
"github.com/frc971/971-Robot-Code/scouting/db"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/debug"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/delete_2023_data_scouting"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/delete_2024_data_scouting"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_2023_data_scouting"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_2023_data_scouting_response"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_2024_data_scouting"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_2024_data_scouting_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_all_driver_rankings"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_all_driver_rankings_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_all_matches"
@@ -23,6 +26,7 @@
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_pit_images_response"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_shift_schedule"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/request_shift_schedule_response"
+ "github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_2024_actions"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_actions"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_driver_ranking"
"github.com/frc971/971-Robot-Code/scouting/webserver/requests/messages/submit_notes"
@@ -209,6 +213,71 @@
}
+// Validates that we can request the 2024 stats.
+func TestRequest2024DataScouting(t *testing.T) {
+ db := MockDatabase{
+ stats2024: []db.Stats2024{
+ {
+ PreScouting: false, TeamNumber: "342",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 4,
+ SpeakerAuto: 1, AmpAuto: 1, NotesDroppedAuto: 0, MobilityAuto: true,
+ Speaker: 4, Amp: 2, SpeakerAmplified: 1, AmpAmplified: 0,
+ NotesDropped: 2, Penalties: 2, TrapNote: true, AvgCycle: 0,
+ Park: true, OnStage: false, Harmony: false, CollectedBy: "alex",
+ },
+ {
+ PreScouting: false, TeamNumber: "982",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 2,
+ SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
+ Speaker: 0, Amp: 2, SpeakerAmplified: 3, AmpAmplified: 2,
+ NotesDropped: 1, Penalties: 0, TrapNote: false, AvgCycle: 0,
+ Park: false, OnStage: true, Harmony: false, CollectedBy: "george",
+ },
+ },
+ }
+ scoutingServer := server.NewScoutingServer()
+ HandleRequests(&db, scoutingServer)
+ scoutingServer.Start(8080)
+ defer scoutingServer.Stop()
+
+ builder := flatbuffers.NewBuilder(1024)
+ builder.Finish((&request_2024_data_scouting.Request2024DataScoutingT{}).Pack(builder))
+
+ response, err := debug.Request2024DataScouting("http://localhost:8080", builder.FinishedBytes())
+ if err != nil {
+ t.Fatal("Failed to request all matches: ", err)
+ }
+
+ expected := request_2024_data_scouting_response.Request2024DataScoutingResponseT{
+ StatsList: []*request_2024_data_scouting_response.Stats2024T{
+ {
+ PreScouting: false, TeamNumber: "342",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 4,
+ SpeakerAuto: 1, AmpAuto: 1, NotesDroppedAuto: 0, MobilityAuto: true,
+ Speaker: 4, Amp: 2, SpeakerAmplified: 1, AmpAmplified: 0,
+ NotesDropped: 2, Penalties: 2, TrapNote: true, AvgCycle: 0,
+ Park: true, OnStage: false, Harmony: false, CollectedBy: "alex",
+ },
+ {
+ PreScouting: false, TeamNumber: "982",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 2,
+ SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
+ Speaker: 0, Amp: 2, SpeakerAmplified: 3, AmpAmplified: 2,
+ NotesDropped: 1, Penalties: 0, TrapNote: false, AvgCycle: 0,
+ Park: false, OnStage: true, Harmony: false, CollectedBy: "george",
+ },
+ },
+ }
+ if len(expected.StatsList) != len(response.StatsList) {
+ t.Fatal("Expected ", expected, ", but got ", *response)
+ }
+ for i, match := range expected.StatsList {
+ if !reflect.DeepEqual(*match, *response.StatsList[i]) {
+ t.Fatal("Expected for stats", i, ":", *match, ", but got:", *response.StatsList[i])
+ }
+ }
+}
+
// Validates that we can request the 2023 stats.
func TestRequest2023DataScouting(t *testing.T) {
db := MockDatabase{
@@ -290,6 +359,141 @@
}
}
+// Validates that we can request the 2024 stats.
+func TestConvertActionsToStat2024(t *testing.T) {
+ builder := flatbuffers.NewBuilder(1024)
+ builder.Finish((&submit_2024_actions.Submit2024ActionsT{
+ TeamNumber: "4244",
+ MatchNumber: 3,
+ SetNumber: 1,
+ CompLevel: "quals",
+ ActionsList: []*submit_2024_actions.ActionT{
+ {
+ ActionTaken: &submit_2024_actions.ActionTypeT{
+ Type: submit_2024_actions.ActionTypeStartMatchAction,
+ Value: &submit_2024_actions.StartMatchActionT{
+ Position: 2,
+ },
+ },
+ Timestamp: 0,
+ },
+ {
+ ActionTaken: &submit_2024_actions.ActionTypeT{
+ Type: submit_2024_actions.ActionTypePickupNoteAction,
+ Value: &submit_2024_actions.PickupNoteActionT{
+ Auto: true,
+ },
+ },
+ Timestamp: 400,
+ },
+ {
+ ActionTaken: &submit_2024_actions.ActionTypeT{
+ Type: submit_2024_actions.ActionTypePickupNoteAction,
+ Value: &submit_2024_actions.PickupNoteActionT{
+ Auto: true,
+ },
+ },
+ Timestamp: 800,
+ },
+ {
+ ActionTaken: &submit_2024_actions.ActionTypeT{
+ Type: submit_2024_actions.ActionTypePlaceNoteAction,
+ Value: &submit_2024_actions.PlaceNoteActionT{
+ ScoreType: submit_2024_actions.ScoreTypekAMP,
+ Auto: true,
+ },
+ },
+ Timestamp: 2000,
+ },
+ {
+ ActionTaken: &submit_2024_actions.ActionTypeT{
+ Type: submit_2024_actions.ActionTypeMobilityAction,
+ Value: &submit_2024_actions.MobilityActionT{
+ Mobility: true,
+ },
+ },
+ Timestamp: 2200,
+ },
+ {
+ ActionTaken: &submit_2024_actions.ActionTypeT{
+ Type: submit_2024_actions.ActionTypePenaltyAction,
+ Value: &submit_2024_actions.PenaltyActionT{},
+ },
+ Timestamp: 2400,
+ },
+ {
+ ActionTaken: &submit_2024_actions.ActionTypeT{
+ Type: submit_2024_actions.ActionTypePickupNoteAction,
+ Value: &submit_2024_actions.PickupNoteActionT{
+ Auto: false,
+ },
+ },
+ Timestamp: 2800,
+ },
+ {
+ ActionTaken: &submit_2024_actions.ActionTypeT{
+ Type: submit_2024_actions.ActionTypePlaceNoteAction,
+ Value: &submit_2024_actions.PlaceNoteActionT{
+ ScoreType: submit_2024_actions.ScoreTypekAMP_AMPLIFIED,
+ Auto: false,
+ },
+ },
+ Timestamp: 3100,
+ },
+ {
+ ActionTaken: &submit_2024_actions.ActionTypeT{
+ Type: submit_2024_actions.ActionTypePickupNoteAction,
+ Value: &submit_2024_actions.PickupNoteActionT{
+ Auto: false,
+ },
+ },
+ Timestamp: 3500,
+ },
+ {
+ ActionTaken: &submit_2024_actions.ActionTypeT{
+ Type: submit_2024_actions.ActionTypePlaceNoteAction,
+ Value: &submit_2024_actions.PlaceNoteActionT{
+ ScoreType: submit_2024_actions.ScoreTypekSPEAKER_AMPLIFIED,
+ Auto: false,
+ },
+ },
+ Timestamp: 3900,
+ },
+ {
+ ActionTaken: &submit_2024_actions.ActionTypeT{
+ Type: submit_2024_actions.ActionTypeEndMatchAction,
+ Value: &submit_2024_actions.EndMatchActionT{
+ StageType: submit_2024_actions.StageTypekHARMONY,
+ TrapNote: false,
+ },
+ },
+ Timestamp: 4200,
+ },
+ },
+ PreScouting: false,
+ }).Pack(builder))
+
+ submit2024Actions := submit_2024_actions.GetRootAsSubmit2024Actions(builder.FinishedBytes(), 0)
+ response, err := ConvertActionsToStat2024(submit2024Actions)
+
+ if err != nil {
+ t.Fatal("Failed to convert actions to stats: ", err)
+ }
+
+ expected := db.Stats2024{
+ PreScouting: false, TeamNumber: "4244",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 2,
+ SpeakerAuto: 0, AmpAuto: 1, NotesDroppedAuto: 1, MobilityAuto: true,
+ Speaker: 0, Amp: 0, SpeakerAmplified: 1, AmpAmplified: 1,
+ NotesDropped: 0, Penalties: 1, TrapNote: false, AvgCycle: 950,
+ Park: false, OnStage: false, Harmony: true, CollectedBy: "",
+ }
+
+ if expected != response {
+ t.Fatal("Expected ", expected, ", but got ", response)
+ }
+}
+
// Validates that we can request the 2023 stats.
func TestConvertActionsToStat(t *testing.T) {
builder := flatbuffers.NewBuilder(1024)
@@ -931,6 +1135,90 @@
return (builder.FinishedBytes())
}
+func TestAddingActions2024(t *testing.T) {
+ database := MockDatabase{}
+ scoutingServer := server.NewScoutingServer()
+ HandleRequests(&database, scoutingServer)
+ scoutingServer.Start(8080)
+ defer scoutingServer.Stop()
+
+ builder := flatbuffers.NewBuilder(1024)
+ builder.Finish((&submit_2024_actions.Submit2024ActionsT{
+ TeamNumber: "3421",
+ MatchNumber: 2,
+ SetNumber: 1,
+ CompLevel: "quals",
+ ActionsList: []*submit_2024_actions.ActionT{
+ {
+ ActionTaken: &submit_2024_actions.ActionTypeT{
+ Type: submit_2024_actions.ActionTypePickupNoteAction,
+ Value: &submit_2024_actions.PickupNoteActionT{
+ Auto: true,
+ },
+ },
+ Timestamp: 1800,
+ },
+ {
+ ActionTaken: &submit_2024_actions.ActionTypeT{
+ Type: submit_2024_actions.ActionTypePlaceNoteAction,
+ Value: &submit_2024_actions.PlaceNoteActionT{
+ ScoreType: submit_2024_actions.ScoreTypekSPEAKER,
+ Auto: false,
+ },
+ },
+ Timestamp: 2500,
+ },
+ },
+ PreScouting: true,
+ }).Pack(builder))
+
+ _, err := debug.Submit2024Actions("http://localhost:8080", builder.FinishedBytes())
+ if err != nil {
+ t.Fatal("Failed to submit actions: ", err)
+ }
+
+ expectedActions := []db.Action{
+ {
+ PreScouting: true,
+ TeamNumber: "3421",
+ MatchNumber: 2,
+ SetNumber: 1,
+ CompLevel: "quals",
+ CollectedBy: "debug_cli",
+ CompletedAction: []byte{},
+ Timestamp: 1800,
+ },
+ {
+ PreScouting: true,
+ TeamNumber: "3421",
+ MatchNumber: 2,
+ SetNumber: 1,
+ CompLevel: "quals",
+ CollectedBy: "debug_cli",
+ CompletedAction: []byte{},
+ Timestamp: 2500,
+ },
+ }
+
+ expectedStats := []db.Stats2024{
+ db.Stats2024{
+ PreScouting: true, TeamNumber: "3421",
+ MatchNumber: 2, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 0,
+ SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
+ Speaker: 1, Amp: 0, SpeakerAmplified: 0, AmpAmplified: 0,
+ NotesDropped: 0, Penalties: 0, TrapNote: false, AvgCycle: 0,
+ Park: false, OnStage: false, Harmony: false, CollectedBy: "debug_cli",
+ },
+ }
+
+ if !reflect.DeepEqual(expectedActions, database.actions) {
+ t.Fatal("Expected ", expectedActions, ", but got:", database.actions)
+ }
+ if !reflect.DeepEqual(expectedStats, database.stats2024) {
+ t.Fatal("Expected ", expectedStats, ", but got:", database.stats2024)
+ }
+}
+
func TestAddingActions(t *testing.T) {
database := MockDatabase{}
scoutingServer := server.NewScoutingServer()
@@ -1155,6 +1443,100 @@
}
}
+// Validates that we can delete 2024 stats.
+func TestDeleteFromStats2024(t *testing.T) {
+ database := MockDatabase{
+ stats2024: []db.Stats2024{
+ {
+ PreScouting: false, TeamNumber: "746",
+ MatchNumber: 3, SetNumber: 1, CompLevel: "quals", StartingQuadrant: 2,
+ SpeakerAuto: 0, AmpAuto: 1, NotesDroppedAuto: 1, MobilityAuto: true,
+ Speaker: 0, Amp: 1, SpeakerAmplified: 1, AmpAmplified: 1,
+ NotesDropped: 0, Penalties: 1, TrapNote: true, AvgCycle: 233,
+ Park: false, OnStage: false, Harmony: true, CollectedBy: "alek",
+ },
+ {
+ PreScouting: false, TeamNumber: "244",
+ MatchNumber: 5, SetNumber: 3, CompLevel: "quals", StartingQuadrant: 1,
+ SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
+ Speaker: 0, Amp: 0, SpeakerAmplified: 3, AmpAmplified: 1,
+ NotesDropped: 0, Penalties: 1, TrapNote: false, AvgCycle: 120,
+ Park: false, OnStage: true, Harmony: false, CollectedBy: "kacey",
+ },
+ },
+ actions: []db.Action{
+ {
+ PreScouting: true,
+ TeamNumber: "746",
+ MatchNumber: 3,
+ SetNumber: 1,
+ CompLevel: "quals",
+ CollectedBy: "debug_cli",
+ CompletedAction: []byte{},
+ Timestamp: 2400,
+ },
+ {
+ PreScouting: true,
+ TeamNumber: "244",
+ MatchNumber: 5,
+ SetNumber: 3,
+ CompLevel: "quals",
+ CollectedBy: "debug_cli",
+ CompletedAction: []byte{},
+ Timestamp: 1009,
+ },
+ },
+ }
+ scoutingServer := server.NewScoutingServer()
+ HandleRequests(&database, scoutingServer)
+ scoutingServer.Start(8080)
+ defer scoutingServer.Stop()
+
+ builder := flatbuffers.NewBuilder(1024)
+ builder.Finish((&delete_2024_data_scouting.Delete2024DataScoutingT{
+ CompLevel: "quals",
+ MatchNumber: 3,
+ SetNumber: 1,
+ TeamNumber: "746",
+ }).Pack(builder))
+
+ _, err := debug.Delete2024DataScouting("http://localhost:8080", builder.FinishedBytes())
+ if err != nil {
+ t.Fatal("Failed to delete from data scouting 2024", err)
+ }
+
+ expectedActions := []db.Action{
+ {
+ PreScouting: true,
+ TeamNumber: "244",
+ MatchNumber: 5,
+ SetNumber: 3,
+ CompLevel: "quals",
+ CollectedBy: "debug_cli",
+ CompletedAction: []byte{},
+ Timestamp: 1009,
+ },
+ }
+
+ expectedStats := []db.Stats2024{
+ {
+ PreScouting: false, TeamNumber: "244",
+ MatchNumber: 5, SetNumber: 3, CompLevel: "quals", StartingQuadrant: 1,
+ SpeakerAuto: 0, AmpAuto: 0, NotesDroppedAuto: 0, MobilityAuto: false,
+ Speaker: 0, Amp: 0, SpeakerAmplified: 3, AmpAmplified: 1,
+ NotesDropped: 0, Penalties: 1, TrapNote: false, AvgCycle: 120,
+ Park: false, OnStage: true, Harmony: false, CollectedBy: "kacey",
+ },
+ }
+
+ if !reflect.DeepEqual(expectedActions, database.actions) {
+ t.Fatal("Expected ", expectedActions, ", but got:", database.actions)
+ }
+ if !reflect.DeepEqual(expectedStats, database.stats2024) {
+ t.Fatal("Expected ", expectedStats, ", but got:", database.stats2024)
+ }
+}
+
// A mocked database we can use for testing. Add functionality to this as
// needed for your tests.
@@ -1164,6 +1546,7 @@
shiftSchedule []db.Shift
driver_ranking []db.DriverRankingData
stats2023 []db.Stats2023
+ stats2024 []db.Stats2024
actions []db.Action
images []db.PitImage
}
@@ -1177,6 +1560,11 @@
database.stats2023 = append(database.stats2023, stats2023)
return nil
}
+
+func (database *MockDatabase) AddToStats2024(stats2024 db.Stats2024) error {
+ database.stats2024 = append(database.stats2024, stats2024)
+ return nil
+}
func (database *MockDatabase) ReturnMatches() ([]db.TeamMatch, error) {
return database.matches, nil
}
@@ -1185,6 +1573,10 @@
return database.stats2023, nil
}
+func (database *MockDatabase) ReturnStats2024() ([]db.Stats2024, error) {
+ return database.stats2024, nil
+}
+
func (database *MockDatabase) ReturnStats2023ForTeam(teamNumber string, matchNumber int32, setNumber int32, compLevel string, preScouting bool) ([]db.Stats2023, error) {
var results []db.Stats2023
for _, stats := range database.stats2023 {
@@ -1195,6 +1587,16 @@
return results, nil
}
+func (database *MockDatabase) ReturnStats2024ForTeam(teamNumber string, matchNumber int32, setNumber int32, compLevel string, preScouting bool) ([]db.Stats2024, error) {
+ var results []db.Stats2024
+ for _, stats := range database.stats2024 {
+ if stats.TeamNumber == teamNumber && stats.MatchNumber == matchNumber && stats.SetNumber == setNumber && stats.CompLevel == compLevel && stats.PreScouting == preScouting {
+ results = append(results, stats)
+ }
+ }
+ return results, nil
+}
+
func (database *MockDatabase) QueryNotes(requestedTeam string) ([]string, error) {
var results []string
for _, data := range database.notes {
@@ -1281,6 +1683,19 @@
return nil
}
+func (database *MockDatabase) DeleteFromStats2024(compLevel_ string, matchNumber_ int32, setNumber_ int32, teamNumber_ string) error {
+ for i, stat := range database.stats2024 {
+ if stat.CompLevel == compLevel_ &&
+ stat.MatchNumber == matchNumber_ &&
+ stat.SetNumber == setNumber_ &&
+ stat.TeamNumber == teamNumber_ {
+ // Match found, remove the element from the array.
+ database.stats2024 = append(database.stats2024[:i], database.stats2024[i+1:]...)
+ }
+ }
+ return nil
+}
+
func (database *MockDatabase) DeleteFromActions(compLevel_ string, matchNumber_ int32, setNumber_ int32, teamNumber_ string) error {
for i, action := range database.actions {
if action.CompLevel == compLevel_ &&
diff --git a/y2014/actors/autonomous_actor.h b/y2014/actors/autonomous_actor.h
index f1b06bf..3ec82fa 100644
--- a/y2014/actors/autonomous_actor.h
+++ b/y2014/actors/autonomous_actor.h
@@ -13,8 +13,7 @@
#include "y2014/queues/auto_mode_generated.h"
#include "y2014/queues/hot_goal_generated.h"
-namespace y2014 {
-namespace actors {
+namespace y2014::actors {
class AutonomousActor : public ::frc971::autonomous::BaseAutonomousActor {
public:
@@ -48,7 +47,6 @@
actors::ShootActor::Factory shoot_action_factory_;
};
-} // namespace actors
-} // namespace y2014
+} // namespace y2014::actors
#endif // Y2014_ACTORS_AUTONOMOUS_ACTOR_H_
diff --git a/y2014/actors/shoot_actor.h b/y2014/actors/shoot_actor.h
index 37dc0c7..1280409 100644
--- a/y2014/actors/shoot_actor.h
+++ b/y2014/actors/shoot_actor.h
@@ -10,8 +10,7 @@
#include "y2014/control_loops/shooter/shooter_goal_generated.h"
#include "y2014/control_loops/shooter/shooter_status_generated.h"
-namespace y2014 {
-namespace actors {
+namespace y2014::actors {
class ShootActor
: public ::aos::common::actions::ActorBase<aos::common::actions::Goal> {
@@ -62,7 +61,6 @@
int previous_shots_;
};
-} // namespace actors
-} // namespace y2014
+} // namespace y2014::actors
#endif // Y2014_ACTORS_SHOOT_ACTOR_H_
diff --git a/y2014/constants.h b/y2014/constants.h
index aa4ac26..4baeb24 100644
--- a/y2014/constants.h
+++ b/y2014/constants.h
@@ -6,8 +6,7 @@
#include "frc971/control_loops/state_feedback_loop.h"
#include "frc971/shifter_hall_effect.h"
-namespace y2014 {
-namespace constants {
+namespace y2014::constants {
using ::frc971::constants::DualHallShifterHallEffect;
@@ -138,7 +137,6 @@
// them.
const Values &GetValuesForTeam(uint16_t team_number);
-} // namespace constants
-} // namespace y2014
+} // namespace y2014::constants
#endif // Y2014_CONSTANTS_H_
diff --git a/y2014/control_loops/drivetrain/drivetrain_base.h b/y2014/control_loops/drivetrain/drivetrain_base.h
index 48143c3..4822f67 100644
--- a/y2014/control_loops/drivetrain/drivetrain_base.h
+++ b/y2014/control_loops/drivetrain/drivetrain_base.h
@@ -3,13 +3,11 @@
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
-namespace y2014 {
-namespace control_loops {
+namespace y2014::control_loops {
const ::frc971::control_loops::drivetrain::DrivetrainConfig<double> &
GetDrivetrainConfig();
-} // namespace control_loops
-} // namespace y2014
+} // namespace y2014::control_loops
#endif // Y2014_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2014_bot3/actors/autonomous_actor.h b/y2014_bot3/actors/autonomous_actor.h
index e4dfe53..844e5a0 100644
--- a/y2014_bot3/actors/autonomous_actor.h
+++ b/y2014_bot3/actors/autonomous_actor.h
@@ -9,8 +9,7 @@
#include "aos/events/event_loop.h"
#include "frc971/autonomous/base_autonomous_actor.h"
-namespace y2014_bot3 {
-namespace actors {
+namespace y2014_bot3::actors {
class AutonomousActor : public ::frc971::autonomous::BaseAutonomousActor {
public:
@@ -26,7 +25,6 @@
}
};
-} // namespace actors
-} // namespace y2014_bot3
+} // namespace y2014_bot3::actors
#endif // Y2014_BOT3_ACTORS_AUTONOMOUS_ACTOR_H_
diff --git a/y2014_bot3/control_loops/drivetrain/drivetrain_base.h b/y2014_bot3/control_loops/drivetrain/drivetrain_base.h
index 98cb31d..914088a 100644
--- a/y2014_bot3/control_loops/drivetrain/drivetrain_base.h
+++ b/y2014_bot3/control_loops/drivetrain/drivetrain_base.h
@@ -3,9 +3,7 @@
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
-namespace y2014_bot3 {
-namespace control_loops {
-namespace drivetrain {
+namespace y2014_bot3::control_loops::drivetrain {
const double kDrivetrainEncoderRatio =
(17.0 / 50.0) /*output reduction*/ * (64.0 / 24.0) /*encoder gears*/;
@@ -13,8 +11,6 @@
const ::frc971::control_loops::drivetrain::DrivetrainConfig<double> &
GetDrivetrainConfig();
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace y2014_bot3
+} // namespace y2014_bot3::control_loops::drivetrain
#endif // Y2014_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2014_bot3/control_loops/rollers/rollers.h b/y2014_bot3/control_loops/rollers/rollers.h
index 3d08f59..675acef 100644
--- a/y2014_bot3/control_loops/rollers/rollers.h
+++ b/y2014_bot3/control_loops/rollers/rollers.h
@@ -7,9 +7,7 @@
#include "y2014_bot3/control_loops/rollers/rollers_position_generated.h"
#include "y2014_bot3/control_loops/rollers/rollers_status_generated.h"
-namespace y2014_bot3 {
-namespace control_loops {
-namespace rollers {
+namespace y2014_bot3::control_loops::rollers {
class Rollers
: public frc971::controls::ControlLoop<Goal, Position, Status, Output> {
@@ -26,8 +24,6 @@
aos::Sender<Status>::Builder *status) override;
};
-} // namespace rollers
-} // namespace control_loops
-} // namespace y2014_bot3
+} // namespace y2014_bot3::control_loops::rollers
#endif // Y2014_BOT3_CONTROL_LOOPS_ROLLERS_H_
diff --git a/y2016/actors/autonomous_actor.h b/y2016/actors/autonomous_actor.h
index 538322b..2e24638 100644
--- a/y2016/actors/autonomous_actor.h
+++ b/y2016/actors/autonomous_actor.h
@@ -16,8 +16,7 @@
#include "y2016/control_loops/superstructure/superstructure_status_generated.h"
#include "y2016/queues/ball_detector_generated.h"
-namespace y2016 {
-namespace actors {
+namespace y2016::actors {
class AutonomousActor : public ::frc971::autonomous::BaseAutonomousActor {
public:
@@ -100,7 +99,6 @@
superstructure_goal_sender_;
};
-} // namespace actors
-} // namespace y2016
+} // namespace y2016::actors
#endif // Y2016_ACTORS_AUTONOMOUS_ACTOR_H_
diff --git a/y2016/actors/superstructure_actor.h b/y2016/actors/superstructure_actor.h
index f1ae1fe..3f28c7e 100644
--- a/y2016/actors/superstructure_actor.h
+++ b/y2016/actors/superstructure_actor.h
@@ -9,8 +9,7 @@
#include "y2016/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2016/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2016 {
-namespace actors {
+namespace y2016::actors {
class SuperstructureActor
: public ::aos::common::actions::ActorBase<superstructure_action::Goal> {
@@ -46,7 +45,6 @@
bool SuperstructureDone();
};
-} // namespace actors
-} // namespace y2016
+} // namespace y2016::actors
#endif // Y2016_ACTORS_SUPERSTRUCTURE_ACTOR_H_
diff --git a/y2016/actors/vision_align_actor.h b/y2016/actors/vision_align_actor.h
index ac25439..9e604ae 100644
--- a/y2016/actors/vision_align_actor.h
+++ b/y2016/actors/vision_align_actor.h
@@ -10,8 +10,7 @@
#include "y2016/actors/vision_align_action_generated.h"
#include "y2016/vision/vision_generated.h"
-namespace y2016 {
-namespace actors {
+namespace y2016::actors {
class VisionAlignActor
: public ::aos::common::actions::ActorBase<vision_align_action::Goal> {
@@ -34,7 +33,6 @@
drivetrain_goal_sender_;
};
-} // namespace actors
-} // namespace y2016
+} // namespace y2016::actors
#endif
diff --git a/y2016/constants.h b/y2016/constants.h
index f332e37..c3bf681 100644
--- a/y2016/constants.h
+++ b/y2016/constants.h
@@ -7,8 +7,7 @@
#include "frc971/control_loops/state_feedback_loop.h"
#include "frc971/shifter_hall_effect.h"
-namespace y2016 {
-namespace constants {
+namespace y2016::constants {
using ::frc971::constants::PotAndIndexPulseZeroingConstants;
using ::frc971::constants::ShifterHallEffect;
@@ -111,7 +110,6 @@
// them.
const Values &GetValuesForTeam(uint16_t team_number);
-} // namespace constants
-} // namespace y2016
+} // namespace y2016::constants
#endif // Y2016_CONSTANTS_H_
diff --git a/y2016/control_loops/drivetrain/drivetrain_base.h b/y2016/control_loops/drivetrain/drivetrain_base.h
index 0186a6c..b0a4bda 100644
--- a/y2016/control_loops/drivetrain/drivetrain_base.h
+++ b/y2016/control_loops/drivetrain/drivetrain_base.h
@@ -3,15 +3,11 @@
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
-namespace y2016 {
-namespace control_loops {
-namespace drivetrain {
+namespace y2016::control_loops::drivetrain {
const ::frc971::control_loops::drivetrain::DrivetrainConfig<double> &
GetDrivetrainConfig();
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace y2016
+} // namespace y2016::control_loops::drivetrain
#endif // Y2016_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2016/control_loops/shooter/shooter.h b/y2016/control_loops/shooter/shooter.h
index 5aaa1c0..b83ed24 100644
--- a/y2016/control_loops/shooter/shooter.h
+++ b/y2016/control_loops/shooter/shooter.h
@@ -13,9 +13,7 @@
#include "y2016/control_loops/shooter/shooter_position_generated.h"
#include "y2016/control_loops/shooter/shooter_status_generated.h"
-namespace y2016 {
-namespace control_loops {
-namespace shooter {
+namespace y2016::control_loops::shooter {
namespace {
constexpr double kTolerance = 10.0;
@@ -94,8 +92,6 @@
DISALLOW_COPY_AND_ASSIGN(Shooter);
};
-} // namespace shooter
-} // namespace control_loops
-} // namespace y2016
+} // namespace y2016::control_loops::shooter
#endif // Y2016_CONTROL_LOOPS_SHOOTER_SHOOTER_H_
diff --git a/y2016/dashboard/dashboard.h b/y2016/dashboard/dashboard.h
index 9b6414e..5152777 100644
--- a/y2016/dashboard/dashboard.h
+++ b/y2016/dashboard/dashboard.h
@@ -21,8 +21,7 @@
#include "y2016/queues/ball_detector_generated.h"
#include "y2016/vision/vision_generated.h"
-namespace y2016 {
-namespace dashboard {
+namespace y2016::dashboard {
// Dashboard is a webserver that opens a socket and stream data from the robot
// to the client. It is divided between the DataCollector, which polls
@@ -105,7 +104,6 @@
void log(Level level, const char *message) override;
};
-} // namespace dashboard
-} // namespace y2016
+} // namespace y2016::dashboard
#endif // Y2016_DASHBOARD_DASHBOARD_H_
diff --git a/y2016/vision/blob_filters.h b/y2016/vision/blob_filters.h
index 85d2c94..e23c820 100644
--- a/y2016/vision/blob_filters.h
+++ b/y2016/vision/blob_filters.h
@@ -10,8 +10,7 @@
#include "aos/vision/math/segment.h"
#include "aos/vision/math/vector.h"
-namespace aos {
-namespace vision {
+namespace aos::vision {
struct SelectedBlob {
SelectedBlob(const RangeImage &blob_inp) : blob(blob_inp) {}
@@ -196,7 +195,6 @@
ImagePtr *image_ = NULL;
};
-} // namespace vision
-} // namespace aos
+} // namespace aos::vision
#endif // Y2016_VISION_BLOB_FILTERS_H_
diff --git a/y2016/vision/stereo_geometry.h b/y2016/vision/stereo_geometry.h
index c18abc5..e2ed92e 100644
--- a/y2016/vision/stereo_geometry.h
+++ b/y2016/vision/stereo_geometry.h
@@ -7,8 +7,7 @@
#include "aos/vision/math/vector.h"
#include "y2016/vision/calibration.pb.h"
-namespace y2016 {
-namespace vision {
+namespace y2016::vision {
// Returns the contents of the calibration file which are embedded into the
// code.
@@ -61,7 +60,6 @@
Calibration calibration_;
};
-} // namespace vision
-} // namespace y2016
+} // namespace y2016::vision
#endif // Y2016_VISION_STEREO_GEOMETRY_H_
diff --git a/y2017/actors/autonomous_actor.h b/y2017/actors/autonomous_actor.h
index f8f1734..51a5da7 100644
--- a/y2017/actors/autonomous_actor.h
+++ b/y2017/actors/autonomous_actor.h
@@ -11,8 +11,7 @@
#include "y2017/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2017/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2017 {
-namespace actors {
+namespace y2017::actors {
using ::frc971::ProfileParameters;
class AutonomousActor : public ::frc971::autonomous::BaseAutonomousActor {
@@ -169,7 +168,6 @@
}
};
-} // namespace actors
-} // namespace y2017
+} // namespace y2017::actors
#endif // Y2017_ACTORS_AUTONOMOUS_ACTOR_H_
diff --git a/y2017/constants.h b/y2017/constants.h
index 9c0f3c2..c70b0ea 100644
--- a/y2017/constants.h
+++ b/y2017/constants.h
@@ -12,8 +12,7 @@
#include "y2017/control_loops/superstructure/intake/intake_plant.h"
#include "y2017/control_loops/superstructure/shooter/shooter_plant.h"
-namespace y2017 {
-namespace constants {
+namespace y2017::constants {
// Has all of our "constants", except the ones that come from other places. The
// ones which change between robots are put together with a workable way to
@@ -143,7 +142,6 @@
// them.
const Values &GetValuesForTeam(uint16_t team_number);
-} // namespace constants
-} // namespace y2017
+} // namespace y2017::constants
#endif // Y2017_CONSTANTS_H_
diff --git a/y2017/control_loops/drivetrain/drivetrain_base.h b/y2017/control_loops/drivetrain/drivetrain_base.h
index c84934f..e0343d9 100644
--- a/y2017/control_loops/drivetrain/drivetrain_base.h
+++ b/y2017/control_loops/drivetrain/drivetrain_base.h
@@ -3,15 +3,11 @@
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
-namespace y2017 {
-namespace control_loops {
-namespace drivetrain {
+namespace y2017::control_loops::drivetrain {
const ::frc971::control_loops::drivetrain::DrivetrainConfig<double> &
GetDrivetrainConfig();
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace y2017
+} // namespace y2017::control_loops::drivetrain
#endif // Y2017_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2017/control_loops/superstructure/column/column.h b/y2017/control_loops/superstructure/column/column.h
index 615565f..f76450e 100644
--- a/y2017/control_loops/superstructure/column/column.h
+++ b/y2017/control_loops/superstructure/column/column.h
@@ -19,10 +19,7 @@
#include "y2017/control_loops/superstructure/vision_time_adjuster.h"
#include "y2017/vision/vision_generated.h"
-namespace y2017 {
-namespace control_loops {
-namespace superstructure {
-namespace column {
+namespace y2017::control_loops::superstructure::column {
class ColumnProfiledSubsystem
: public ::frc971::control_loops::ProfiledSubsystem<
@@ -208,9 +205,6 @@
const double vision_error_;
};
-} // namespace column
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2017
+} // namespace y2017::control_loops::superstructure::column
#endif // Y2017_CONTROL_LOOPS_SUPERSTRUCTURE_COLUMN_COLUMN_H_
diff --git a/y2017/control_loops/superstructure/column/column_zeroing.h b/y2017/control_loops/superstructure/column/column_zeroing.h
index c07a504..bb4fb76 100644
--- a/y2017/control_loops/superstructure/column/column_zeroing.h
+++ b/y2017/control_loops/superstructure/column/column_zeroing.h
@@ -8,10 +8,7 @@
#include "y2017/control_loops/superstructure/superstructure_position_generated.h"
#include "y2017/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2017 {
-namespace control_loops {
-namespace superstructure {
-namespace column {
+namespace y2017::control_loops::superstructure::column {
class ColumnZeroingEstimator {
public:
@@ -66,9 +63,6 @@
const double turret_zeroed_distance_;
};
-} // namespace column
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2017
+} // namespace y2017::control_loops::superstructure::column
#endif // y2017_CONTROL_LOOPS_SUPERSTRUCTURE_COLUMN_H_
diff --git a/y2017/control_loops/superstructure/hood/hood.h b/y2017/control_loops/superstructure/hood/hood.h
index 47ace6e..9f6f120 100644
--- a/y2017/control_loops/superstructure/hood/hood.h
+++ b/y2017/control_loops/superstructure/hood/hood.h
@@ -6,10 +6,7 @@
#include "y2017/constants.h"
#include "y2017/control_loops/superstructure/superstructure_goal_generated.h"
-namespace y2017 {
-namespace control_loops {
-namespace superstructure {
-namespace hood {
+namespace y2017::control_loops::superstructure::hood {
// Profiled subsystem class with significantly relaxed limits while zeroing. We
// need relaxed limits, because if you start at the top of the range, you need
@@ -75,9 +72,6 @@
::aos::monotonic_clock::min_time;
};
-} // namespace hood
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2017
+} // namespace y2017::control_loops::superstructure::hood
#endif // Y2017_CONTROL_LOOPS_SUPERSTRUCTURE_HOOD_HOOD_H_
diff --git a/y2017/control_loops/superstructure/intake/intake.h b/y2017/control_loops/superstructure/intake/intake.h
index 29899fb..f88393d 100644
--- a/y2017/control_loops/superstructure/intake/intake.h
+++ b/y2017/control_loops/superstructure/intake/intake.h
@@ -6,10 +6,7 @@
#include "y2017/constants.h"
#include "y2017/control_loops/superstructure/superstructure_goal_generated.h"
-namespace y2017 {
-namespace control_loops {
-namespace superstructure {
-namespace intake {
+namespace y2017::control_loops::superstructure::intake {
class Intake {
public:
@@ -64,9 +61,6 @@
profiled_subsystem_;
};
-} // namespace intake
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2017
+} // namespace y2017::control_loops::superstructure::intake
#endif // Y2017_CONTROL_LOOPS_SUPERSTRUCTURE_INTAKE_INTAKE_H_
diff --git a/y2017/control_loops/superstructure/shooter/shooter.h b/y2017/control_loops/superstructure/shooter/shooter.h
index 44da1dc..9cc515f 100644
--- a/y2017/control_loops/superstructure/shooter/shooter.h
+++ b/y2017/control_loops/superstructure/shooter/shooter.h
@@ -13,10 +13,7 @@
#include "y2017/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2017/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2017 {
-namespace control_loops {
-namespace superstructure {
-namespace shooter {
+namespace y2017::control_loops::superstructure::shooter {
class ShooterController {
public:
@@ -109,9 +106,6 @@
DISALLOW_COPY_AND_ASSIGN(Shooter);
};
-} // namespace shooter
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2017
+} // namespace y2017::control_loops::superstructure::shooter
#endif // Y2017_CONTROL_LOOPS_SHOOTER_SHOOTER_H_
diff --git a/y2017/control_loops/superstructure/superstructure.h b/y2017/control_loops/superstructure/superstructure.h
index c10ebbd..9403d06 100644
--- a/y2017/control_loops/superstructure/superstructure.h
+++ b/y2017/control_loops/superstructure/superstructure.h
@@ -16,9 +16,7 @@
#include "y2017/control_loops/superstructure/superstructure_status_generated.h"
#include "y2017/control_loops/superstructure/vision_distance_average.h"
-namespace y2017 {
-namespace control_loops {
-namespace superstructure {
+namespace y2017::control_loops::superstructure {
class Superstructure
: public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
@@ -63,8 +61,6 @@
DISALLOW_COPY_AND_ASSIGN(Superstructure);
};
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2017
+} // namespace y2017::control_loops::superstructure
#endif // Y2017_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
diff --git a/y2017/control_loops/superstructure/vision_distance_average.h b/y2017/control_loops/superstructure/vision_distance_average.h
index 5f81586..6d1bdb6 100644
--- a/y2017/control_loops/superstructure/vision_distance_average.h
+++ b/y2017/control_loops/superstructure/vision_distance_average.h
@@ -8,9 +8,7 @@
#include "aos/time/time.h"
#include "y2017/vision/vision_generated.h"
-namespace y2017 {
-namespace control_loops {
-namespace superstructure {
+namespace y2017::control_loops::superstructure {
namespace chrono = ::std::chrono;
@@ -61,8 +59,6 @@
::aos::RingBuffer<DistanceEvent, 25> data_;
};
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2017
+} // namespace y2017::control_loops::superstructure
#endif // Y2017_CONTROL_LOOPS_SUPERSTRUCTURE_VISION_DISTANCE_AVERAGE_H_
diff --git a/y2017/control_loops/superstructure/vision_time_adjuster.h b/y2017/control_loops/superstructure/vision_time_adjuster.h
index 45dd8bb..b38876f 100644
--- a/y2017/control_loops/superstructure/vision_time_adjuster.h
+++ b/y2017/control_loops/superstructure/vision_time_adjuster.h
@@ -9,9 +9,7 @@
#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
#include "y2017/vision/vision_generated.h"
-namespace y2017 {
-namespace control_loops {
-namespace superstructure {
+namespace y2017::control_loops::superstructure {
class VisionTimeAdjuster {
public:
@@ -74,8 +72,6 @@
bool valid_ = false;
};
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2017
+} // namespace y2017::control_loops::superstructure
#endif // Y2017_CONTROL_LOOPS_SUPERSTRUCTURE_VISION_TIME_ADJUSTER_H_
diff --git a/y2017/vision/target_finder.h b/y2017/vision/target_finder.h
index 34fd90d..5c89a6d 100644
--- a/y2017/vision/target_finder.h
+++ b/y2017/vision/target_finder.h
@@ -11,8 +11,7 @@
using aos::vision::RangeImage;
using aos::vision::Vector;
-namespace y2017 {
-namespace vision {
+namespace y2017::vision {
// This polynomial exists in transpose space.
struct TargetComponent {
@@ -84,7 +83,6 @@
aos::vision::PixelLinesOverlay overlay_;
};
-} // namespace vision
-} // namespace y2017
+} // namespace y2017::vision
#endif // _Y2017_VISION_TARGET_FINDER_H_
diff --git a/y2018/actors/autonomous_actor.h b/y2018/actors/autonomous_actor.h
index 88eb126..a9c629c 100644
--- a/y2018/actors/autonomous_actor.h
+++ b/y2018/actors/autonomous_actor.h
@@ -14,8 +14,7 @@
#include "y2018/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2018/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2018 {
-namespace actors {
+namespace y2018::actors {
class AutonomousActor : public ::frc971::autonomous::BaseAutonomousActor {
public:
@@ -226,7 +225,6 @@
}
};
-} // namespace actors
-} // namespace y2018
+} // namespace y2018::actors
#endif // Y2018_ACTORS_AUTONOMOUS_ACTOR_H_
diff --git a/y2018/constants.h b/y2018/constants.h
index 8bc5fbc..c0f0d7d 100644
--- a/y2018/constants.h
+++ b/y2018/constants.h
@@ -10,8 +10,7 @@
#include "y2018/control_loops/superstructure/arm/arm_constants.h"
#include "y2018/control_loops/superstructure/intake/intake_plant.h"
-namespace y2018 {
-namespace constants {
+namespace y2018::constants {
// Has all of our "constants", except the ones that come from other places. The
// ones which change between robots are put together with a workable way to
@@ -122,7 +121,6 @@
// them.
const Values &GetValuesForTeam(uint16_t team_number);
-} // namespace constants
-} // namespace y2018
+} // namespace y2018::constants
#endif // Y2018_CONSTANTS_H_
diff --git a/y2018/control_loops/drivetrain/drivetrain_base.h b/y2018/control_loops/drivetrain/drivetrain_base.h
index 0592a25..85e60e7 100644
--- a/y2018/control_loops/drivetrain/drivetrain_base.h
+++ b/y2018/control_loops/drivetrain/drivetrain_base.h
@@ -3,15 +3,11 @@
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
-namespace y2018 {
-namespace control_loops {
-namespace drivetrain {
+namespace y2018::control_loops::drivetrain {
const ::frc971::control_loops::drivetrain::DrivetrainConfig<double> &
GetDrivetrainConfig();
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace y2018
+} // namespace y2018::control_loops::drivetrain
#endif // Y2018_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2018/control_loops/python/arm_bounds.h b/y2018/control_loops/python/arm_bounds.h
index c175616..f9645d5 100644
--- a/y2018/control_loops/python/arm_bounds.h
+++ b/y2018/control_loops/python/arm_bounds.h
@@ -13,8 +13,7 @@
// Prototype level code to find the nearest point and distance to a polygon.
-namespace y2018 {
-namespace control_loops {
+namespace y2018::control_loops {
typedef CGAL::Exact_predicates_inexact_constructions_kernel K;
typedef K::Point_2 Point;
@@ -239,7 +238,6 @@
BoundsCheck MakeClippedArmSpace();
BoundsCheck MakeFullArmSpace();
-} // namespace control_loops
-} // namespace y2018
+} // namespace y2018::control_loops
#endif // Y2018_CONTORL_LOOPS_PYTHON_ARM_BOUNDS_H_
diff --git a/y2018/control_loops/superstructure/arm/BUILD b/y2018/control_loops/superstructure/arm/BUILD
index ec18f9d..319e591 100644
--- a/y2018/control_loops/superstructure/arm/BUILD
+++ b/y2018/control_loops/superstructure/arm/BUILD
@@ -73,7 +73,7 @@
deps = [
":arm_constants",
":generated_graph",
- "//frc971/analysis:in_process_plotter",
+ "//aos/analysis:in_process_plotter",
"//frc971/control_loops/double_jointed_arm:ekf",
"//frc971/control_loops/double_jointed_arm:trajectory",
"@com_github_gflags_gflags//:gflags",
diff --git a/y2018/control_loops/superstructure/arm/arm.h b/y2018/control_loops/superstructure/arm/arm.h
index a9cf614..095ef1d 100644
--- a/y2018/control_loops/superstructure/arm/arm.h
+++ b/y2018/control_loops/superstructure/arm/arm.h
@@ -16,10 +16,7 @@
using frc971::control_loops::arm::EKF;
using frc971::control_loops::arm::TrajectoryFollower;
-namespace y2018 {
-namespace control_loops {
-namespace superstructure {
-namespace arm {
+namespace y2018::control_loops::superstructure::arm {
class Arm {
public:
@@ -141,9 +138,6 @@
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
};
-} // namespace arm
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2018
+} // namespace y2018::control_loops::superstructure::arm
#endif // Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_ARM_H_
diff --git a/y2018/control_loops/superstructure/arm/arm_constants.h b/y2018/control_loops/superstructure/arm/arm_constants.h
index 932da7a..12c1584 100644
--- a/y2018/control_loops/superstructure/arm/arm_constants.h
+++ b/y2018/control_loops/superstructure/arm/arm_constants.h
@@ -3,10 +3,7 @@
#include "frc971/control_loops/double_jointed_arm/dynamics.h"
-namespace y2018 {
-namespace control_loops {
-namespace superstructure {
-namespace arm {
+namespace y2018::control_loops::superstructure::arm {
constexpr double kEfficiencyTweak = 0.95;
constexpr double kStallTorque = 1.41 * kEfficiencyTweak;
@@ -44,9 +41,6 @@
.num_distal_motors = 2.0,
};
-} // namespace arm
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2018
+} // namespace y2018::control_loops::superstructure::arm
#endif // Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_ARM_CONSTANTS_H_
diff --git a/y2018/control_loops/superstructure/arm/trajectory_plot.cc b/y2018/control_loops/superstructure/arm/trajectory_plot.cc
index 6739b07..eeb0fbc 100644
--- a/y2018/control_loops/superstructure/arm/trajectory_plot.cc
+++ b/y2018/control_loops/superstructure/arm/trajectory_plot.cc
@@ -1,7 +1,7 @@
#include "gflags/gflags.h"
+#include "aos/analysis/in_process_plotter.h"
#include "aos/init.h"
-#include "frc971/analysis/in_process_plotter.h"
#include "frc971/control_loops/double_jointed_arm/dynamics.h"
#include "frc971/control_loops/double_jointed_arm/ekf.h"
#include "frc971/control_loops/double_jointed_arm/trajectory.h"
@@ -255,7 +255,7 @@
}
if (FLAGS_plot) {
- frc971::analysis::Plotter plotter;
+ aos::analysis::Plotter plotter;
plotter.AddFigure();
plotter.Title("Trajectory");
diff --git a/y2018/control_loops/superstructure/intake/intake.h b/y2018/control_loops/superstructure/intake/intake.h
index bec5ff6..3b5c840 100644
--- a/y2018/control_loops/superstructure/intake/intake.h
+++ b/y2018/control_loops/superstructure/intake/intake.h
@@ -15,10 +15,7 @@
#include "y2018/control_loops/superstructure/superstructure_position_generated.h"
#include "y2018/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2018 {
-namespace control_loops {
-namespace superstructure {
-namespace intake {
+namespace y2018::control_loops::superstructure::intake {
class IntakeController {
public:
@@ -130,9 +127,6 @@
double intake_last_position_ = 0.0;
};
-} // namespace intake
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2018
+} // namespace y2018::control_loops::superstructure::intake
#endif // Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_INTAKE_INTAKE_H_
diff --git a/y2018/control_loops/superstructure/superstructure.h b/y2018/control_loops/superstructure/superstructure.h
index 6621794..6abefa4 100644
--- a/y2018/control_loops/superstructure/superstructure.h
+++ b/y2018/control_loops/superstructure/superstructure.h
@@ -17,9 +17,7 @@
#include "y2018/status_light_generated.h"
#include "y2018/vision/vision_generated.h"
-namespace y2018 {
-namespace control_loops {
-namespace superstructure {
+namespace y2018::control_loops::superstructure {
class Superstructure
: public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
@@ -75,8 +73,6 @@
DISALLOW_COPY_AND_ASSIGN(Superstructure);
};
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2018
+} // namespace y2018::control_loops::superstructure
#endif // Y2018_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
diff --git a/y2019/actors/auto_splines.h b/y2019/actors/auto_splines.h
index 7b56c11..4d6fbc1 100644
--- a/y2019/actors/auto_splines.h
+++ b/y2019/actors/auto_splines.h
@@ -11,8 +11,7 @@
*/
-namespace y2019 {
-namespace actors {
+namespace y2019::actors {
class AutonomousSplines {
public:
@@ -88,7 +87,6 @@
*builder);
};
-} // namespace actors
-} // namespace y2019
+} // namespace y2019::actors
#endif // Y2019_ACTORS_AUTO_SPLINES_H_
diff --git a/y2019/actors/autonomous_actor.h b/y2019/actors/autonomous_actor.h
index 5b21195..9ba59fa 100644
--- a/y2019/actors/autonomous_actor.h
+++ b/y2019/actors/autonomous_actor.h
@@ -13,8 +13,7 @@
#include "y2019/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2019/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2019 {
-namespace actors {
+namespace y2019::actors {
using ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
@@ -250,7 +249,6 @@
superstructure_status_fetcher_;
};
-} // namespace actors
-} // namespace y2019
+} // namespace y2019::actors
#endif // Y2019_ACTORS_AUTONOMOUS_ACTOR_H_
diff --git a/y2019/constants.h b/y2019/constants.h
index a36e4b3..0555d4e 100644
--- a/y2019/constants.h
+++ b/y2019/constants.h
@@ -17,8 +17,7 @@
#include "y2019/control_loops/superstructure/stilts/stilts_plant.h"
#include "y2019/control_loops/superstructure/wrist/wrist_plant.h"
-namespace y2019 {
-namespace constants {
+namespace y2019::constants {
// Has all of our "constants", except the ones that come from other places. The
// ones which change between robots are put together with a workable way to
@@ -215,7 +214,6 @@
// them.
const Values &GetValuesForTeam(uint16_t team_number);
-} // namespace constants
-} // namespace y2019
+} // namespace y2019::constants
#endif // Y2019_CONSTANTS_H_
diff --git a/y2019/control_loops/drivetrain/drivetrain_base.h b/y2019/control_loops/drivetrain/drivetrain_base.h
index 3a8bd6b..80aa1a8 100644
--- a/y2019/control_loops/drivetrain/drivetrain_base.h
+++ b/y2019/control_loops/drivetrain/drivetrain_base.h
@@ -3,15 +3,11 @@
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
-namespace y2019 {
-namespace control_loops {
-namespace drivetrain {
+namespace y2019::control_loops::drivetrain {
const ::frc971::control_loops::drivetrain::DrivetrainConfig<double> &
GetDrivetrainConfig();
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace y2019
+} // namespace y2019::control_loops::drivetrain
#endif // Y2019_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2019/control_loops/drivetrain/event_loop_localizer.h b/y2019/control_loops/drivetrain/event_loop_localizer.h
index 0847479..61caf87 100644
--- a/y2019/control_loops/drivetrain/event_loop_localizer.h
+++ b/y2019/control_loops/drivetrain/event_loop_localizer.h
@@ -7,9 +7,7 @@
#include "y2019/control_loops/drivetrain/localizer.h"
#include "y2019/control_loops/drivetrain/target_selector.h"
-namespace y2019 {
-namespace control_loops {
-namespace drivetrain {
+namespace y2019::control_loops::drivetrain {
// Wrap the localizer to allow it to fetch camera frames from the queues.
// TODO(james): Provide a way of resetting the current position and
@@ -89,7 +87,5 @@
::std::array<EventLoopLocalizer::Camera, constants::Values::kNumCameras>
MakeCameras(EventLoopLocalizer::Pose *pose);
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace y2019
+} // namespace y2019::control_loops::drivetrain
#endif // Y2019_CONTROL_LOOPS_DRIVETRAIN_EVENT_LOOP_LOCALIZER_H_
diff --git a/y2019/control_loops/drivetrain/localizer.h b/y2019/control_loops/drivetrain/localizer.h
index 2e7c3a5..f4c7a8a 100644
--- a/y2019/control_loops/drivetrain/localizer.h
+++ b/y2019/control_loops/drivetrain/localizer.h
@@ -17,8 +17,7 @@
#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
#endif
-namespace y2019 {
-namespace control_loops {
+namespace y2019::control_loops {
template <int num_cameras, int num_targets, int num_obstacles,
int max_targets_per_frame, typename Scalar = double>
@@ -576,7 +575,6 @@
#pragma GCC diagnostic pop
#endif
-} // namespace control_loops
-} // namespace y2019
+} // namespace y2019::control_loops
#endif // Y2019_CONTROL_LOOPS_DRIVETRAIN_LOCALIZATER_H_
diff --git a/y2019/control_loops/drivetrain/target_selector.h b/y2019/control_loops/drivetrain/target_selector.h
index b8d89c7..ba6d970 100644
--- a/y2019/control_loops/drivetrain/target_selector.h
+++ b/y2019/control_loops/drivetrain/target_selector.h
@@ -8,8 +8,7 @@
#include "y2019/control_loops/drivetrain/target_selector_generated.h"
#include "y2019/control_loops/superstructure/superstructure_goal_generated.h"
-namespace y2019 {
-namespace control_loops {
+namespace y2019::control_loops {
// A class to identify which target the driver is currently driving towards so
// that we can guide them into the target.
@@ -75,7 +74,6 @@
drivetrain::SelectionHint target_hint_ = drivetrain::SelectionHint::NONE;
};
-} // namespace control_loops
-} // namespace y2019
+} // namespace y2019::control_loops
#endif // Y2019_CONTROL_LOOPS_DRIVETRAIN_TARGET_SELECTOR_H_
diff --git a/y2019/control_loops/superstructure/collision_avoidance.h b/y2019/control_loops/superstructure/collision_avoidance.h
index ac88cec..e872e8c 100644
--- a/y2019/control_loops/superstructure/collision_avoidance.h
+++ b/y2019/control_loops/superstructure/collision_avoidance.h
@@ -9,9 +9,7 @@
#include "y2019/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2019/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2019 {
-namespace control_loops {
-namespace superstructure {
+namespace y2019::control_loops::superstructure {
// CollisionAvoidance computes the min and max allowable ranges for various
// subsystems to avoid collisions. It also shoves the elevator up to let the
@@ -108,8 +106,6 @@
double max_intake_goal_;
};
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2019
+} // namespace y2019::control_loops::superstructure
#endif // Y2019_CONTROL_LOOPS_SUPERSTRUCTURE_COLLISION_AVOIDANCE_H_
diff --git a/y2019/control_loops/superstructure/superstructure.h b/y2019/control_loops/superstructure/superstructure.h
index 4d59132..ab80eb4 100644
--- a/y2019/control_loops/superstructure/superstructure.h
+++ b/y2019/control_loops/superstructure/superstructure.h
@@ -16,9 +16,7 @@
#include "y2019/control_loops/superstructure/vacuum.h"
#include "y2019/status_light_generated.h"
-namespace y2019 {
-namespace control_loops {
-namespace superstructure {
+namespace y2019::control_loops::superstructure {
class Superstructure
: public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
@@ -68,8 +66,6 @@
DISALLOW_COPY_AND_ASSIGN(Superstructure);
};
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2019
+} // namespace y2019::control_loops::superstructure
#endif // Y2019_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
diff --git a/y2019/control_loops/superstructure/vacuum.h b/y2019/control_loops/superstructure/vacuum.h
index c4671ab..58ad109 100644
--- a/y2019/control_loops/superstructure/vacuum.h
+++ b/y2019/control_loops/superstructure/vacuum.h
@@ -7,9 +7,7 @@
#include "y2019/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2019/control_loops/superstructure/superstructure_output_generated.h"
-namespace y2019 {
-namespace control_loops {
-namespace superstructure {
+namespace y2019::control_loops::superstructure {
class Vacuum {
public:
@@ -55,8 +53,6 @@
DISALLOW_COPY_AND_ASSIGN(Vacuum);
};
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2019
+} // namespace y2019::control_loops::superstructure
#endif // Y2019_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
diff --git a/y2019/jevois/camera/image_stream.h b/y2019/jevois/camera/image_stream.h
index f1ab0af..5b29070 100644
--- a/y2019/jevois/camera/image_stream.h
+++ b/y2019/jevois/camera/image_stream.h
@@ -7,8 +7,7 @@
#include "aos/vision/image/camera_params.pb.h"
#include "y2019/jevois/camera/reader.h"
-namespace y2019 {
-namespace camera {
+namespace y2019::camera {
// Converts a camera reader into a virtual base class that calls ProcessImage
// on each new image.
@@ -48,7 +47,6 @@
std::unique_ptr<Reader> reader_;
};
-} // namespace camera
-} // namespace y2019
+} // namespace y2019::camera
#endif // Y2019_JEVOIS_CAMERA_IMAGE_STREAM_H_
diff --git a/y2019/jevois/camera/reader.h b/y2019/jevois/camera/reader.h
index ef4f34d..77f0799 100644
--- a/y2019/jevois/camera/reader.h
+++ b/y2019/jevois/camera/reader.h
@@ -10,8 +10,7 @@
#include "aos/vision/image/camera_params.pb.h"
#include "aos/vision/image/image_types.h"
-namespace y2019 {
-namespace camera {
+namespace y2019::camera {
aos::vision::CameraParams MakeCameraParams(int32_t width, int32_t height,
int32_t exposure, int32_t brightness,
@@ -65,7 +64,6 @@
aos::vision::CameraParams params_;
};
-} // namespace camera
-} // namespace y2019
+} // namespace y2019::camera
#endif // AOS_VISION_IMAGE_READER_H_
diff --git a/y2019/jevois/cobs.h b/y2019/jevois/cobs.h
index c429622..271a41f 100644
--- a/y2019/jevois/cobs.h
+++ b/y2019/jevois/cobs.h
@@ -11,8 +11,7 @@
// Stuffing data. <http://www.stuartcheshire.org/papers/cobsforton.pdf> has
// details on what this entails and why it's a good idea.
-namespace frc971 {
-namespace jevois {
+namespace frc971::jevois {
constexpr size_t CobsMaxEncodedSize(size_t decoded_size) {
return decoded_size + ((decoded_size + 253) / 254);
@@ -213,7 +212,6 @@
}
}
-} // namespace jevois
-} // namespace frc971
+} // namespace frc971::jevois
#endif // Y2019_JEVOIS_COBS_H_
diff --git a/y2019/jevois/spi.h b/y2019/jevois/spi.h
index 62e5ea7..fd999de 100644
--- a/y2019/jevois/spi.h
+++ b/y2019/jevois/spi.h
@@ -14,8 +14,7 @@
//
// Our SPI transfers are fixed-size to simplify everything.
-namespace frc971 {
-namespace jevois {
+namespace frc971::jevois {
constexpr size_t spi_transfer_size() {
// The teensy->RoboRIO side is way bigger, so just calculate that.
@@ -33,7 +32,6 @@
std::optional<RoborioToTeensy> SpiUnpackToTeensy(
absl::Span<const char> transfer);
-} // namespace jevois
-} // namespace frc971
+} // namespace frc971::jevois
#endif // Y2019_JEVOIS_SPI_H_
diff --git a/y2019/jevois/structures.h b/y2019/jevois/structures.h
index 85cca21..a8d2843 100644
--- a/y2019/jevois/structures.h
+++ b/y2019/jevois/structures.h
@@ -11,8 +11,7 @@
#include "aos/containers/sized_array.h"
#include "aos/time/time.h"
-namespace frc971 {
-namespace jevois {
+namespace frc971::jevois {
// The overall flow to get data to the roboRIO consists of:
// 1. Camera captures a frame and grabs an absolute timestamp.
@@ -233,7 +232,6 @@
CameraCommand camera_command;
};
-} // namespace jevois
-} // namespace frc971
+} // namespace frc971::jevois
#endif // Y2019_JEVOIS_STRUCTURES_H_
diff --git a/y2019/jevois/uart.h b/y2019/jevois/uart.h
index d3eebee..7bacbd1 100644
--- a/y2019/jevois/uart.h
+++ b/y2019/jevois/uart.h
@@ -12,8 +12,7 @@
// This file manages serializing and deserializing the various structures for
// transport via UART.
-namespace frc971 {
-namespace jevois {
+namespace frc971::jevois {
constexpr size_t uart_to_teensy_size() {
return 1 /* number of targets */ +
@@ -38,7 +37,6 @@
std::optional<CameraCalibration> UartUnpackToCamera(
absl::Span<const char> buffer);
-} // namespace jevois
-} // namespace frc971
+} // namespace frc971::jevois
#endif // Y2019_JEVOIS_UART_H_
diff --git a/y2019/joystick_angle.h b/y2019/joystick_angle.h
index dfd8bb9..2dad968 100644
--- a/y2019/joystick_angle.h
+++ b/y2019/joystick_angle.h
@@ -6,9 +6,7 @@
using ::frc971::input::driver_station::Data;
using ::frc971::input::driver_station::JoystickAxis;
-namespace y2019 {
-namespace input {
-namespace joysticks {
+namespace y2019::input::joysticks {
bool AngleCloseTo(double angle, double near, double range);
enum class JoystickAngle {
@@ -25,8 +23,6 @@
const JoystickAxis &y_axis, const Data &data);
JoystickAngle GetJoystickPosition(float x_axis, float y_axis);
-} // namespace joysticks
-} // namespace input
-} // namespace y2019
+} // namespace y2019::input::joysticks
#endif // Y2019_JOYSTICK_ANGLE_H_
diff --git a/y2019/vision/constants.h b/y2019/vision/constants.h
index 959f5b7..7078d6b 100644
--- a/y2019/vision/constants.h
+++ b/y2019/vision/constants.h
@@ -6,8 +6,7 @@
#include <cstdint>
#include <string>
-namespace y2019 {
-namespace vision {
+namespace y2019::vision {
// Position of the idealized camera in 3d space.
struct CameraGeometry {
@@ -107,7 +106,6 @@
void DumpCameraConstants(const char *fname, int camera_id,
const CameraCalibration &value);
-} // namespace vision
-} // namespace y2019
+} // namespace y2019::vision
#endif // _Y2019_VISION_CONSTANTS_H_
diff --git a/y2019/vision/image_writer.h b/y2019/vision/image_writer.h
index 1192368..27dcb4a 100644
--- a/y2019/vision/image_writer.h
+++ b/y2019/vision/image_writer.h
@@ -5,8 +5,7 @@
#include "aos/vision/image/image_types.h"
-namespace y2019 {
-namespace vision {
+namespace y2019::vision {
class ImageWriter {
public:
@@ -23,7 +22,6 @@
unsigned int image_count_ = 0;
};
-} // namespace vision
-} // namespace y2019
+} // namespace y2019::vision
#endif // Y2019_VISION_IMAGE_WRITER_H_
diff --git a/y2019/vision/target_finder.h b/y2019/vision/target_finder.h
index fdcfbde..20bf87a 100644
--- a/y2019/vision/target_finder.h
+++ b/y2019/vision/target_finder.h
@@ -16,8 +16,7 @@
class Context;
} // namespace ceres
-namespace y2019 {
-namespace vision {
+namespace y2019::vision {
using aos::vision::BlobList;
using aos::vision::ContourNode;
@@ -115,7 +114,6 @@
int current_exposure_ = 0;
};
-} // namespace vision
-} // namespace y2019
+} // namespace y2019::vision
#endif
diff --git a/y2019/vision/target_types.h b/y2019/vision/target_types.h
index 5019646..fb57b71 100644
--- a/y2019/vision/target_types.h
+++ b/y2019/vision/target_types.h
@@ -7,8 +7,7 @@
#include "aos/vision/math/vector.h"
#include "y2019/vision/constants.h"
-namespace y2019 {
-namespace vision {
+namespace y2019::vision {
// This polynomial exists in transpose space.
struct TargetComponent {
@@ -239,7 +238,6 @@
240.0 - res.y() * scale);
}
-} // namespace vision
-} // namespace y2019
+} // namespace y2019::vision
#endif
diff --git a/y2020/actors/auto_splines.h b/y2020/actors/auto_splines.h
index e7bef0a..396fe4b 100644
--- a/y2020/actors/auto_splines.h
+++ b/y2020/actors/auto_splines.h
@@ -13,8 +13,7 @@
*/
-namespace y2020 {
-namespace actors {
+namespace y2020::actors {
class AutonomousSplines {
public:
@@ -89,7 +88,6 @@
aos::FlatbufferDetachedBuffer<frc971::MultiSpline> far_side_fender_;
};
-} // namespace actors
-} // namespace y2020
+} // namespace y2020::actors
#endif // y2020_ACTORS_AUTO_SPLINES_H_
diff --git a/y2020/actors/autonomous_actor.h b/y2020/actors/autonomous_actor.h
index abf9ea0..9368a8e 100644
--- a/y2020/actors/autonomous_actor.h
+++ b/y2020/actors/autonomous_actor.h
@@ -11,8 +11,7 @@
#include "y2020/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2020/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2020 {
-namespace actors {
+namespace y2020::actors {
using frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
@@ -104,7 +103,6 @@
std::optional<Eigen::Vector3d> starting_position_;
};
-} // namespace actors
-} // namespace y2020
+} // namespace y2020::actors
#endif // y2020_ACTORS_AUTONOMOUS_ACTOR_H_
diff --git a/y2020/constants.h b/y2020/constants.h
index 7332b4f..efae264 100644
--- a/y2020/constants.h
+++ b/y2020/constants.h
@@ -21,8 +21,7 @@
using ::frc971::shooter_interpolation::InterpolationTable;
-namespace y2020 {
-namespace constants {
+namespace y2020::constants {
struct Values {
static const uint16_t kCompTeamNumber = 971;
@@ -241,7 +240,6 @@
// InitValues() before calling this.
const Values &GetValues();
-} // namespace constants
-} // namespace y2020
+} // namespace y2020::constants
#endif // y2020_CONSTANTS_H_
diff --git a/y2020/control_loops/drivetrain/drivetrain_base.h b/y2020/control_loops/drivetrain/drivetrain_base.h
index e35c2af..321e7cc 100644
--- a/y2020/control_loops/drivetrain/drivetrain_base.h
+++ b/y2020/control_loops/drivetrain/drivetrain_base.h
@@ -3,15 +3,11 @@
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
-namespace y2020 {
-namespace control_loops {
-namespace drivetrain {
+namespace y2020::control_loops::drivetrain {
const ::frc971::control_loops::drivetrain::DrivetrainConfig<double> &
GetDrivetrainConfig();
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace y2020
+} // namespace y2020::control_loops::drivetrain
#endif // y2020_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2020/control_loops/drivetrain/localizer.h b/y2020/control_loops/drivetrain/localizer.h
index de57091..bc12fd6 100644
--- a/y2020/control_loops/drivetrain/localizer.h
+++ b/y2020/control_loops/drivetrain/localizer.h
@@ -13,9 +13,7 @@
#include "y2020/control_loops/superstructure/superstructure_status_generated.h"
#include "y2020/vision/sift/sift_generated.h"
-namespace y2020 {
-namespace control_loops {
-namespace drivetrain {
+namespace y2020::control_loops::drivetrain {
// This class handles the localization for the 2020 robot. In order to handle
// camera updates, we get the ImageMatchResult message from the cameras and then
@@ -164,8 +162,6 @@
Statistics statistics_;
};
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace y2020
+} // namespace y2020::control_loops::drivetrain
#endif // Y2020_CONTROL_LOOPS_DRIVETRAIN_LOCALIZER_H_
diff --git a/y2020/control_loops/superstructure/shooter/shooter.h b/y2020/control_loops/superstructure/shooter/shooter.h
index a1d7be3..3280c69 100644
--- a/y2020/control_loops/superstructure/shooter/shooter.h
+++ b/y2020/control_loops/superstructure/shooter/shooter.h
@@ -9,10 +9,7 @@
#include "y2020/control_loops/superstructure/superstructure_position_generated.h"
#include "y2020/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2020 {
-namespace control_loops {
-namespace superstructure {
-namespace shooter {
+namespace y2020::control_loops::superstructure::shooter {
// Handles all flywheels together.
class Shooter {
@@ -60,9 +57,6 @@
DISALLOW_COPY_AND_ASSIGN(Shooter);
};
-} // namespace shooter
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2020
+} // namespace y2020::control_loops::superstructure::shooter
#endif // Y2020_CONTROL_LOOPS_SHOOTER_SHOOTER_H_
diff --git a/y2020/control_loops/superstructure/superstructure.h b/y2020/control_loops/superstructure/superstructure.h
index 8a00bf0..ff38770 100644
--- a/y2020/control_loops/superstructure/superstructure.h
+++ b/y2020/control_loops/superstructure/superstructure.h
@@ -17,9 +17,7 @@
#include "y2020/control_loops/superstructure/superstructure_status_generated.h"
#include "y2020/control_loops/superstructure/turret/aiming.h"
-namespace y2020 {
-namespace control_loops {
-namespace superstructure {
+namespace y2020::control_loops::superstructure {
class Superstructure
: public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
@@ -88,8 +86,6 @@
DISALLOW_COPY_AND_ASSIGN(Superstructure);
};
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2020
+} // namespace y2020::control_loops::superstructure
#endif // y2020_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
diff --git a/y2020/control_loops/superstructure/turret/aiming.h b/y2020/control_loops/superstructure/turret/aiming.h
index 45f690f..98ebb2f 100644
--- a/y2020/control_loops/superstructure/turret/aiming.h
+++ b/y2020/control_loops/superstructure/turret/aiming.h
@@ -9,10 +9,7 @@
#include "frc971/input/joystick_state_generated.h"
#include "y2020/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2020 {
-namespace control_loops {
-namespace superstructure {
-namespace turret {
+namespace y2020::control_loops::superstructure::turret {
// Returns the port that we want to score on given our current alliance. The yaw
// of the port will be such that the positive x axis points out the back of the
@@ -68,8 +65,5 @@
Eigen::Matrix<double, 2, 2> Tlr_to_la_;
};
-} // namespace turret
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2020
+} // namespace y2020::control_loops::superstructure::turret
#endif // y2020_CONTROL_LOOPS_SUPERSTRUCTURE_TURRET_AIMING_H_
diff --git a/y2020/vision/camera_reader.h b/y2020/vision/camera_reader.h
index 9a8cf6f..81dfa1a 100644
--- a/y2020/vision/camera_reader.h
+++ b/y2020/vision/camera_reader.h
@@ -17,8 +17,7 @@
#include "y2020/vision/sift/sift_training_generated.h"
#include "y2020/vision/tools/python_code/sift_training_data.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
class CameraReader {
public:
@@ -170,6 +169,5 @@
new frc971::vision::SIFT971_Impl()};
};
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // Y2020_VISION_CAMERA_READER_H_
diff --git a/y2020/vision/sift/fast_gaussian.h b/y2020/vision/sift/fast_gaussian.h
index f243e53..d9a5f07 100644
--- a/y2020/vision/sift/fast_gaussian.h
+++ b/y2020/vision/sift/fast_gaussian.h
@@ -8,8 +8,7 @@
#include "HalideBuffer.h"
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
// Returns a Halide buffer representing the data in mat.
template <typename T>
@@ -39,7 +38,6 @@
void FastGaussianAndSubtract(const cv::Mat &source, cv::Mat *blurred,
cv::Mat *difference, double sigma);
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // Y2020_VISION_SIFT_FAST_GAUSSIAN_H_
diff --git a/y2020/vision/sift/get_gaussian_kernel.h b/y2020/vision/sift/get_gaussian_kernel.h
index c13c588..9252e24 100644
--- a/y2020/vision/sift/get_gaussian_kernel.h
+++ b/y2020/vision/sift/get_gaussian_kernel.h
@@ -4,8 +4,7 @@
#include <cmath>
#include <vector>
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
// A reimplementation of cv::getGaussianKernel for CV_32F without external
// dependencies. See fast_gaussian_halide_generator.sh for details why we want
@@ -24,7 +23,6 @@
return result;
}
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // Y2020_VISION_SIFT_GET_GAUSSIAN_KERNEL_H_
diff --git a/y2020/vision/sift/sift971.h b/y2020/vision/sift/sift971.h
index b351d70..a235afb 100644
--- a/y2020/vision/sift/sift971.h
+++ b/y2020/vision/sift/sift971.h
@@ -6,8 +6,7 @@
#include <opencv2/core/types.hpp>
#include <opencv2/features2d.hpp>
-namespace frc971 {
-namespace vision {
+namespace frc971::vision {
/*!
SIFT implementation.
@@ -66,7 +65,6 @@
bool use_fast_pyramid_difference_ = true;
};
-} // namespace vision
-} // namespace frc971
+} // namespace frc971::vision
#endif // Y2020_VISION_SIFT_SIFT971_H_
diff --git a/y2021_bot3/actors/auto_splines.h b/y2021_bot3/actors/auto_splines.h
index 9984c15..9225a49 100644
--- a/y2021_bot3/actors/auto_splines.h
+++ b/y2021_bot3/actors/auto_splines.h
@@ -11,8 +11,7 @@
*/
-namespace y2021_bot3 {
-namespace actors {
+namespace y2021_bot3::actors {
class AutonomousSplines {
public:
@@ -22,7 +21,6 @@
aos::Sender<frc971::control_loops::drivetrain::Goal>::Builder *builder);
};
-} // namespace actors
-} // namespace y2021_bot3
+} // namespace y2021_bot3::actors
#endif // Y2021_BOT3_ACTORS_AUTO_SPLINES_H_
diff --git a/y2021_bot3/actors/autonomous_actor.h b/y2021_bot3/actors/autonomous_actor.h
index 5fa509b..bcf58ee 100644
--- a/y2021_bot3/actors/autonomous_actor.h
+++ b/y2021_bot3/actors/autonomous_actor.h
@@ -7,8 +7,7 @@
#include "frc971/control_loops/control_loops_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
-namespace y2021_bot3 {
-namespace actors {
+namespace y2021_bot3::actors {
class AutonomousActor : public ::frc971::autonomous::BaseAutonomousActor {
public:
@@ -21,7 +20,6 @@
void Reset();
};
-} // namespace actors
-} // namespace y2021_bot3
+} // namespace y2021_bot3::actors
#endif // Y2021_BOT3_ACTORS_AUTONOMOUS_ACTOR_H_
diff --git a/y2021_bot3/constants.h b/y2021_bot3/constants.h
index f0cbacb..a6d7957 100644
--- a/y2021_bot3/constants.h
+++ b/y2021_bot3/constants.h
@@ -10,8 +10,7 @@
#include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h"
#include "y2021_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
-namespace y2021_bot3 {
-namespace constants {
+namespace y2021_bot3::constants {
struct Values {
static const int kZeroingSampleSize = 200;
@@ -42,7 +41,6 @@
// them.
const Values &GetValuesForTeam(uint16_t team_number);
-} // namespace constants
-} // namespace y2021_bot3
+} // namespace y2021_bot3::constants
#endif // Y2021_BOT3_CONSTANTS_H_
diff --git a/y2021_bot3/control_loops/drivetrain/drivetrain_base.h b/y2021_bot3/control_loops/drivetrain/drivetrain_base.h
index f796d4e..c9a06c6 100644
--- a/y2021_bot3/control_loops/drivetrain/drivetrain_base.h
+++ b/y2021_bot3/control_loops/drivetrain/drivetrain_base.h
@@ -3,15 +3,11 @@
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
-namespace y2021_bot3 {
-namespace control_loops {
-namespace drivetrain {
+namespace y2021_bot3::control_loops::drivetrain {
const ::frc971::control_loops::drivetrain::DrivetrainConfig<double> &
GetDrivetrainConfig();
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace y2021_bot3
+} // namespace y2021_bot3::control_loops::drivetrain
#endif // Y2021_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2021_bot3/control_loops/superstructure/superstructure.h b/y2021_bot3/control_loops/superstructure/superstructure.h
index 23dd801..4a0d701 100644
--- a/y2021_bot3/control_loops/superstructure/superstructure.h
+++ b/y2021_bot3/control_loops/superstructure/superstructure.h
@@ -9,9 +9,7 @@
#include "y2021_bot3/control_loops/superstructure/superstructure_position_generated.h"
#include "y2021_bot3/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2021_bot3 {
-namespace control_loops {
-namespace superstructure {
+namespace y2021_bot3::control_loops::superstructure {
class Superstructure
: public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
@@ -28,8 +26,6 @@
DISALLOW_COPY_AND_ASSIGN(Superstructure);
};
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2021_bot3
+} // namespace y2021_bot3::control_loops::superstructure
#endif // Y2021_BOT3_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
diff --git a/y2022/actors/auto_splines.h b/y2022/actors/auto_splines.h
index 2f5c399..42760e5 100644
--- a/y2022/actors/auto_splines.h
+++ b/y2022/actors/auto_splines.h
@@ -13,8 +13,7 @@
*/
-namespace y2022 {
-namespace actors {
+namespace y2022::actors {
class AutonomousSplines {
public:
@@ -73,7 +72,6 @@
aos::FlatbufferDetachedBuffer<frc971::MultiSpline> spline_two2_;
};
-} // namespace actors
-} // namespace y2022
+} // namespace y2022::actors
#endif // Y2022_ACTORS_AUTO_SPLINES_H_
diff --git a/y2022/actors/autonomous_actor.h b/y2022/actors/autonomous_actor.h
index b36e010..1dfdcdf 100644
--- a/y2022/actors/autonomous_actor.h
+++ b/y2022/actors/autonomous_actor.h
@@ -11,8 +11,7 @@
#include "y2022/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2022 {
-namespace actors {
+namespace y2022::actors {
using control_loops::superstructure::RequestedIntake;
using frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
@@ -106,7 +105,6 @@
std::optional<Eigen::Vector3d> starting_position_;
};
-} // namespace actors
-} // namespace y2022
+} // namespace y2022::actors
#endif // Y2022_ACTORS_AUTONOMOUS_ACTOR_H_
diff --git a/y2022/constants.h b/y2022/constants.h
index f27b6cd..b89613f 100644
--- a/y2022/constants.h
+++ b/y2022/constants.h
@@ -18,8 +18,7 @@
using ::frc971::shooter_interpolation::InterpolationTable;
-namespace y2022 {
-namespace constants {
+namespace y2022::constants {
constexpr uint16_t kCompTeamNumber = 971;
constexpr uint16_t kPracticeTeamNumber = 9971;
@@ -276,7 +275,6 @@
// Calls MakeValues with aos::network::GetTeamNumber()
Values MakeValues();
-} // namespace constants
-} // namespace y2022
+} // namespace y2022::constants
#endif // Y2022_CONSTANTS_H_
diff --git a/y2022/control_loops/drivetrain/drivetrain_base.h b/y2022/control_loops/drivetrain/drivetrain_base.h
index 1f4cfe4..5568698 100644
--- a/y2022/control_loops/drivetrain/drivetrain_base.h
+++ b/y2022/control_loops/drivetrain/drivetrain_base.h
@@ -3,15 +3,11 @@
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
-namespace y2022 {
-namespace control_loops {
-namespace drivetrain {
+namespace y2022::control_loops::drivetrain {
const ::frc971::control_loops::drivetrain::DrivetrainConfig<double> &
GetDrivetrainConfig();
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace y2022
+} // namespace y2022::control_loops::drivetrain
#endif // Y2022_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2022/control_loops/superstructure/collision_avoidance.h b/y2022/control_loops/superstructure/collision_avoidance.h
index 1d6f89c..034f72f 100644
--- a/y2022/control_loops/superstructure/collision_avoidance.h
+++ b/y2022/control_loops/superstructure/collision_avoidance.h
@@ -8,9 +8,7 @@
#include "y2022/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2022/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2022 {
-namespace control_loops {
-namespace superstructure {
+namespace y2022::control_loops::superstructure {
// Returns the wrapped angle as well as number of wraps (positive or negative).
// The returned angle will be inside [0.0, 2 * M_PI).
@@ -146,8 +144,6 @@
double max_turret_goal_;
};
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2022
+} // namespace y2022::control_loops::superstructure
#endif
diff --git a/y2022/control_loops/superstructure/superstructure.h b/y2022/control_loops/superstructure/superstructure.h
index 3e10956..f081589 100644
--- a/y2022/control_loops/superstructure/superstructure.h
+++ b/y2022/control_loops/superstructure/superstructure.h
@@ -18,9 +18,7 @@
#include "y2022/control_loops/superstructure/turret/aiming.h"
#include "y2022/vision/ball_color_generated.h"
-namespace y2022 {
-namespace control_loops {
-namespace superstructure {
+namespace y2022::control_loops::superstructure {
class Superstructure
: public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
@@ -113,8 +111,6 @@
DISALLOW_COPY_AND_ASSIGN(Superstructure);
};
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2022
+} // namespace y2022::control_loops::superstructure
#endif // Y2022_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
diff --git a/y2022/vision/ball_color.h b/y2022/vision/ball_color.h
index 695d2e3..824cf30 100644
--- a/y2022/vision/ball_color.h
+++ b/y2022/vision/ball_color.h
@@ -9,8 +9,7 @@
#include "y2022/constants.h"
#include "y2022/vision/ball_color_generated.h"
-namespace y2022 {
-namespace vision {
+namespace y2022::vision {
using namespace frc971::vision;
@@ -62,6 +61,5 @@
const cv::Rect reference_blue_;
const cv::Rect ball_location_;
};
-} // namespace vision
-} // namespace y2022
+} // namespace y2022::vision
#endif
diff --git a/y2022/vision/blob_detector.h b/y2022/vision/blob_detector.h
index a60316a..93bba09 100644
--- a/y2022/vision/blob_detector.h
+++ b/y2022/vision/blob_detector.h
@@ -4,8 +4,7 @@
#include <opencv2/features2d.hpp>
#include <opencv2/imgproc.hpp>
-namespace y2022 {
-namespace vision {
+namespace y2022::vision {
class BlobDetector {
public:
@@ -52,7 +51,6 @@
static void ExtractBlobs(cv::Mat bgr_image, BlobResult *blob_result);
};
-} // namespace vision
-} // namespace y2022
+} // namespace y2022::vision
#endif // Y2022_BLOB_DETECTOR_H_
diff --git a/y2022/vision/camera_reader.h b/y2022/vision/camera_reader.h
index 8782886..54fcb30 100644
--- a/y2022/vision/camera_reader.h
+++ b/y2022/vision/camera_reader.h
@@ -20,8 +20,7 @@
#include "y2022/vision/target_estimate_generated.h"
#include "y2022/vision/target_estimator.h"
-namespace y2022 {
-namespace vision {
+namespace y2022::vision {
using namespace frc971::vision;
using frc971::controls::LedOutput;
@@ -163,6 +162,5 @@
GPIOControl gpio_disable_control_;
};
-} // namespace vision
-} // namespace y2022
+} // namespace y2022::vision
#endif // Y2022_VISION_CAMERA_READER_H_
diff --git a/y2022/vision/gpio.h b/y2022/vision/gpio.h
index 6ed7328..d7b44d4 100644
--- a/y2022/vision/gpio.h
+++ b/y2022/vision/gpio.h
@@ -14,8 +14,7 @@
#include "aos/init.h"
-namespace y2022 {
-namespace vision {
+namespace y2022::vision {
using namespace frc971::vision;
@@ -353,6 +352,5 @@
aos::TimerHandler *const pwm_timer_;
};
-} // namespace vision
-} // namespace y2022
+} // namespace y2022::vision
#endif // Y2022_VISION_GPIO_H_
diff --git a/y2022_bot3/actors/auto_splines.h b/y2022_bot3/actors/auto_splines.h
index c4c32fb..a655e2a 100644
--- a/y2022_bot3/actors/auto_splines.h
+++ b/y2022_bot3/actors/auto_splines.h
@@ -13,8 +13,7 @@
*/
-namespace y2022_bot3 {
-namespace actors {
+namespace y2022_bot3::actors {
class AutonomousSplines {
public:
@@ -36,7 +35,6 @@
aos::FlatbufferDetachedBuffer<frc971::MultiSpline> test_spline_;
};
-} // namespace actors
-} // namespace y2022_bot3
+} // namespace y2022_bot3::actors
#endif // Y2022_BOT3_ACTORS_AUTO_SPLINES_H_
diff --git a/y2022_bot3/actors/autonomous_actor.h b/y2022_bot3/actors/autonomous_actor.h
index 72262fb..a4eaa29 100644
--- a/y2022_bot3/actors/autonomous_actor.h
+++ b/y2022_bot3/actors/autonomous_actor.h
@@ -11,8 +11,7 @@
#include "y2022_bot3/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2022_bot3/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2022_bot3 {
-namespace actors {
+namespace y2022_bot3::actors {
using frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
@@ -60,7 +59,6 @@
std::optional<Eigen::Vector3d> starting_position_;
};
-} // namespace actors
-} // namespace y2022_bot3
+} // namespace y2022_bot3::actors
#endif // Y2022_BOT3_ACTORS_AUTONOMOUS_ACTOR_H_
diff --git a/y2022_bot3/constants.h b/y2022_bot3/constants.h
index a87930f..33c2b1a 100644
--- a/y2022_bot3/constants.h
+++ b/y2022_bot3/constants.h
@@ -16,8 +16,7 @@
using ::frc971::shooter_interpolation::InterpolationTable;
-namespace y2022_bot3 {
-namespace constants {
+namespace y2022_bot3::constants {
struct Values {
static const int kZeroingSampleSize = 200;
@@ -119,7 +118,6 @@
// Calls MakeValues with aos::network::GetTeamNumber()
Values MakeValues();
-} // namespace constants
-} // namespace y2022_bot3
+} // namespace y2022_bot3::constants
#endif // Y2022_BOT3_CONSTANTS_H_
diff --git a/y2022_bot3/control_loops/drivetrain/drivetrain_base.h b/y2022_bot3/control_loops/drivetrain/drivetrain_base.h
index 04c6c86..41de094 100644
--- a/y2022_bot3/control_loops/drivetrain/drivetrain_base.h
+++ b/y2022_bot3/control_loops/drivetrain/drivetrain_base.h
@@ -3,15 +3,11 @@
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
-namespace y2022_bot3 {
-namespace control_loops {
-namespace drivetrain {
+namespace y2022_bot3::control_loops::drivetrain {
const ::frc971::control_loops::drivetrain::DrivetrainConfig<double> &
GetDrivetrainConfig();
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace y2022_bot3
+} // namespace y2022_bot3::control_loops::drivetrain
#endif // Y2022_BOT3_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2022_bot3/control_loops/superstructure/superstructure.h b/y2022_bot3/control_loops/superstructure/superstructure.h
index 13d5dec..4522dfd 100644
--- a/y2022_bot3/control_loops/superstructure/superstructure.h
+++ b/y2022_bot3/control_loops/superstructure/superstructure.h
@@ -11,9 +11,7 @@
#include "y2022_bot3/control_loops/superstructure/superstructure_position_generated.h"
#include "y2022_bot3/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2022_bot3 {
-namespace control_loops {
-namespace superstructure {
+namespace y2022_bot3::control_loops::superstructure {
class Superstructure
: public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
@@ -63,8 +61,6 @@
DISALLOW_COPY_AND_ASSIGN(Superstructure);
};
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2022_bot3
+} // namespace y2022_bot3::control_loops::superstructure
#endif // Y2022_BOT3_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
diff --git a/y2023/autonomous/auto_splines.h b/y2023/autonomous/auto_splines.h
index 6921e64..13c24c0 100644
--- a/y2023/autonomous/auto_splines.h
+++ b/y2023/autonomous/auto_splines.h
@@ -13,8 +13,7 @@
*/
-namespace y2023 {
-namespace autonomous {
+namespace y2023::autonomous {
class AutonomousSplines {
public:
@@ -95,7 +94,6 @@
aos::FlatbufferDetachedBuffer<frc971::MultiSpline> splinecable_4_;
};
-} // namespace autonomous
-} // namespace y2023
+} // namespace y2023::autonomous
#endif // Y2023_AUTONOMOUS_AUTO_SPLINES_H_
diff --git a/y2023/autonomous/autonomous_actor.h b/y2023/autonomous/autonomous_actor.h
index 5a5cd06..829cd0e 100644
--- a/y2023/autonomous/autonomous_actor.h
+++ b/y2023/autonomous/autonomous_actor.h
@@ -11,8 +11,7 @@
#include "y2023/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2023/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2023 {
-namespace autonomous {
+namespace y2023::autonomous {
class AutonomousActor
: public ::frc971::autonomous::UserButtonLocalizedAutonomousActor {
@@ -83,7 +82,6 @@
const ::std::vector<::Eigen::Matrix<double, 3, 1>> points_;
};
-} // namespace autonomous
-} // namespace y2023
+} // namespace y2023::autonomous
#endif // Y2023_AUTONOMOUS_AUTONOMOUS_ACTOR_H_
diff --git a/y2023/constants.h b/y2023/constants.h
index 92428db..402fc73 100644
--- a/y2023/constants.h
+++ b/y2023/constants.h
@@ -15,8 +15,7 @@
#include "y2023/control_loops/superstructure/roll/roll_plant.h"
#include "y2023/control_loops/superstructure/wrist/wrist_plant.h"
-namespace y2023 {
-namespace constants {
+namespace y2023::constants {
constexpr uint16_t kCompTeamNumber = 971;
constexpr uint16_t kPracticeTeamNumber = 9971;
@@ -236,7 +235,6 @@
// Calls MakeValues with aos::network::GetTeamNumber()
Values MakeValues();
-} // namespace constants
-} // namespace y2023
+} // namespace y2023::constants
#endif // Y2023_CONSTANTS_H_
diff --git a/y2023/control_loops/drivetrain/drivetrain_base.h b/y2023/control_loops/drivetrain/drivetrain_base.h
index 98f984e..00d4d0e 100644
--- a/y2023/control_loops/drivetrain/drivetrain_base.h
+++ b/y2023/control_loops/drivetrain/drivetrain_base.h
@@ -3,15 +3,11 @@
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
-namespace y2023 {
-namespace control_loops {
-namespace drivetrain {
+namespace y2023::control_loops::drivetrain {
const ::frc971::control_loops::drivetrain::DrivetrainConfig<double> &
GetDrivetrainConfig();
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace y2023
+} // namespace y2023::control_loops::drivetrain
#endif // Y2023_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2023/control_loops/superstructure/arm/BUILD b/y2023/control_loops/superstructure/arm/BUILD
index 2f4e7d6..a54f72c 100644
--- a/y2023/control_loops/superstructure/arm/BUILD
+++ b/y2023/control_loops/superstructure/arm/BUILD
@@ -119,7 +119,7 @@
deps = [
":arm_constants",
"//aos:init",
- "//frc971/analysis:in_process_plotter",
+ "//aos/analysis:in_process_plotter",
"//frc971/control_loops:dlqr",
"//frc971/control_loops:jacobian",
"//frc971/control_loops/double_jointed_arm:dynamics",
@@ -166,7 +166,7 @@
":arm_constants",
":generated_graph",
":trajectory",
- "//frc971/analysis:in_process_plotter",
+ "//aos/analysis:in_process_plotter",
"//frc971/control_loops:binomial",
"//frc971/control_loops:fixed_quadrature",
"//frc971/control_loops/double_jointed_arm:ekf",
diff --git a/y2023/control_loops/superstructure/arm/arm.h b/y2023/control_loops/superstructure/arm/arm.h
index 6153400..2160b38 100644
--- a/y2023/control_loops/superstructure/arm/arm.h
+++ b/y2023/control_loops/superstructure/arm/arm.h
@@ -15,10 +15,7 @@
using frc971::control_loops::arm::EKF;
-namespace y2023 {
-namespace control_loops {
-namespace superstructure {
-namespace arm {
+namespace y2023::control_loops::superstructure::arm {
class Arm {
public:
@@ -116,9 +113,6 @@
EIGEN_MAKE_ALIGNED_OPERATOR_NEW;
};
-} // namespace arm
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2023
+} // namespace y2023::control_loops::superstructure::arm
#endif // Y2023_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_ARM_H_
diff --git a/y2023/control_loops/superstructure/arm/arm_constants.h b/y2023/control_loops/superstructure/arm/arm_constants.h
index fc716af..d5b11cb 100644
--- a/y2023/control_loops/superstructure/arm/arm_constants.h
+++ b/y2023/control_loops/superstructure/arm/arm_constants.h
@@ -3,10 +3,7 @@
#include "frc971/control_loops/double_jointed_arm/dynamics.h"
-namespace y2023 {
-namespace control_loops {
-namespace superstructure {
-namespace arm {
+namespace y2023::control_loops::superstructure::arm {
constexpr double kEfficiencyTweak = 0.95;
constexpr double kStallTorque = 4.69 * kEfficiencyTweak;
@@ -45,9 +42,6 @@
.num_distal_motors = 1.0,
};
-} // namespace arm
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2023
+} // namespace y2023::control_loops::superstructure::arm
#endif // Y2023_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_ARM_CONSTANTS_H_
diff --git a/y2023/control_loops/superstructure/arm/arm_design.cc b/y2023/control_loops/superstructure/arm/arm_design.cc
index e918746..8c5664e 100644
--- a/y2023/control_loops/superstructure/arm/arm_design.cc
+++ b/y2023/control_loops/superstructure/arm/arm_design.cc
@@ -1,5 +1,5 @@
+#include "aos/analysis/in_process_plotter.h"
#include "aos/init.h"
-#include "frc971/analysis/in_process_plotter.h"
#include "frc971/control_loops/dlqr.h"
#include "frc971/control_loops/double_jointed_arm/dynamics.h"
#include "frc971/control_loops/jacobian.h"
@@ -20,7 +20,7 @@
namespace y2023::control_loops::superstructure::arm {
int Main() {
- frc971::analysis::Plotter plotter;
+ aos::analysis::Plotter plotter;
frc971::control_loops::arm::Dynamics dynamics(kArmConstants);
diff --git a/y2023/control_loops/superstructure/arm/trajectory.h b/y2023/control_loops/superstructure/arm/trajectory.h
index 7994d60..7b56789 100644
--- a/y2023/control_loops/superstructure/arm/trajectory.h
+++ b/y2023/control_loops/superstructure/arm/trajectory.h
@@ -16,10 +16,7 @@
#include "frc971/control_loops/state_feedback_loop.h"
#include "y2023/control_loops/superstructure/arm/arm_trajectories_generated.h"
-namespace y2023 {
-namespace control_loops {
-namespace superstructure {
-namespace arm {
+namespace y2023::control_loops::superstructure::arm {
using frc971::control_loops::Binomial;
using frc971::control_loops::GaussianQuadrature5;
@@ -623,9 +620,6 @@
int failed_solutions_ = 0;
};
-} // namespace arm
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2023
+} // namespace y2023::control_loops::superstructure::arm
#endif // Y2023_CONTROL_LOOPS_SUPERSTRUCTURE_ARM_TRAJECTORY_H_
diff --git a/y2023/control_loops/superstructure/arm/trajectory_plot.cc b/y2023/control_loops/superstructure/arm/trajectory_plot.cc
index 4db5080..8488d72 100644
--- a/y2023/control_loops/superstructure/arm/trajectory_plot.cc
+++ b/y2023/control_loops/superstructure/arm/trajectory_plot.cc
@@ -1,7 +1,7 @@
#include "gflags/gflags.h"
+#include "aos/analysis/in_process_plotter.h"
#include "aos/init.h"
-#include "frc971/analysis/in_process_plotter.h"
#include "frc971/control_loops/binomial.h"
#include "frc971/control_loops/double_jointed_arm/dynamics.h"
#include "frc971/control_loops/double_jointed_arm/ekf.h"
@@ -396,7 +396,7 @@
}
if (FLAGS_plot) {
- frc971::analysis::Plotter plotter;
+ aos::analysis::Plotter plotter;
plotter.AddFigure();
plotter.Title("Input spline");
diff --git a/y2023/control_loops/superstructure/end_effector.h b/y2023/control_loops/superstructure/end_effector.h
index da0ce5e..04cde94 100644
--- a/y2023/control_loops/superstructure/end_effector.h
+++ b/y2023/control_loops/superstructure/end_effector.h
@@ -9,9 +9,7 @@
#include "y2023/control_loops/superstructure/superstructure_status_generated.h"
#include "y2023/vision/game_pieces_generated.h"
-namespace y2023 {
-namespace control_loops {
-namespace superstructure {
+namespace y2023::control_loops::superstructure {
class EndEffector {
public:
@@ -39,8 +37,6 @@
bool beambreak_;
};
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2023
+} // namespace y2023::control_loops::superstructure
#endif // Y2023_CONTROL_LOOPS_SUPERSTRUCTURE_END_EFFECTOR_H_
diff --git a/y2023/control_loops/superstructure/superstructure.h b/y2023/control_loops/superstructure/superstructure.h
index bcee3ea..349131b 100644
--- a/y2023/control_loops/superstructure/superstructure.h
+++ b/y2023/control_loops/superstructure/superstructure.h
@@ -22,9 +22,7 @@
using y2023::control_loops::superstructure::arm::ArmTrajectories;
using y2023::control_loops::superstructure::arm::TrajectoryAndParams;
-namespace y2023 {
-namespace control_loops {
-namespace superstructure {
+namespace y2023::control_loops::superstructure {
class Superstructure
: public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
@@ -86,8 +84,6 @@
DISALLOW_COPY_AND_ASSIGN(Superstructure);
};
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2023
+} // namespace y2023::control_loops::superstructure
#endif // Y2023_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
diff --git a/y2023/vision/aprilrobotics.h b/y2023/vision/aprilrobotics.h
index 123f352..e11bfcc 100644
--- a/y2023/vision/aprilrobotics.h
+++ b/y2023/vision/aprilrobotics.h
@@ -21,8 +21,7 @@
#include "frc971/vision/visualize_robot.h"
#include "y2023/constants/constants_generated.h"
-namespace y2023 {
-namespace vision {
+namespace y2023::vision {
class AprilRoboticsDetector {
public:
@@ -97,5 +96,4 @@
frc971::vision::VisualizeRobot vis_robot_;
};
-} // namespace vision
-} // namespace y2023
+} // namespace y2023::vision
diff --git a/y2023/vision/game_pieces.h b/y2023/vision/game_pieces.h
index 442d95c..45bf894 100644
--- a/y2023/vision/game_pieces.h
+++ b/y2023/vision/game_pieces.h
@@ -6,8 +6,7 @@
#include "y2023/vision/game_pieces_generated.h"
#include "y2023/vision/yolov5.h"
-namespace y2023 {
-namespace vision {
+namespace y2023::vision {
using namespace frc971::vision;
@@ -23,6 +22,5 @@
aos::Sender<GamePieces> game_pieces_sender_;
std::unique_ptr<YOLOV5> model;
};
-} // namespace vision
-} // namespace y2023
+} // namespace y2023::vision
#endif
diff --git a/y2023/vision/yolov5.h b/y2023/vision/yolov5.h
index 9853b4f..2d7f641 100644
--- a/y2023/vision/yolov5.h
+++ b/y2023/vision/yolov5.h
@@ -13,8 +13,7 @@
#include <opencv2/imgcodecs.hpp>
#include <opencv2/imgproc.hpp>
-namespace y2023 {
-namespace vision {
+namespace y2023::vision {
struct Detection {
cv::Rect box;
@@ -36,7 +35,6 @@
std::unique_ptr<YOLOV5> MakeYOLOV5();
-} // namespace vision
-} // namespace y2023
+} // namespace y2023::vision
#endif // Y2023_VISION_YOLOV5_H_
diff --git a/y2023_bot3/autonomous/auto_splines.h b/y2023_bot3/autonomous/auto_splines.h
index daa39b7..2494880 100644
--- a/y2023_bot3/autonomous/auto_splines.h
+++ b/y2023_bot3/autonomous/auto_splines.h
@@ -13,8 +13,7 @@
*/
-namespace y2023_bot3 {
-namespace autonomous {
+namespace y2023_bot3::autonomous {
class AutonomousSplines {
public:
@@ -74,7 +73,6 @@
aos::FlatbufferDetachedBuffer<frc971::MultiSpline> spline_middle_1_;
};
-} // namespace autonomous
-} // namespace y2023_bot3
+} // namespace y2023_bot3::autonomous
#endif // Y2023_AUTONOMOUS_AUTO_SPLINES_H_
diff --git a/y2023_bot3/autonomous/autonomous_actor.h b/y2023_bot3/autonomous/autonomous_actor.h
index bc0a35c..2247b4a 100644
--- a/y2023_bot3/autonomous/autonomous_actor.h
+++ b/y2023_bot3/autonomous/autonomous_actor.h
@@ -11,8 +11,7 @@
#include "y2023_bot3/control_loops/superstructure/superstructure_goal_generated.h"
#include "y2023_bot3/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2023_bot3 {
-namespace autonomous {
+namespace y2023_bot3::autonomous {
class AutonomousActor : public ::frc971::autonomous::BaseAutonomousActor {
public:
@@ -59,7 +58,6 @@
std::optional<std::array<SplineHandle, 1>> charged_up_middle_splines_;
};
-} // namespace autonomous
-} // namespace y2023_bot3
+} // namespace y2023_bot3::autonomous
#endif // Y2023_AUTONOMOUS_AUTONOMOUS_ACTOR_H_
diff --git a/y2023_bot3/constants.h b/y2023_bot3/constants.h
index 60fe404..beca532 100644
--- a/y2023_bot3/constants.h
+++ b/y2023_bot3/constants.h
@@ -10,8 +10,7 @@
#include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h"
#include "frc971/zeroing/pot_and_absolute_encoder.h"
#include "y2023_bot3/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
-namespace y2023_bot3 {
-namespace constants {
+namespace y2023_bot3::constants {
constexpr uint16_t kThirdRobotTeamNumber = 9984;
@@ -66,7 +65,6 @@
// Calls MakeValues with aos::network::GetTeamNumber()
Values MakeValues();
-} // namespace constants
-} // namespace y2023_bot3
+} // namespace y2023_bot3::constants
#endif // Y2023_BOT3_CONSTANTS_H_
diff --git a/y2023_bot3/control_loops/drivetrain/drivetrain_base.h b/y2023_bot3/control_loops/drivetrain/drivetrain_base.h
index 6922ea6..a3cfeff 100644
--- a/y2023_bot3/control_loops/drivetrain/drivetrain_base.h
+++ b/y2023_bot3/control_loops/drivetrain/drivetrain_base.h
@@ -3,15 +3,11 @@
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
-namespace y2023_bot3 {
-namespace control_loops {
-namespace drivetrain {
+namespace y2023_bot3::control_loops::drivetrain {
const ::frc971::control_loops::drivetrain::DrivetrainConfig<double> &
GetDrivetrainConfig();
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace y2023_bot3
+} // namespace y2023_bot3::control_loops::drivetrain
#endif // Y2023_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2023_bot3/control_loops/superstructure/superstructure.h b/y2023_bot3/control_loops/superstructure/superstructure.h
index d0cd0db..4b55d76 100644
--- a/y2023_bot3/control_loops/superstructure/superstructure.h
+++ b/y2023_bot3/control_loops/superstructure/superstructure.h
@@ -14,9 +14,7 @@
#include "y2023_bot3/control_loops/superstructure/superstructure_position_generated.h"
#include "y2023_bot3/control_loops/superstructure/superstructure_status_generated.h"
-namespace y2023_bot3 {
-namespace control_loops {
-namespace superstructure {
+namespace y2023_bot3::control_loops::superstructure {
class Superstructure
: public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
@@ -47,8 +45,6 @@
DISALLOW_COPY_AND_ASSIGN(Superstructure);
};
-} // namespace superstructure
-} // namespace control_loops
-} // namespace y2023_bot3
+} // namespace y2023_bot3::control_loops::superstructure
#endif // Y2023_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
diff --git a/y2023_bot4/constants.h b/y2023_bot4/constants.h
index 676ae06..fbbc5f2 100644
--- a/y2023_bot4/constants.h
+++ b/y2023_bot4/constants.h
@@ -9,8 +9,7 @@
#include "frc971/constants.h"
-namespace y2023_bot4 {
-namespace constants {
+namespace y2023_bot4::constants {
struct Values {
static const int kZeroingSampleSize = 200;
@@ -49,7 +48,6 @@
// Calls MakeValues with aos::network::GetTeamNumber()
Values MakeValues();
-} // namespace constants
-} // namespace y2023_bot4
+} // namespace y2023_bot4::constants
#endif // Y2023_BOT4_CONSTANTS_H
diff --git a/y2024/BUILD b/y2024/BUILD
index 148c23d..875bf84 100644
--- a/y2024/BUILD
+++ b/y2024/BUILD
@@ -54,7 +54,7 @@
"//aos/util:foxglove_websocket",
"//frc971/image_streamer:image_streamer",
"//frc971/vision:intrinsics_calibration",
- "//y2023/vision:viewer",
+ "//y2024/vision:viewer",
"//y2024/constants:constants_sender",
"//y2024/vision:foxglove_image_converter",
],
@@ -211,6 +211,7 @@
"//frc971/zeroing:absolute_encoder",
"//frc971/zeroing:pot_and_absolute_encoder",
"//y2024/control_loops/drivetrain:polydrivetrain_plants",
+ "//y2024/control_loops/superstructure/climber:climber_plants",
"//y2024/control_loops/superstructure/intake_pivot:intake_pivot_plants",
"@com_github_google_glog//:glog",
"@com_google_absl//absl/base",
@@ -321,6 +322,7 @@
data = [
":aos_config",
"//aos/network:log_web_proxy_main",
+ "//y2024/www:field_main_bundle.min.js",
"//y2024/www:files",
],
target_compatible_with = ["@platforms//os:linux"],
diff --git a/y2024/constants.h b/y2024/constants.h
index b90534c..8eac0c9 100644
--- a/y2024/constants.h
+++ b/y2024/constants.h
@@ -11,10 +11,10 @@
#include "frc971/zeroing/absolute_encoder.h"
#include "frc971/zeroing/pot_and_absolute_encoder.h"
#include "y2024/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "y2024/control_loops/superstructure/climber/climber_plant.h"
#include "y2024/control_loops/superstructure/intake_pivot/intake_pivot_plant.h"
-namespace y2024 {
-namespace constants {
+namespace y2024::constants {
constexpr uint16_t kCompTeamNumber = 971;
constexpr uint16_t kPracticeTeamNumber = 9971;
@@ -39,9 +39,6 @@
kDrivetrainEncoderCountsPerRevolution();
}
- static constexpr double kDrivetrainSupplyCurrentLimit() { return 35.0; }
- static constexpr double kDrivetrainStatorCurrentLimit() { return 60.0; }
-
static double DrivetrainEncoderToMeters(int32_t in) {
return ((static_cast<double>(in) /
kDrivetrainEncoderCountsPerRevolution()) *
@@ -77,6 +74,28 @@
kIntakePivotEncoderCountsPerRevolution();
}
+ // TODO(Filip): Update climber values once we have them.
+ static constexpr double kClimberEncoderCountsPerRevolution() {
+ return 4096.0;
+ }
+
+ static constexpr double kClimberEncoderRatio() {
+ return (16.0 / 64.0) * (18.0 / 62.0);
+ }
+
+ static constexpr double kClimberPotRatio() { return 16.0 / 64.0; }
+
+ static constexpr double kClimberPotRadiansPerVolt() {
+ return kClimberPotRatio() * (3.0 /*turns*/ / 5.0 /*volts*/) *
+ (2 * M_PI /*radians*/);
+ }
+
+ static constexpr double kMaxClimberEncoderPulsesPerSecond() {
+ return control_loops::superstructure::climber::kFreeSpeed / (2.0 * M_PI) *
+ control_loops::superstructure::climber::kOutputRatio /
+ kClimberEncoderRatio() * kClimberEncoderCountsPerRevolution();
+ }
+
struct PotAndAbsEncoderConstants {
::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemParams<
::frc971::zeroing::PotAndAbsoluteEncoderZeroingEstimator>
@@ -93,7 +112,6 @@
// Calls MakeValues with aos::network::GetTeamNumber()
constants::Values MakeValues();
-} // namespace constants
-} // namespace y2024
+} // namespace y2024::constants
#endif // Y2024_CONSTANTS_H_
diff --git a/y2024/constants/7971.json b/y2024/constants/7971.json
index 7e04438..9e6bafb 100644
--- a/y2024/constants/7971.json
+++ b/y2024/constants/7971.json
@@ -1,4 +1,5 @@
{% from 'y2024/constants/common.jinja2' import intake_pivot_zero %}
+{% from 'y2024/constants/common.jinja2' import climber_zero %}
{
"robot": {
@@ -8,7 +9,16 @@
"measured_absolute_position" : 0.0
}
) %}
- "intake_pivot_zero": {{ intake_pivot_zero | tojson(indent=2)}},
+ "zeroing_constants": {{ intake_pivot_zero | tojson(indent=2)}},
+ "potentiometer_offset": 0.0
+ },
+ "climber_constants": {
+ {% set _ = climber_zero.update(
+ {
+ "measured_absolute_position" : 0.0
+ }
+ ) %}
+ "zeroing_constants": {{ climber_zero | tojson(indent=2)}},
"potentiometer_offset": 0.0
}
},
diff --git a/y2024/constants/971.json b/y2024/constants/971.json
index a061f39..641783f 100644
--- a/y2024/constants/971.json
+++ b/y2024/constants/971.json
@@ -1,4 +1,5 @@
{% from 'y2024/constants/common.jinja2' import intake_pivot_zero %}
+{% from 'y2024/constants/common.jinja2' import climber_zero %}
{
"cameras": [
@@ -13,7 +14,16 @@
"measured_absolute_position" : 0.0
}
) %}
- "intake_pivot_zero": {{ intake_pivot_zero | tojson(indent=2)}},
+ "zeroing_constants": {{ intake_pivot_zero | tojson(indent=2)}},
+ "potentiometer_offset": 0.0
+ },
+ "climber_constants": {
+ {% set _ = climber_zero.update(
+ {
+ "measured_absolute_position" : 0.0
+ }
+ ) %}
+ "zeroing_constants": {{ climber_zero | tojson(indent=2)}},
"potentiometer_offset": 0.0
}
},
diff --git a/y2024/constants/9971.json b/y2024/constants/9971.json
index 7e04438..9e6bafb 100644
--- a/y2024/constants/9971.json
+++ b/y2024/constants/9971.json
@@ -1,4 +1,5 @@
{% from 'y2024/constants/common.jinja2' import intake_pivot_zero %}
+{% from 'y2024/constants/common.jinja2' import climber_zero %}
{
"robot": {
@@ -8,7 +9,16 @@
"measured_absolute_position" : 0.0
}
) %}
- "intake_pivot_zero": {{ intake_pivot_zero | tojson(indent=2)}},
+ "zeroing_constants": {{ intake_pivot_zero | tojson(indent=2)}},
+ "potentiometer_offset": 0.0
+ },
+ "climber_constants": {
+ {% set _ = climber_zero.update(
+ {
+ "measured_absolute_position" : 0.0
+ }
+ ) %}
+ "zeroing_constants": {{ climber_zero | tojson(indent=2)}},
"potentiometer_offset": 0.0
}
},
diff --git a/y2024/constants/BUILD b/y2024/constants/BUILD
index 18e506a..1f25bcb 100644
--- a/y2024/constants/BUILD
+++ b/y2024/constants/BUILD
@@ -23,6 +23,7 @@
"test_data/*.json",
]) + [
"//y2024/control_loops/superstructure/intake_pivot:intake_pivot_json",
+ "//y2024/control_loops/superstructure/climber:climber_json",
"//y2024/control_loops/drivetrain:drivetrain_config.json",
"common.json",
"common.jinja2",
@@ -43,6 +44,7 @@
"common.json",
"//y2024/constants/calib_files",
"//y2024/control_loops/drivetrain:drivetrain_config.json",
+ "//y2024/control_loops/superstructure/climber:climber_json",
"//y2024/control_loops/superstructure/intake_pivot:intake_pivot_json",
"//y2024/vision/maps",
],
diff --git a/y2024/constants/common.jinja2 b/y2024/constants/common.jinja2
index b260074..d6db5e5 100644
--- a/y2024/constants/common.jinja2
+++ b/y2024/constants/common.jinja2
@@ -1,7 +1,7 @@
{% set pi = 3.14159265 %}
{# we do this here so we keep the encoder ratio in plaintext and also keep the math we're using. #}
-{% set intake_pivot_encoder_ratio = (16.0 / 64.0) * (18.0 / 62.0) %}
+{% set intake_pivot_encoder_ratio = (24.0 / 15.0) %}
{%set zeroing_sample_size = 200 %}
@@ -14,3 +14,16 @@
"allowable_encoder_error": 0.9
}
%}
+
+{# TODO(Filip): Update climber values #}
+{% set climber_encoder_ratio = (1.0 / 1.0) %}
+{% set climber_radius = 0.436496 %}
+{%
+set climber_zero = {
+ "average_filter_size": zeroing_sample_size,
+ "one_revolution_distance": pi * 2.0 * climber_encoder_ratio * climber_radius,
+ "zeroing_threshold": 0.0005,
+ "moving_buffer_size": 20,
+ "allowable_encoder_error": 0.9
+}
+%}
diff --git a/y2024/constants/common.json b/y2024/constants/common.json
index 2e89bfa..554f1e8 100644
--- a/y2024/constants/common.json
+++ b/y2024/constants/common.json
@@ -45,10 +45,38 @@
"intake_roller_supply_current_limit": 35,
"intake_roller_stator_current_limit": 60,
"transfer_roller_supply_current_limit": 35,
- "transfer_roller_stator_current_limit": 60
+ "transfer_roller_stator_current_limit": 60,
+ "drivetrain_supply_current_limit": 35,
+ "drivetrain_stator_current_limit": 60,
+ "climber_supply_current_limit": 35,
+ "climber_stator_current_limit": 60
},
"transfer_roller_voltages": {
"transfer_in": 12.0,
"transfer_out": -12.0
+ },
+ "climber_set_points": {
+ "full_extend": 0.8,
+ "half_extend": 0.6,
+ "retract": 0.2
+ },
+ "climber": {
+ "zeroing_voltage": 3.0,
+ "operating_voltage": 12.0,
+ "zeroing_profile_params": {
+ "max_velocity": 0.5,
+ "max_acceleration": 3.0
+ },
+ "default_profile_params":{
+ "max_velocity": 6.0,
+ "max_acceleration": 30.0
+ },
+ "range": {
+ "lower_hard": 0.1,
+ "upper_hard": 2.01,
+ "lower": 0.2,
+ "upper": 2.0
+ },
+ "loop": {% include 'y2024/control_loops/superstructure/climber/integral_climber_plant.json' %}
}
}
diff --git a/y2024/constants/constants.fbs b/y2024/constants/constants.fbs
index 54e6925..40d609f 100644
--- a/y2024/constants/constants.fbs
+++ b/y2024/constants/constants.fbs
@@ -36,9 +36,18 @@
retracted:double (id: 1);
}
-// Intake Constants
-table IntakeConstants {
- intake_pivot_zero:frc971.zeroing.PotAndAbsoluteEncoderZeroingConstants (id: 0);
+// Set points for the climber in meters when:
+// fully extended, which represents meters for when ClimberGoal is FULL_EXTEND
+// partially extended, which represents meters for when ClimberGoal is HALF_EXTEND
+// and retracted, which represents meters for when ClimberGoal is RETRACT
+table ClimberSetPoints {
+ full_extend:double (id: 0);
+ half_extend:double (id: 1);
+ retract:double (id: 2);
+}
+
+table PotAndAbsEncoderConstants {
+ zeroing_constants:frc971.zeroing.PotAndAbsoluteEncoderZeroingConstants (id: 0);
potentiometer_offset:double (id: 1);
}
@@ -50,6 +59,10 @@
intake_roller_stator_current_limit:double (id: 3);
transfer_roller_supply_current_limit:double (id: 4);
transfer_roller_stator_current_limit:double (id: 5);
+ drivetrain_supply_current_limit:double (id: 6);
+ drivetrain_stator_current_limit:double (id: 7);
+ climber_supply_current_limit:double (id: 8);
+ climber_stator_current_limit:double (id: 9);
}
table TransferRollerVoltages {
@@ -58,7 +71,9 @@
}
table RobotConstants {
- intake_constants:IntakeConstants (id: 0);
+ intake_constants:PotAndAbsEncoderConstants (id: 0);
+ climber_constants:PotAndAbsEncoderConstants (id: 1);
+
}
// Common table for constants unrelated to the robot
@@ -71,6 +86,8 @@
drivetrain:frc971.control_loops.drivetrain.fbs.DrivetrainConfig (id: 5);
current_limits:CurrentLimits (id: 6);
transfer_roller_voltages:TransferRollerVoltages (id: 7);
+ climber:frc971.control_loops.StaticZeroingSingleDOFProfiledSubsystemCommonParams (id: 8);
+ climber_set_points:ClimberSetPoints (id: 9);
}
table Constants {
diff --git a/y2024/constants/test_data/test_team.json b/y2024/constants/test_data/test_team.json
index 7e04438..9e6bafb 100644
--- a/y2024/constants/test_data/test_team.json
+++ b/y2024/constants/test_data/test_team.json
@@ -1,4 +1,5 @@
{% from 'y2024/constants/common.jinja2' import intake_pivot_zero %}
+{% from 'y2024/constants/common.jinja2' import climber_zero %}
{
"robot": {
@@ -8,7 +9,16 @@
"measured_absolute_position" : 0.0
}
) %}
- "intake_pivot_zero": {{ intake_pivot_zero | tojson(indent=2)}},
+ "zeroing_constants": {{ intake_pivot_zero | tojson(indent=2)}},
+ "potentiometer_offset": 0.0
+ },
+ "climber_constants": {
+ {% set _ = climber_zero.update(
+ {
+ "measured_absolute_position" : 0.0
+ }
+ ) %}
+ "zeroing_constants": {{ climber_zero | tojson(indent=2)}},
"potentiometer_offset": 0.0
}
},
diff --git a/y2024/control_loops/python/BUILD b/y2024/control_loops/python/BUILD
index f92b484..da80d87 100644
--- a/y2024/control_loops/python/BUILD
+++ b/y2024/control_loops/python/BUILD
@@ -61,6 +61,22 @@
],
)
+py_binary(
+ name = "climber",
+ srcs = [
+ "climber.py",
+ ],
+ legacy_create_init = False,
+ target_compatible_with = ["@platforms//cpu:x86_64"],
+ deps = [
+ ":python_init",
+ "//frc971/control_loops/python:controls",
+ "//frc971/control_loops/python:linear_system",
+ "@pip//glog",
+ "@pip//python_gflags",
+ ],
+)
+
py_library(
name = "python_init",
srcs = ["__init__.py"],
diff --git a/y2024/control_loops/python/climber.py b/y2024/control_loops/python/climber.py
new file mode 100644
index 0000000..10aeff9
--- /dev/null
+++ b/y2024/control_loops/python/climber.py
@@ -0,0 +1,54 @@
+#!/usr/bin/python3
+
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import linear_system
+import numpy
+import sys
+import gflags
+import glog
+
+FLAGS = gflags.FLAGS
+
+try:
+ gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+except gflags.DuplicateFlagError:
+ pass
+
+# TODO(Filip): Update information the climber when design is finalized.
+kClimber = linear_system.LinearSystemParams(
+ name='Climber',
+ motor=control_loop.Falcon(),
+ G=(1.0 / 4.0) * (1.0 / 3.0) * (1.0 / 3.0),
+ radius=22 * 0.25 / numpy.pi / 2.0 * 0.0254,
+ mass=2.0,
+ q_pos=0.10,
+ q_vel=1.35,
+ kalman_q_pos=0.12,
+ kalman_q_vel=2.00,
+ kalman_q_voltage=35.0,
+ kalman_r_position=0.05)
+
+
+def main(argv):
+ if FLAGS.plot:
+ R = numpy.matrix([[0.2], [0.0]])
+ linear_system.PlotKick(kClimber, R, plant_params=kClimber)
+ linear_system.PlotMotion(kClimber,
+ R,
+ max_velocity=5.0,
+ plant_params=kClimber)
+
+ # Write the generated constants out to a file.
+ if len(argv) != 7:
+ glog.fatal(
+ 'Expected .h file name and .cc file name for the climber and integral climber.'
+ )
+ else:
+ namespaces = ['y2024', 'control_loops', 'superstructure', 'climber']
+ linear_system.WriteLinearSystem(kClimber, argv[1:4], argv[4:7], namespaces)
+
+
+if __name__ == '__main__':
+ argv = FLAGS(sys.argv)
+ glog.init()
+ sys.exit(main(argv))
diff --git a/y2024/control_loops/python/intake_pivot.py b/y2024/control_loops/python/intake_pivot.py
index 9e7543b..f32aa8b 100644
--- a/y2024/control_loops/python/intake_pivot.py
+++ b/y2024/control_loops/python/intake_pivot.py
@@ -20,16 +20,15 @@
kIntakePivot = angular_system.AngularSystemParams(
name='IntakePivot',
motor=control_loop.KrakenFOC(),
- # TODO(Niko): Change gear ratios when we have all of them
- G=0.02,
- J=0.34,
+ G=(16.0 / 60.0) * (18.0 / 62.0) * (18.0 / 62.0) * (15.0 / 24.0),
+ J=0.34, # Borrowed from 2022, 0.035 seems too low
q_pos=0.40,
q_vel=20.0,
kalman_q_pos=0.12,
kalman_q_vel=2.0,
kalman_q_voltage=4.0,
kalman_r_position=0.05,
- radius=13 * 0.0254)
+ radius=6.85 * 0.0254)
def main(argv):
diff --git a/y2024/control_loops/superstructure/climber/BUILD b/y2024/control_loops/superstructure/climber/BUILD
new file mode 100644
index 0000000..4a044d2
--- /dev/null
+++ b/y2024/control_loops/superstructure/climber/BUILD
@@ -0,0 +1,42 @@
+package(default_visibility = ["//y2024:__subpackages__"])
+
+genrule(
+ name = "genrule_climber",
+ outs = [
+ "climber_plant.h",
+ "climber_plant.cc",
+ "climber_plant.json",
+ "integral_climber_plant.h",
+ "integral_climber_plant.cc",
+ "integral_climber_plant.json",
+ ],
+ cmd = "$(location //y2024/control_loops/python:climber) $(OUTS)",
+ target_compatible_with = ["@platforms//os:linux"],
+ tools = [
+ "//y2024/control_loops/python:climber",
+ ],
+)
+
+cc_library(
+ name = "climber_plants",
+ srcs = [
+ "climber_plant.cc",
+ "integral_climber_plant.cc",
+ ],
+ hdrs = [
+ "climber_plant.h",
+ "integral_climber_plant.h",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//frc971/control_loops:hybrid_state_feedback_loop",
+ "//frc971/control_loops:state_feedback_loop",
+ ],
+)
+
+filegroup(
+ name = "climber_json",
+ srcs = ["integral_climber_plant.json"],
+ visibility = ["//visibility:public"],
+)
diff --git a/y2024/control_loops/superstructure/superstructure.cc b/y2024/control_loops/superstructure/superstructure.cc
index 9a703e3..18db6d6 100644
--- a/y2024/control_loops/superstructure/superstructure.cc
+++ b/y2024/control_loops/superstructure/superstructure.cc
@@ -33,7 +33,10 @@
transfer_goal_(TransferRollerGoal::NONE),
intake_pivot_(
robot_constants_->common()->intake_pivot(),
- robot_constants_->robot()->intake_constants()->intake_pivot_zero()) {
+ robot_constants_->robot()->intake_constants()->zeroing_constants()),
+ climber_(
+ robot_constants_->common()->climber(),
+ robot_constants_->robot()->climber_constants()->zeroing_constants()) {
event_loop->SetRuntimeRealtimePriority(30);
}
@@ -50,6 +53,7 @@
if (WasReset()) {
AOS_LOG(ERROR, "WPILib reset, restarting\n");
intake_pivot_.Reset();
+ climber_.Reset();
}
OutputT output_struct;
@@ -109,6 +113,28 @@
break;
}
+ double climber_position =
+ robot_constants_->common()->climber_set_points()->retract();
+
+ if (unsafe_goal != nullptr) {
+ switch (unsafe_goal->climber_goal()) {
+ case ClimberGoal::FULL_EXTEND:
+ climber_position =
+ robot_constants_->common()->climber_set_points()->full_extend();
+ break;
+ case ClimberGoal::HALF_EXTEND:
+ climber_position =
+ robot_constants_->common()->climber_set_points()->half_extend();
+ break;
+ case ClimberGoal::RETRACT:
+ climber_position =
+ robot_constants_->common()->climber_set_points()->retract();
+ break;
+ default:
+ break;
+ }
+ }
+
if (joystick_state_fetcher_.Fetch() &&
joystick_state_fetcher_->has_alliance()) {
alliance_ = joystick_state_fetcher_->alliance();
@@ -133,20 +159,38 @@
output != nullptr ? &output_struct.intake_pivot_voltage : nullptr,
status->fbb());
+ aos::FlatbufferFixedAllocatorArray<
+ frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal, 512>
+ climber_goal_buffer;
+
+ climber_goal_buffer.Finish(
+ frc971::control_loops::CreateStaticZeroingSingleDOFProfiledSubsystemGoal(
+ *climber_goal_buffer.fbb(), climber_position));
+
+ const frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal
+ *climber_goal = &climber_goal_buffer.message();
+
+ const flatbuffers::Offset<PotAndAbsoluteEncoderProfiledJointStatus>
+ climber_status_offset = climber_.Iterate(
+ climber_goal, position->climber(),
+ output != nullptr ? &output_struct.climber_voltage : nullptr,
+ status->fbb());
+
if (output) {
output->CheckOk(output->Send(Output::Pack(*output->fbb(), &output_struct)));
}
Status::Builder status_builder = status->MakeBuilder<Status>();
- const bool zeroed = intake_pivot_.zeroed();
- const bool estopped = intake_pivot_.estopped();
+ const bool zeroed = intake_pivot_.zeroed() && climber_.zeroed();
+ const bool estopped = intake_pivot_.estopped() || climber_.estopped();
status_builder.add_zeroed(zeroed);
status_builder.add_estopped(estopped);
status_builder.add_intake_roller_state(intake_roller_state);
status_builder.add_intake_pivot_state(intake_pivot_status_offset);
status_builder.add_transfer_roller_state(transfer_roller_state);
+ status_builder.add_climber_state(climber_status_offset);
(void)status->Send(status_builder.Finish());
}
diff --git a/y2024/control_loops/superstructure/superstructure.h b/y2024/control_loops/superstructure/superstructure.h
index 67a8328..88db2e2 100644
--- a/y2024/control_loops/superstructure/superstructure.h
+++ b/y2024/control_loops/superstructure/superstructure.h
@@ -34,6 +34,10 @@
return intake_pivot_;
}
+ inline const PotAndAbsoluteEncoderSubsystem &climber() const {
+ return climber_;
+ }
+
double robot_velocity() const;
protected:
@@ -53,7 +57,7 @@
TransferRollerGoal transfer_goal_;
PotAndAbsoluteEncoderSubsystem intake_pivot_;
-
+ PotAndAbsoluteEncoderSubsystem climber_;
DISALLOW_COPY_AND_ASSIGN(Superstructure);
};
diff --git a/y2024/control_loops/superstructure/superstructure_can_position.fbs b/y2024/control_loops/superstructure/superstructure_can_position.fbs
index f9f4ca9..6cd3f1e 100644
--- a/y2024/control_loops/superstructure/superstructure_can_position.fbs
+++ b/y2024/control_loops/superstructure/superstructure_can_position.fbs
@@ -20,6 +20,9 @@
// CAN Position of the transfer roller falcon
transfer_roller:frc971.control_loops.CANTalonFX (id: 4);
+
+ // CAN Position of the climber falcon
+ climber:frc971.control_loops.CANTalonFX (id: 5);
}
root_type CANPosition;
\ No newline at end of file
diff --git a/y2024/control_loops/superstructure/superstructure_goal.fbs b/y2024/control_loops/superstructure/superstructure_goal.fbs
index 0af8ca3..bb7b706 100644
--- a/y2024/control_loops/superstructure/superstructure_goal.fbs
+++ b/y2024/control_loops/superstructure/superstructure_goal.fbs
@@ -25,13 +25,21 @@
TRANSFER_OUT = 2,
}
+// Represents goal for climber
+// FULL_EXTEND is for fully extending the climber
+// HALF_EXTEND is for partially extending the climber
+// RETRACT is for retracting the climber
+enum ClimberGoal : ubyte {
+ FULL_EXTEND = 0,
+ HALF_EXTEND = 1,
+ RETRACT = 2,
+}
+
table Goal {
intake_roller_goal:IntakeRollerGoal (id: 0);
intake_pivot_goal:IntakePivotGoal (id: 1);
-
catapult_goal:frc971.control_loops.catapult.CatapultGoal (id: 2);
-
transfer_roller_goal:TransferRollerGoal (id: 3);
+ climber_goal:ClimberGoal (id: 4);
}
-
root_type Goal;
diff --git a/y2024/control_loops/superstructure/superstructure_lib_test.cc b/y2024/control_loops/superstructure/superstructure_lib_test.cc
index 26e75e4..8020a4d 100644
--- a/y2024/control_loops/superstructure/superstructure_lib_test.cc
+++ b/y2024/control_loops/superstructure/superstructure_lib_test.cc
@@ -12,6 +12,7 @@
#include "frc971/zeroing/absolute_encoder.h"
#include "y2024/constants/simulated_constants_sender.h"
#include "y2024/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "y2024/control_loops/superstructure/climber/climber_plant.h"
#include "y2024/control_loops/superstructure/intake_pivot/intake_pivot_plant.h"
#include "y2024/control_loops/superstructure/superstructure.h"
@@ -56,13 +57,13 @@
new CappedTestPlant(intake_pivot::MakeIntakePivotPlant()),
PositionSensorSimulator(simulated_robot_constants->robot()
->intake_constants()
- ->intake_pivot_zero()
+ ->zeroing_constants()
->one_revolution_distance()),
{.subsystem_params =
{simulated_robot_constants->common()->intake_pivot(),
simulated_robot_constants->robot()
->intake_constants()
- ->intake_pivot_zero()},
+ ->zeroing_constants()},
.potentiometer_offset = simulated_robot_constants->robot()
->intake_constants()
->potentiometer_offset()},
@@ -70,13 +71,37 @@
simulated_robot_constants->common()->intake_pivot()->range()),
simulated_robot_constants->robot()
->intake_constants()
- ->intake_pivot_zero()
+ ->zeroing_constants()
->measured_absolute_position(),
- dt_) {
+ dt_),
+ climber_(new CappedTestPlant(climber::MakeClimberPlant()),
+ PositionSensorSimulator(simulated_robot_constants->robot()
+ ->climber_constants()
+ ->zeroing_constants()
+ ->one_revolution_distance()),
+ {.subsystem_params =
+ {simulated_robot_constants->common()->climber(),
+ simulated_robot_constants->robot()
+ ->climber_constants()
+ ->zeroing_constants()},
+ .potentiometer_offset = simulated_robot_constants->robot()
+ ->climber_constants()
+ ->potentiometer_offset()},
+ frc971::constants::Range::FromFlatbuffer(
+ simulated_robot_constants->common()->climber()->range()),
+ simulated_robot_constants->robot()
+ ->climber_constants()
+ ->zeroing_constants()
+ ->measured_absolute_position(),
+ dt_) {
intake_pivot_.InitializePosition(
frc971::constants::Range::FromFlatbuffer(
simulated_robot_constants->common()->intake_pivot()->range())
.middle());
+ climber_.InitializePosition(
+ frc971::constants::Range::FromFlatbuffer(
+ simulated_robot_constants->common()->climber()->range())
+ .middle());
phased_loop_handle_ = event_loop_->AddPhasedLoop(
[this](int) {
// Skip this the first time.
@@ -87,6 +112,9 @@
intake_pivot_.Simulate(
superstructure_output_fetcher_->intake_pivot_voltage(),
superstructure_status_fetcher_->intake_pivot_state());
+
+ climber_.Simulate(superstructure_output_fetcher_->climber_voltage(),
+ superstructure_status_fetcher_->climber_state());
}
first_ = false;
SendPositionMessage();
@@ -104,11 +132,17 @@
flatbuffers::Offset<frc971::PotAndAbsolutePosition> intake_pivot_offset =
intake_pivot_.encoder()->GetSensorValues(&intake_pivot_builder);
+ frc971::PotAndAbsolutePosition::Builder climber_builder =
+ builder.MakeBuilder<frc971::PotAndAbsolutePosition>();
+ flatbuffers::Offset<frc971::PotAndAbsolutePosition> climber_offset =
+ climber_.encoder()->GetSensorValues(&climber_builder);
+
Position::Builder position_builder = builder.MakeBuilder<Position>();
position_builder.add_transfer_beambreak(transfer_beambreak_);
position_builder.add_intake_pivot(intake_pivot_offset);
+ position_builder.add_climber(climber_offset);
CHECK_EQ(builder.Send(position_builder.Finish()),
aos::RawSender::Error::kOk);
}
@@ -119,6 +153,8 @@
PotAndAbsoluteEncoderSimulator *intake_pivot() { return &intake_pivot_; }
+ PotAndAbsoluteEncoderSimulator *climber() { return &climber_; }
+
private:
::aos::EventLoop *event_loop_;
const chrono::nanoseconds dt_;
@@ -131,6 +167,8 @@
bool transfer_beambreak_;
PotAndAbsoluteEncoderSimulator intake_pivot_;
+ PotAndAbsoluteEncoderSimulator climber_;
+
bool first_ = true;
};
@@ -211,6 +249,27 @@
IntakeRollerState::NONE) {
EXPECT_EQ(superstructure_output_fetcher_->intake_roller_voltage(), 0.0);
}
+
+ if (superstructure_goal_fetcher_->has_climber_goal()) {
+ double set_point =
+ simulated_robot_constants_->common()->climber_set_points()->retract();
+
+ if (superstructure_goal_fetcher_->climber_goal() ==
+ ClimberGoal::FULL_EXTEND) {
+ set_point = simulated_robot_constants_->common()
+ ->climber_set_points()
+ ->full_extend();
+ } else if (superstructure_goal_fetcher_->climber_goal() ==
+ ClimberGoal::HALF_EXTEND) {
+ set_point = simulated_robot_constants_->common()
+ ->climber_set_points()
+ ->half_extend();
+ }
+
+ EXPECT_NEAR(set_point,
+ superstructure_status_fetcher_->climber_state()->position(),
+ 0.001);
+ }
}
void CheckIfZeroed() {
@@ -294,12 +353,11 @@
auto builder = superstructure_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
-
goal_builder.add_intake_pivot_goal(IntakePivotGoal::RETRACTED);
+ goal_builder.add_climber_goal(ClimberGoal::RETRACT);
ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
}
-
RunFor(chrono::seconds(10));
EXPECT_TRUE(superstructure_output_fetcher_.Fetch());
@@ -314,13 +372,17 @@
frc971::constants::Range::FromFlatbuffer(
simulated_robot_constants_->common()->intake_pivot()->range())
.middle());
+ superstructure_plant_.climber()->InitializePosition(
+ frc971::constants::Range::FromFlatbuffer(
+ simulated_robot_constants_->common()->climber()->range())
+ .lower);
WaitUntilZeroed();
{
auto builder = superstructure_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
-
goal_builder.add_intake_pivot_goal(IntakePivotGoal::EXTENDED);
+ goal_builder.add_climber_goal(ClimberGoal::FULL_EXTEND);
ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
}
@@ -343,8 +405,8 @@
auto builder = superstructure_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
-
goal_builder.add_intake_pivot_goal(IntakePivotGoal::EXTENDED);
+ goal_builder.add_climber_goal(ClimberGoal::FULL_EXTEND);
ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
}
@@ -357,8 +419,8 @@
auto builder = superstructure_goal_sender_.MakeBuilder();
Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
-
goal_builder.add_intake_pivot_goal(IntakePivotGoal::RETRACTED);
+ goal_builder.add_climber_goal(ClimberGoal::RETRACT);
ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
}
@@ -375,6 +437,9 @@
EXPECT_EQ(PotAndAbsoluteEncoderSubsystem::State::RUNNING,
superstructure_.intake_pivot().state());
+
+ EXPECT_EQ(PotAndAbsoluteEncoderSubsystem::State::RUNNING,
+ superstructure_.climber().state());
}
// Tests that running disabled works
@@ -383,6 +448,65 @@
CheckIfZeroed();
}
+// Tests Climber in multiple scenarios
+TEST_F(SuperstructureTest, ClimberTest) {
+ SetEnabled(true);
+ WaitUntilZeroed();
+
+ superstructure_plant_.climber()->InitializePosition(
+ frc971::constants::Range::FromFlatbuffer(
+ simulated_robot_constants_->common()->climber()->range())
+ .middle());
+
+ WaitUntilZeroed();
+
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+
+ goal_builder.add_climber_goal(ClimberGoal::FULL_EXTEND);
+
+ ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
+ }
+
+ RunFor(chrono::seconds(5));
+
+ VerifyNearGoal();
+
+ WaitUntilZeroed();
+
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+
+ goal_builder.add_climber_goal(ClimberGoal::HALF_EXTEND);
+
+ ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
+ }
+
+ RunFor(chrono::seconds(5));
+
+ VerifyNearGoal();
+
+ WaitUntilZeroed();
+
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+
+ goal_builder.add_climber_goal(ClimberGoal::RETRACT);
+
+ ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
+ }
+
+ RunFor(chrono::seconds(5));
+
+ VerifyNearGoal();
+}
+
// Tests intake and transfer in multiple scenarios
TEST_F(SuperstructureTest, IntakeGoal) {
SetEnabled(true);
diff --git a/y2024/control_loops/superstructure/superstructure_output.fbs b/y2024/control_loops/superstructure/superstructure_output.fbs
index 976707d..a429976 100644
--- a/y2024/control_loops/superstructure/superstructure_output.fbs
+++ b/y2024/control_loops/superstructure/superstructure_output.fbs
@@ -20,6 +20,11 @@
// Positive voltage is for transfering in
// Negative voltage is for transfering out
transfer_roller_voltage:double (id: 5);
+
+ // Voltage of climber
+ // Positive voltage is for climber up
+ // Negative voltage is for climber down
+ climber_voltage:double (id: 6);
}
root_type Output;
diff --git a/y2024/control_loops/superstructure/superstructure_position.fbs b/y2024/control_loops/superstructure/superstructure_position.fbs
index da867a9..cd12da0 100644
--- a/y2024/control_loops/superstructure/superstructure_position.fbs
+++ b/y2024/control_loops/superstructure/superstructure_position.fbs
@@ -18,6 +18,10 @@
// True means there is a game piece in the transfer.
transfer_beambreak:bool (id: 4);
+
+ // Values of the encoder and potentiometer at the climber.
+ // Zero is fully retracted, positive is extended upward.
+ climber:frc971.PotAndAbsolutePosition (id: 5);
}
root_type Position;
diff --git a/y2024/control_loops/superstructure/superstructure_status.fbs b/y2024/control_loops/superstructure/superstructure_status.fbs
index 9084361..cd727ac 100644
--- a/y2024/control_loops/superstructure/superstructure_status.fbs
+++ b/y2024/control_loops/superstructure/superstructure_status.fbs
@@ -43,6 +43,9 @@
// State of transfer rollers
transfer_roller_state:TransferRollerState (id: 4);
+
+ // Estimated angle and angular velocitiy of the climber.
+ climber_state:frc971.control_loops.PotAndAbsoluteEncoderProfiledJointStatus (id: 5);
}
root_type Status;
diff --git a/y2024/vision/BUILD b/y2024/vision/BUILD
index 795d9fa..4b515cf 100644
--- a/y2024/vision/BUILD
+++ b/y2024/vision/BUILD
@@ -58,3 +58,60 @@
"@com_github_nvidia_cuco//:cuco",
],
)
+
+cc_binary(
+ name = "viewer",
+ srcs = [
+ "viewer.cc",
+ "vision_util.cc",
+ "vision_util.h",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = [
+ "//y2024:__subpackages__",
+ ],
+ deps = [
+ "//aos:init",
+ "//aos:json_to_flatbuffer",
+ "//aos/events:shm_event_loop",
+ "//frc971/constants:constants_sender_lib",
+ "//frc971/vision:vision_fbs",
+ "//frc971/vision:vision_util_lib",
+ "//third_party:opencv",
+ "//y2024/constants:constants_fbs",
+ "@com_google_absl//absl/strings",
+ ],
+)
+
+cc_binary(
+ name = "calibrate_multi_cameras",
+ srcs = [
+ "calibrate_multi_cameras.cc",
+ "vision_util.cc",
+ "vision_util.h",
+ ],
+ data = [
+ "//y2024:aos_config",
+ "//y2024/constants:constants.json",
+ "//y2024/vision:maps",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//y2024:__subpackages__"],
+ deps = [
+ "//aos:init",
+ "//aos/events:simulated_event_loop",
+ "//aos/events/logging:log_reader",
+ "//aos/util:mcap_logger",
+ "//frc971/constants:constants_sender_lib",
+ "//frc971/control_loops:pose",
+ "//frc971/vision:calibration_fbs",
+ "//frc971/vision:charuco_lib",
+ "//frc971/vision:extrinsics_calibration",
+ "//frc971/vision:target_mapper",
+ "//frc971/vision:vision_util_lib",
+ "//third_party:opencv",
+ "//y2024/constants:constants_fbs",
+ "//y2024/constants:simulated_constants_sender",
+ "@org_tuxfamily_eigen//:eigen",
+ ],
+)
diff --git a/y2024/vision/calibrate_multi_cameras.cc b/y2024/vision/calibrate_multi_cameras.cc
new file mode 100644
index 0000000..9148217
--- /dev/null
+++ b/y2024/vision/calibrate_multi_cameras.cc
@@ -0,0 +1,709 @@
+#include <numeric>
+
+#include "aos/configuration.h"
+#include "aos/events/logging/log_reader.h"
+#include "aos/events/simulated_event_loop.h"
+#include "aos/init.h"
+#include "aos/util/mcap_logger.h"
+#include "frc971/control_loops/pose.h"
+#include "frc971/control_loops/quaternion_utils.h"
+#include "frc971/vision/calibration_generated.h"
+#include "frc971/vision/charuco_lib.h"
+#include "frc971/vision/extrinsics_calibration.h"
+#include "frc971/vision/target_mapper.h"
+#include "frc971/vision/visualize_robot.h"
+// clang-format off
+// OpenCV eigen files must be included after Eigen includes
+#include "opencv2/aruco.hpp"
+#include "opencv2/calib3d.hpp"
+#include "opencv2/core/eigen.hpp"
+#include "opencv2/features2d.hpp"
+#include "opencv2/highgui.hpp"
+#include "opencv2/highgui/highgui.hpp"
+#include "opencv2/imgproc.hpp"
+// clang-format on
+#include "frc971/constants/constants_sender_lib.h"
+#include "frc971/vision/vision_util_lib.h"
+#include "y2024/constants/simulated_constants_sender.h"
+#include "y2024/vision/vision_util.h"
+
+DEFINE_bool(alt_view, false,
+ "If true, show visualization from field level, rather than above");
+DEFINE_string(config, "",
+ "If set, override the log's config file with this one.");
+DEFINE_string(constants_path, "y2023/constants/constants.json",
+ "Path to the constant file");
+DEFINE_double(max_pose_error, 5e-5,
+ "Throw out target poses with a higher pose error than this");
+DEFINE_double(
+ max_pose_error_ratio, 0.4,
+ "Throw out target poses with a higher pose error ratio than this");
+DEFINE_string(output_folder, "/tmp",
+ "Directory in which to store the updated calibration files");
+DEFINE_string(target_type, "charuco_diamond",
+ "Type of target being used [aruco, charuco, charuco_diamond]");
+DEFINE_int32(team_number, 0,
+ "Required: Use the calibration for a node with this team number");
+DEFINE_bool(use_full_logs, false,
+ "If true, extract data from logs with images");
+DEFINE_uint64(
+ wait_key, 1,
+ "Time in ms to wait between images (0 to wait indefinitely until click)");
+
+DECLARE_int32(min_target_id);
+DECLARE_int32(max_target_id);
+
+// Calibrate extrinsic relationship between cameras using two targets
+// seen jointly between cameras. Uses two types of information: 1)
+// when a single camera sees two targets, we estimate the pose between
+// targets, and 2) when two separate cameras each see a target, we can
+// use the pose between targets to estimate the pose between cameras.
+
+// We then create the extrinsics for the robot by starting with the
+// given extrinsic for camera 1 (between imu/robot and camera frames)
+// and then map each subsequent camera based on the data collected and
+// the extrinsic poses computed here.
+
+// TODO<Jim>: Not currently using estimate from pi1->pi4-- should do full
+// estimation, and probably also include camera->imu extrinsics from all
+// cameras, not just pi1
+
+namespace y2023::vision {
+using frc971::vision::DataAdapter;
+using frc971::vision::ImageCallback;
+using frc971::vision::PoseUtils;
+using frc971::vision::TargetMap;
+using frc971::vision::TargetMapper;
+using frc971::vision::VisualizeRobot;
+namespace calibration = frc971::vision::calibration;
+
+static constexpr double kImagePeriodMs =
+ 1.0 / 30.0 * 1000.0; // Image capture period in ms
+
+// Change reference frame from camera to robot
+Eigen::Affine3d CameraToRobotDetection(Eigen::Affine3d H_camera_target,
+ Eigen::Affine3d extrinsics) {
+ const Eigen::Affine3d H_robot_camera = extrinsics;
+ const Eigen::Affine3d H_robot_target = H_robot_camera * H_camera_target;
+ return H_robot_target;
+}
+
+struct TimestampedPiDetection {
+ aos::distributed_clock::time_point time;
+ // Pose of target relative to robot
+ Eigen::Affine3d H_camera_target;
+ // name of pi
+ std::string pi_name;
+ int board_id;
+};
+
+TimestampedPiDetection last_observation;
+std::vector<std::pair<TimestampedPiDetection, TimestampedPiDetection>>
+ detection_list;
+std::vector<TimestampedPiDetection> two_board_extrinsics_list;
+VisualizeRobot vis_robot_;
+
+// TODO<jim>: Implement variance calcs
+Eigen::Affine3d ComputeAveragePose(
+ std::vector<Eigen::Vector3d> &translation_list,
+ std::vector<Eigen::Vector4d> &rotation_list,
+ Eigen::Vector3d *translation_variance = nullptr,
+ Eigen::Vector3d *rotation_variance = nullptr) {
+ Eigen::Vector3d avg_translation =
+ std::accumulate(translation_list.begin(), translation_list.end(),
+ Eigen::Vector3d{0, 0, 0}) /
+ translation_list.size();
+
+ // TODO<Jim>: Use QuaternionMean from quaternion_utils.cc (but this
+ // requires a fixed number of quaternions to be averaged
+ Eigen::Vector4d avg_rotation =
+ std::accumulate(rotation_list.begin(), rotation_list.end(),
+ Eigen::Vector4d{0, 0, 0, 0}) /
+ rotation_list.size();
+ // Normalize, so it's a valid quaternion
+ avg_rotation = avg_rotation / avg_rotation.norm();
+ Eigen::Quaterniond avg_rotation_q{avg_rotation[0], avg_rotation[1],
+ avg_rotation[2], avg_rotation[3]};
+ Eigen::Translation3d translation(avg_translation);
+ Eigen::Affine3d return_pose = translation * avg_rotation_q;
+ if (translation_variance != nullptr) {
+ *translation_variance = Eigen::Vector3d();
+ }
+ if (rotation_variance != nullptr) {
+ LOG(INFO) << *rotation_variance;
+ }
+
+ return return_pose;
+}
+
+Eigen::Affine3d ComputeAveragePose(
+ std::vector<Eigen::Affine3d> &pose_list,
+ Eigen::Vector3d *translation_variance = nullptr,
+ Eigen::Vector3d *rotation_variance = nullptr) {
+ std::vector<Eigen::Vector3d> translation_list;
+ std::vector<Eigen::Vector4d> rotation_list;
+
+ for (Eigen::Affine3d pose : pose_list) {
+ translation_list.push_back(pose.translation());
+ Eigen::Quaterniond quat(pose.rotation().matrix());
+ rotation_list.push_back(
+ Eigen::Vector4d(quat.w(), quat.x(), quat.y(), quat.z()));
+ }
+
+ return ComputeAveragePose(translation_list, rotation_list,
+ translation_variance, rotation_variance);
+}
+
+Eigen::Affine3d ComputeAveragePose(
+ std::vector<TimestampedPiDetection> &pose_list,
+ Eigen::Vector3d *translation_variance = nullptr,
+ Eigen::Vector3d *rotation_variance = nullptr) {
+ std::vector<Eigen::Vector3d> translation_list;
+ std::vector<Eigen::Vector4d> rotation_list;
+
+ for (TimestampedPiDetection pose : pose_list) {
+ translation_list.push_back(pose.H_camera_target.translation());
+ Eigen::Quaterniond quat(pose.H_camera_target.rotation().matrix());
+ rotation_list.push_back(
+ Eigen::Vector4d(quat.w(), quat.x(), quat.y(), quat.z()));
+ }
+ return ComputeAveragePose(translation_list, rotation_list,
+ translation_variance, rotation_variance);
+}
+
+void HandlePoses(cv::Mat rgb_image,
+ std::vector<TargetMapper::TargetPose> target_poses,
+ aos::distributed_clock::time_point distributed_eof,
+ std::string node_name) {
+ // This is used to transform points for visualization
+ // Assumes targets are aligned with x->right, y->up, z->out of board
+ Eigen::Affine3d H_world_board;
+ H_world_board = Eigen::Translation3d::Identity() *
+ Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
+ if (FLAGS_alt_view) {
+ // Don't rotate -- this is like viewing from the side
+ H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0);
+ }
+
+ bool draw_vis = false;
+ CHECK_LE(target_poses.size(), 2u)
+ << "Can't handle more than two tags in field of view";
+ if (target_poses.size() == 2) {
+ draw_vis = true;
+ VLOG(1) << "Saw two boards in same view from " << node_name;
+ int from_index = 0;
+ int to_index = 1;
+ // Handle when we see two boards at once
+ // We'll store them referenced to the lower id board
+ if (target_poses[from_index].id > target_poses[to_index].id) {
+ std::swap<int>(from_index, to_index);
+ }
+
+ // Create "from" (A) and "to" (B) transforms
+ Eigen::Affine3d H_camera_boardA =
+ PoseUtils::Pose3dToAffine3d(target_poses[from_index].pose);
+ Eigen::Affine3d H_camera_boardB =
+ PoseUtils::Pose3dToAffine3d(target_poses[to_index].pose);
+
+ Eigen::Affine3d H_boardA_boardB =
+ H_camera_boardA.inverse() * H_camera_boardB;
+
+ TimestampedPiDetection boardA_boardB{
+ .time = distributed_eof,
+ .H_camera_target = H_boardA_boardB,
+ .pi_name = node_name,
+ .board_id = target_poses[from_index].id};
+
+ VLOG(1) << "Map from board " << from_index << " to " << to_index << " is\n"
+ << H_boardA_boardB.matrix();
+ // Store this observation of the transform between two boards
+ two_board_extrinsics_list.push_back(boardA_boardB);
+
+ if (FLAGS_visualize) {
+ vis_robot_.DrawFrameAxes(
+ H_world_board,
+ std::string("board ") + std::to_string(target_poses[from_index].id),
+ cv::Scalar(0, 255, 0));
+ vis_robot_.DrawFrameAxes(
+ H_world_board * boardA_boardB.H_camera_target,
+ std::string("board ") + std::to_string(target_poses[to_index].id),
+ cv::Scalar(255, 0, 0));
+ VLOG(2) << "Detection map from camera " << node_name << " to board "
+ << target_poses[from_index].id << " is\n"
+ << H_camera_boardA.matrix() << "\n and inverse is\n"
+ << H_camera_boardA.inverse().matrix()
+ << "\n and with world to board rotation is\n"
+ << H_world_board * H_camera_boardA.inverse().matrix();
+ vis_robot_.DrawRobotOutline(H_world_board * H_camera_boardA.inverse(),
+ node_name, cv::Scalar(0, 0, 255));
+ }
+ } else if (target_poses.size() == 1) {
+ VLOG(1) << "Saw single board in camera " << node_name;
+ Eigen::Affine3d H_camera2_board2 =
+ PoseUtils::Pose3dToAffine3d(target_poses[0].pose);
+ TimestampedPiDetection new_observation{.time = distributed_eof,
+ .H_camera_target = H_camera2_board2,
+ .pi_name = node_name,
+ .board_id = target_poses[0].id};
+
+ // Only take two observations if they're within half an image cycle of each
+ // other (i.e., as close in time as possible)
+ if (std::abs((distributed_eof - last_observation.time).count()) <
+ kImagePeriodMs / 2.0 * 1000000.0) {
+ // Sort by pi numbering, since this is how we will handle them
+ std::pair<TimestampedPiDetection, TimestampedPiDetection> new_pair;
+ if (last_observation.pi_name < new_observation.pi_name) {
+ new_pair = std::pair(last_observation, new_observation);
+ } else if (last_observation.pi_name > new_observation.pi_name) {
+ new_pair = std::pair(new_observation, last_observation);
+ } else {
+ LOG(WARNING) << "Got 2 observations in a row from same pi. Probably "
+ "not too much of an issue???";
+ }
+ detection_list.push_back(new_pair);
+
+ // This bit is just for visualization and checking purposes-- use the
+ // last two-board observation to figure out the current estimate
+ // between the two cameras
+ if (FLAGS_visualize && two_board_extrinsics_list.size() > 0) {
+ draw_vis = true;
+ TimestampedPiDetection &last_two_board_ext =
+ two_board_extrinsics_list[two_board_extrinsics_list.size() - 1];
+ Eigen::Affine3d &H_boardA_boardB = last_two_board_ext.H_camera_target;
+ int boardA_boardB_id = last_two_board_ext.board_id;
+
+ TimestampedPiDetection camera1_boardA = new_pair.first;
+ TimestampedPiDetection camera2_boardB = new_pair.second;
+ // If camera1_boardA doesn't point to the first target, then swap
+ // these two
+ if (camera1_boardA.board_id != boardA_boardB_id) {
+ camera1_boardA = new_pair.second;
+ camera2_boardB = new_pair.first;
+ }
+ VLOG(1) << "Camera " << camera1_boardA.pi_name << " seeing board "
+ << camera1_boardA.board_id << " and camera "
+ << camera2_boardB.pi_name << " seeing board "
+ << camera2_boardB.board_id;
+
+ vis_robot_.DrawRobotOutline(
+ H_world_board * camera1_boardA.H_camera_target.inverse(),
+ camera1_boardA.pi_name, cv::Scalar(0, 0, 255));
+ vis_robot_.DrawRobotOutline(
+ H_world_board * H_boardA_boardB *
+ camera2_boardB.H_camera_target.inverse(),
+ camera2_boardB.pi_name, cv::Scalar(128, 128, 0));
+ vis_robot_.DrawFrameAxes(
+ H_world_board,
+ std::string("Board ") + std::to_string(last_two_board_ext.board_id),
+ cv::Scalar(0, 255, 0));
+ vis_robot_.DrawFrameAxes(H_world_board * H_boardA_boardB, "Board B",
+ cv::Scalar(255, 0, 0));
+ }
+ VLOG(1) << "Storing observation between " << new_pair.first.pi_name
+ << ", target " << new_pair.first.board_id << " and "
+ << new_pair.second.pi_name << ", target "
+ << new_pair.second.board_id;
+ } else {
+ VLOG(2) << "Storing observation for " << node_name << " at time "
+ << distributed_eof;
+ last_observation = new_observation;
+ }
+ }
+
+ if (FLAGS_visualize) {
+ if (!rgb_image.empty()) {
+ std::string image_name = node_name + " Image";
+ cv::Mat rgb_small;
+ cv::resize(rgb_image, rgb_small, cv::Size(), 0.5, 0.5);
+ cv::imshow(image_name, rgb_small);
+ cv::waitKey(FLAGS_wait_key);
+ }
+
+ if (draw_vis) {
+ cv::imshow("View", vis_robot_.image_);
+ cv::waitKey(FLAGS_wait_key);
+ vis_robot_.ClearImage();
+ }
+ }
+}
+
+void HandleTargetMap(const TargetMap &map,
+ aos::distributed_clock::time_point distributed_eof,
+ std::string node_name) {
+ VLOG(1) << "Got april tag map call from node " << node_name;
+ // Create empty RGB image in this case
+ cv::Mat rgb_image;
+ std::vector<TargetMapper::TargetPose> target_poses;
+
+ for (const auto *target_pose_fbs : *map.target_poses()) {
+ // Skip detections with invalid ids
+ if (static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) <
+ FLAGS_min_target_id ||
+ static_cast<TargetMapper::TargetId>(target_pose_fbs->id()) >
+ FLAGS_max_target_id) {
+ LOG(INFO) << "Skipping tag with invalid id of " << target_pose_fbs->id();
+ continue;
+ }
+
+ // Skip detections with high pose errors
+ if (target_pose_fbs->pose_error() > FLAGS_max_pose_error) {
+ LOG(INFO) << "Skipping tag " << target_pose_fbs->id()
+ << " due to pose error of " << target_pose_fbs->pose_error();
+ continue;
+ }
+ // Skip detections with high pose error ratios
+ if (target_pose_fbs->pose_error_ratio() > FLAGS_max_pose_error_ratio) {
+ LOG(INFO) << "Skipping tag " << target_pose_fbs->id()
+ << " due to pose error ratio of "
+ << target_pose_fbs->pose_error_ratio();
+ continue;
+ }
+
+ const TargetMapper::TargetPose target_pose =
+ PoseUtils::TargetPoseFromFbs(*target_pose_fbs);
+
+ target_poses.emplace_back(target_pose);
+
+ Eigen::Affine3d H_camera_target =
+ PoseUtils::Pose3dToAffine3d(target_pose.pose);
+ VLOG(2) << node_name << " saw target " << target_pose.id
+ << " from TargetMap at timestamp " << distributed_eof
+ << " with pose = " << H_camera_target.matrix();
+ }
+ HandlePoses(rgb_image, target_poses, distributed_eof, node_name);
+}
+
+void HandleImage(aos::EventLoop *event_loop, cv::Mat rgb_image,
+ const aos::monotonic_clock::time_point eof,
+ aos::distributed_clock::time_point distributed_eof,
+ frc971::vision::CharucoExtractor &charuco_extractor,
+ std::string node_name) {
+ std::vector<cv::Vec4i> charuco_ids;
+ std::vector<std::vector<cv::Point2f>> charuco_corners;
+ bool valid = false;
+ std::vector<Eigen::Vector3d> rvecs_eigen;
+ std::vector<Eigen::Vector3d> tvecs_eigen;
+ // Why eof vs. distributed_eof?
+ charuco_extractor.ProcessImage(rgb_image, eof, event_loop->monotonic_now(),
+ charuco_ids, charuco_corners, valid,
+ rvecs_eigen, tvecs_eigen);
+ if (rvecs_eigen.size() > 0 && !valid) {
+ LOG(WARNING) << "Charuco extractor returned not valid";
+ return;
+ }
+
+ std::vector<TargetMapper::TargetPose> target_poses;
+ for (size_t i = 0; i < tvecs_eigen.size(); i++) {
+ Eigen::Quaterniond rotation(
+ frc971::controls::ToQuaternionFromRotationVector(rvecs_eigen[i]));
+ ceres::examples::Pose3d pose(Eigen::Vector3d(tvecs_eigen[i]), rotation);
+ TargetMapper::TargetPose target_pose{charuco_ids[i][0], pose};
+ target_poses.emplace_back(target_pose);
+
+ Eigen::Affine3d H_camera_target = PoseUtils::Pose3dToAffine3d(pose);
+ VLOG(2) << node_name << " saw target " << target_pose.id
+ << " from image at timestamp " << distributed_eof
+ << " with pose = " << H_camera_target.matrix();
+ }
+ HandlePoses(rgb_image, target_poses, distributed_eof, node_name);
+}
+
+void ExtrinsicsMain(int argc, char *argv[]) {
+ vis_robot_ = VisualizeRobot(cv::Size(1000, 1000));
+ vis_robot_.ClearImage();
+ const double kFocalLength = 1000.0;
+ const int kImageWidth = 1000;
+ vis_robot_.SetDefaultViewpoint(kImageWidth, kFocalLength);
+
+ std::optional<aos::FlatbufferDetachedBuffer<aos::Configuration>> config =
+ (FLAGS_config.empty()
+ ? std::nullopt
+ : std::make_optional(aos::configuration::ReadConfig(FLAGS_config)));
+
+ // open logfiles
+ aos::logger::LogReader reader(
+ aos::logger::SortParts(aos::logger::FindLogs(argc, argv)),
+ config.has_value() ? &config->message() : nullptr);
+
+ constexpr size_t kNumPis = 4;
+ for (size_t i = 1; i <= kNumPis; i++) {
+ reader.RemapLoggedChannel(absl::StrFormat("/pi%u/constants", i),
+ "y2023.Constants");
+ }
+
+ reader.RemapLoggedChannel("/imu/constants", "y2023.Constants");
+ reader.RemapLoggedChannel("/logger/constants", "y2023.Constants");
+ reader.RemapLoggedChannel("/roborio/constants", "y2023.Constants");
+ reader.Register();
+
+ y2024::SendSimulationConstants(reader.event_loop_factory(), FLAGS_team_number,
+ FLAGS_constants_path);
+
+ VLOG(1) << "Using target type " << FLAGS_target_type;
+ std::vector<std::string> node_list;
+ node_list.push_back("pi1");
+ node_list.push_back("pi2");
+ node_list.push_back("pi3");
+ node_list.push_back("pi4");
+ std::vector<const calibration::CameraCalibration *> calibration_list;
+
+ std::vector<std::unique_ptr<aos::EventLoop>> detection_event_loops;
+ std::vector<frc971::vision::CharucoExtractor *> charuco_extractors;
+ std::vector<frc971::vision::ImageCallback *> image_callbacks;
+ std::vector<Eigen::Affine3d> default_extrinsics;
+
+ for (uint i = 0; i < node_list.size(); i++) {
+ std::string node = node_list[i];
+ const aos::Node *pi =
+ aos::configuration::GetNode(reader.configuration(), node.c_str());
+
+ detection_event_loops.emplace_back(
+ reader.event_loop_factory()->MakeEventLoop(
+ (node + "_detection").c_str(), pi));
+
+ frc971::constants::ConstantsFetcher<y2024::Constants> constants_fetcher(
+ detection_event_loops.back().get());
+
+ const calibration::CameraCalibration *calibration =
+ y2024::vision::FindCameraCalibration(constants_fetcher.constants(),
+ node);
+ calibration_list.push_back(calibration);
+
+ frc971::vision::TargetType target_type =
+ frc971::vision::TargetTypeFromString(FLAGS_target_type);
+ frc971::vision::CharucoExtractor *charuco_ext =
+ new frc971::vision::CharucoExtractor(calibration, target_type);
+ charuco_extractors.emplace_back(charuco_ext);
+
+ cv::Mat extrinsics_cv =
+ frc971::vision::CameraExtrinsics(calibration).value();
+ Eigen::Matrix4d extrinsics_matrix;
+ cv::cv2eigen(extrinsics_cv, extrinsics_matrix);
+ const auto ext_H_robot_pi = Eigen::Affine3d(extrinsics_matrix);
+ default_extrinsics.emplace_back(ext_H_robot_pi);
+
+ VLOG(1) << "Got extrinsics for " << node << " as\n"
+ << default_extrinsics.back().matrix();
+
+ if (FLAGS_use_full_logs) {
+ LOG(INFO) << "Set up image callback for node " << node_list[i];
+ frc971::vision::ImageCallback *image_callback =
+ new frc971::vision::ImageCallback(
+ detection_event_loops[i].get(), "/" + node_list[i] + "/camera",
+ [&reader, &charuco_extractors, &detection_event_loops, &node_list,
+ i](cv::Mat rgb_image,
+ const aos::monotonic_clock::time_point eof) {
+ aos::distributed_clock::time_point pi_distributed_time =
+ reader.event_loop_factory()
+ ->GetNodeEventLoopFactory(
+ detection_event_loops[i].get()->node())
+ ->ToDistributedClock(eof);
+ HandleImage(detection_event_loops[i].get(), rgb_image, eof,
+ pi_distributed_time, *charuco_extractors[i],
+ node_list[i]);
+ });
+
+ image_callbacks.emplace_back(image_callback);
+ } else {
+ detection_event_loops[i]->MakeWatcher(
+ "/camera", [&reader, &detection_event_loops, &node_list,
+ i](const TargetMap &map) {
+ aos::distributed_clock::time_point pi_distributed_time =
+ reader.event_loop_factory()
+ ->GetNodeEventLoopFactory(detection_event_loops[i]->node())
+ ->ToDistributedClock(aos::monotonic_clock::time_point(
+ aos::monotonic_clock::duration(
+ map.monotonic_timestamp_ns())));
+
+ HandleTargetMap(map, pi_distributed_time, node_list[i]);
+ });
+ LOG(INFO) << "Created watcher for using the detection event loop for "
+ << node_list[i] << " with i = " << i << " and size "
+ << detection_event_loops.size();
+ }
+ }
+
+ reader.event_loop_factory()->Run();
+
+ // Do quick check to see what averaged two-board pose for each pi is
+ // individually
+ CHECK_GT(two_board_extrinsics_list.size(), 0u)
+ << "Must have at least one view of both boards";
+ int base_target_id = two_board_extrinsics_list[0].board_id;
+ VLOG(1) << "Base id for two_board_extrinsics_list is " << base_target_id;
+ for (auto node : node_list) {
+ std::vector<TimestampedPiDetection> pose_list;
+ for (auto ext : two_board_extrinsics_list) {
+ CHECK_EQ(base_target_id, ext.board_id)
+ << " All boards should have same reference id";
+ if (ext.pi_name == node) {
+ pose_list.push_back(ext);
+ }
+ }
+ Eigen::Affine3d avg_pose_from_pi = ComputeAveragePose(pose_list);
+ VLOG(1) << "Estimate from " << node << " with " << pose_list.size()
+ << " observations is:\n"
+ << avg_pose_from_pi.matrix();
+ }
+ Eigen::Affine3d H_boardA_boardB_avg =
+ ComputeAveragePose(two_board_extrinsics_list);
+ // TODO: Should probably do some outlier rejection
+ LOG(INFO) << "Estimate of two board pose using all nodes with "
+ << two_board_extrinsics_list.size() << " observations is:\n"
+ << H_boardA_boardB_avg.matrix() << "\n";
+
+ // Next, compute the relative camera poses
+ LOG(INFO) << "Got " << detection_list.size() << " extrinsic observations";
+ std::vector<Eigen::Affine3d> H_camera1_camera2_list;
+ std::vector<Eigen::Affine3d> updated_extrinsics;
+ // Use the first node's extrinsics as our base, and fix from there
+ updated_extrinsics.push_back(default_extrinsics[0]);
+ LOG(INFO) << "Default extrinsic for node " << node_list[0] << " is "
+ << default_extrinsics[0].matrix();
+ for (uint i = 0; i < node_list.size() - 1; i++) {
+ H_camera1_camera2_list.clear();
+ // Go through the list, and find successive pairs of cameras
+ for (auto [pose1, pose2] : detection_list) {
+ if ((pose1.pi_name == node_list[i]) &&
+ (pose2.pi_name == node_list[i + 1])) {
+ Eigen::Affine3d H_camera1_boardA = pose1.H_camera_target;
+ // If pose1 isn't referenced to base_target_id, correct that
+ if (pose1.board_id != base_target_id) {
+ // pose1.H_camera_target references boardB, so map back to boardA
+ H_camera1_boardA =
+ pose1.H_camera_target * H_boardA_boardB_avg.inverse();
+ }
+
+ // Now, get the camera2->boardA map (notice it's boardA, same as
+ // camera1, so we can compute the difference based both on boardA)
+ Eigen::Affine3d H_camera2_boardA = pose2.H_camera_target;
+ // If pose2 isn't referenced to boardA (base_target_id), correct
+ // that
+ if (pose2.board_id != base_target_id) {
+ // pose2.H_camera_target references boardB, so map back to boardA
+ H_camera2_boardA =
+ pose2.H_camera_target * H_boardA_boardB_avg.inverse();
+ }
+
+ // Compute camera1->camera2 map
+ Eigen::Affine3d H_camera1_camera2 =
+ H_camera1_boardA * H_camera2_boardA.inverse();
+ H_camera1_camera2_list.push_back(H_camera1_camera2);
+ VLOG(1) << "Map from camera " << pose1.pi_name << " and tag "
+ << pose1.board_id << " with observation: \n"
+ << pose1.H_camera_target.matrix() << "\n to camera "
+ << pose2.pi_name << " and tag " << pose2.board_id
+ << " with observation: \n"
+ << pose2.H_camera_target.matrix() << "\ngot map as\n"
+ << H_camera1_camera2.matrix();
+
+ Eigen::Affine3d H_world_board;
+ H_world_board = Eigen::Translation3d::Identity() *
+ Eigen::AngleAxisd(M_PI / 2.0, Eigen::Vector3d::UnitX());
+ if (FLAGS_alt_view) {
+ H_world_board = Eigen::Translation3d(0.0, 0.0, 3.0);
+ }
+
+ VLOG(2) << "Camera1 " << pose1.pi_name << " in world frame is \n"
+ << (H_world_board * H_camera1_boardA.inverse()).matrix();
+ VLOG(2) << "Camera2 " << pose2.pi_name << " in world frame is \n"
+ << (H_world_board * H_camera2_boardA.inverse()).matrix();
+ }
+ }
+ // TODO<Jim>: If we don't get any matches, we could just use default
+ // extrinsics
+ CHECK(H_camera1_camera2_list.size() > 0)
+ << "Failed with zero poses for node " << node_list[i];
+ if (H_camera1_camera2_list.size() > 0) {
+ Eigen::Affine3d H_camera1_camera2_avg =
+ ComputeAveragePose(H_camera1_camera2_list);
+ LOG(INFO) << "From " << node_list[i] << " to " << node_list[i + 1]
+ << " found " << H_camera1_camera2_list.size()
+ << " observations, and the average pose is:\n"
+ << H_camera1_camera2_avg.matrix();
+ Eigen::Affine3d H_camera1_camera2_default =
+ default_extrinsics[i].inverse() * default_extrinsics[i + 1];
+ LOG(INFO) << "Compare this to that from default values:\n"
+ << H_camera1_camera2_default.matrix();
+ Eigen::Affine3d H_camera1_camera2_diff =
+ H_camera1_camera2_avg * H_camera1_camera2_default.inverse();
+ LOG(INFO)
+ << "Difference between averaged and default delta poses "
+ "has |T| = "
+ << H_camera1_camera2_diff.translation().norm() << "m and |R| = "
+ << Eigen::AngleAxisd(H_camera1_camera2_diff.rotation()).angle()
+ << " radians ("
+ << Eigen::AngleAxisd(H_camera1_camera2_diff.rotation()).angle() *
+ 180.0 / M_PI
+ << " degrees)";
+ // Next extrinsic is just previous one * avg_delta_pose
+ Eigen::Affine3d next_extrinsic =
+ updated_extrinsics.back() * H_camera1_camera2_avg;
+ updated_extrinsics.push_back(next_extrinsic);
+ LOG(INFO) << "Default Extrinsic for " << node_list[i + 1] << " is \n"
+ << default_extrinsics[i + 1].matrix();
+ LOG(INFO) << "--> Updated Extrinsic for " << node_list[i + 1] << " is \n"
+ << next_extrinsic.matrix();
+
+ // Wirte out this extrinsic to a file
+ flatbuffers::FlatBufferBuilder fbb;
+ flatbuffers::Offset<flatbuffers::Vector<float>> data_offset =
+ fbb.CreateVector(
+ frc971::vision::MatrixToVector(next_extrinsic.matrix()));
+ calibration::TransformationMatrix::Builder matrix_builder(fbb);
+ matrix_builder.add_data(data_offset);
+ flatbuffers::Offset<calibration::TransformationMatrix>
+ extrinsic_calibration_offset = matrix_builder.Finish();
+
+ calibration::CameraCalibration::Builder calibration_builder(fbb);
+ calibration_builder.add_fixed_extrinsics(extrinsic_calibration_offset);
+ const aos::realtime_clock::time_point realtime_now =
+ aos::realtime_clock::now();
+ calibration_builder.add_calibration_timestamp(
+ realtime_now.time_since_epoch().count());
+ fbb.Finish(calibration_builder.Finish());
+ aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
+ solved_extrinsics = fbb.Release();
+
+ aos::FlatbufferDetachedBuffer<
+ frc971::vision::calibration::CameraCalibration>
+ cal_copy = aos::RecursiveCopyFlatBuffer(calibration_list[i + 1]);
+ cal_copy.mutable_message()->clear_fixed_extrinsics();
+ cal_copy.mutable_message()->clear_calibration_timestamp();
+ aos::FlatbufferDetachedBuffer<calibration::CameraCalibration>
+ merged_calibration = aos::MergeFlatBuffers(
+ &cal_copy.message(), &solved_extrinsics.message());
+
+ std::stringstream time_ss;
+ time_ss << realtime_now;
+
+ // Assumes node_list name is of form "pi#" to create camera id
+ const std::string calibration_filename =
+ FLAGS_output_folder +
+ absl::StrFormat("/calibration_pi-%d-%s_cam-%s_%s.json",
+ FLAGS_team_number, node_list[i + 1].substr(2, 3),
+ calibration_list[i + 1]->camera_id()->data(),
+ time_ss.str());
+
+ LOG(INFO) << calibration_filename << " -> "
+ << aos::FlatbufferToJson(merged_calibration,
+ {.multi_line = true});
+
+ aos::util::WriteStringToFileOrDie(
+ calibration_filename,
+ aos::FlatbufferToJson(merged_calibration, {.multi_line = true}));
+ }
+ }
+
+ // Cleanup
+ for (uint i = 0; i < image_callbacks.size(); i++) {
+ delete charuco_extractors[i];
+ delete image_callbacks[i];
+ }
+}
+} // namespace y2023::vision
+
+int main(int argc, char **argv) {
+ aos::InitGoogle(&argc, &argv);
+ y2023::vision::ExtrinsicsMain(argc, argv);
+}
diff --git a/y2024/vision/foxglove_image_converter.cc b/y2024/vision/foxglove_image_converter.cc
index bfaafc8..c004ac0 100644
--- a/y2024/vision/foxglove_image_converter.cc
+++ b/y2024/vision/foxglove_image_converter.cc
@@ -3,6 +3,7 @@
#include "frc971/vision/foxglove_image_converter_lib.h"
DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
+DEFINE_string(channel, "/camera", "Input/Output channel to use.");
int main(int argc, char *argv[]) {
aos::InitGoogle(&argc, &argv);
@@ -13,7 +14,7 @@
aos::ShmEventLoop event_loop(&config.message());
frc971::vision::FoxgloveImageConverter converter(
- &event_loop, "/camera", "/camera",
+ &event_loop, FLAGS_channel, FLAGS_channel,
frc971::vision::ImageCompression::kJpeg);
event_loop.Run();
diff --git a/y2024/vision/viewer.cc b/y2024/vision/viewer.cc
new file mode 100644
index 0000000..6f83ec2
--- /dev/null
+++ b/y2024/vision/viewer.cc
@@ -0,0 +1,118 @@
+#include "absl/strings/match.h"
+#include <opencv2/calib3d.hpp>
+#include <opencv2/highgui/highgui.hpp>
+#include <opencv2/imgproc.hpp>
+
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/time/time.h"
+#include "frc971/constants/constants_sender_lib.h"
+#include "frc971/vision/vision_generated.h"
+#include "frc971/vision/vision_util_lib.h"
+#include "y2024/vision/vision_util.h"
+
+DEFINE_string(capture, "",
+ "If set, capture a single image and save it to this filename.");
+DEFINE_string(channel, "/camera", "Channel name for the image.");
+DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
+DEFINE_int32(rate, 100, "Time in milliseconds to wait between images");
+DEFINE_double(scale, 1.0, "Scale factor for images being displayed");
+
+namespace y2024::vision {
+namespace {
+
+using frc971::vision::CameraImage;
+
+bool DisplayLoop(const cv::Mat intrinsics, const cv::Mat dist_coeffs,
+ aos::Fetcher<CameraImage> *image_fetcher) {
+ const CameraImage *image;
+
+ // Read next image
+ if (!image_fetcher->Fetch()) {
+ VLOG(2) << "Couldn't fetch next image";
+ return true;
+ }
+ image = image_fetcher->get();
+ CHECK(image != nullptr) << "Couldn't read image";
+
+ // Create color image:
+ cv::Mat image_color_mat(cv::Size(image->cols(), image->rows()), CV_8UC2,
+ (void *)image->data()->data());
+ cv::Mat bgr_image(cv::Size(image->cols(), image->rows()), CV_8UC3);
+ cv::cvtColor(image_color_mat, bgr_image, cv::COLOR_YUV2BGR_YUYV);
+
+ if (!FLAGS_capture.empty()) {
+ if (absl::EndsWith(FLAGS_capture, ".bfbs")) {
+ aos::WriteFlatbufferToFile(FLAGS_capture,
+ image_fetcher->CopyFlatBuffer());
+ } else {
+ cv::imwrite(FLAGS_capture, bgr_image);
+ }
+
+ return false;
+ }
+
+ cv::Mat undistorted_image;
+ cv::undistort(bgr_image, undistorted_image, intrinsics, dist_coeffs);
+ if (FLAGS_scale != 1.0) {
+ cv::resize(undistorted_image, undistorted_image, cv::Size(), FLAGS_scale,
+ FLAGS_scale);
+ }
+ cv::imshow("Display", undistorted_image);
+
+ int keystroke = cv::waitKey(1);
+ if ((keystroke & 0xFF) == static_cast<int>('c')) {
+ // Convert again, to get clean image
+ cv::cvtColor(image_color_mat, bgr_image, cv::COLOR_YUV2BGR_YUYV);
+ std::stringstream name;
+ name << "capture-" << aos::realtime_clock::now() << ".png";
+ cv::imwrite(name.str(), bgr_image);
+ LOG(INFO) << "Saved image file: " << name.str();
+ } else if ((keystroke & 0xFF) == static_cast<int>('q')) {
+ return false;
+ }
+ return true;
+}
+
+void ViewerMain() {
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig(FLAGS_config);
+
+ frc971::constants::WaitForConstants<y2024::Constants>(&config.message());
+
+ aos::ShmEventLoop event_loop(&config.message());
+
+ frc971::constants::ConstantsFetcher<y2024::Constants> constants_fetcher(
+ &event_loop);
+ const auto *calibration_data = FindCameraCalibration(
+ constants_fetcher.constants(), event_loop.node()->name()->string_view());
+ const cv::Mat intrinsics = frc971::vision::CameraIntrinsics(calibration_data);
+ const cv::Mat dist_coeffs =
+ frc971::vision::CameraDistCoeffs(calibration_data);
+
+ aos::Fetcher<CameraImage> image_fetcher =
+ event_loop.MakeFetcher<CameraImage>(FLAGS_channel);
+
+ // Run the display loop
+ event_loop.AddPhasedLoop(
+ [&](int) {
+ if (!DisplayLoop(intrinsics, dist_coeffs, &image_fetcher)) {
+ LOG(INFO) << "Calling event_loop Exit";
+ event_loop.Exit();
+ };
+ },
+ ::std::chrono::milliseconds(FLAGS_rate));
+
+ event_loop.Run();
+
+ image_fetcher = aos::Fetcher<CameraImage>();
+}
+
+} // namespace
+} // namespace y2024::vision
+
+int main(int argc, char **argv) {
+ aos::InitGoogle(&argc, &argv);
+ y2024::vision::ViewerMain();
+}
diff --git a/y2024/wpilib_interface.cc b/y2024/wpilib_interface.cc
index b708266..4a6c00b 100644
--- a/y2024/wpilib_interface.cc
+++ b/y2024/wpilib_interface.cc
@@ -81,6 +81,10 @@
return voltage * Values::kIntakePivotPotRadiansPerVolt();
}
+double climber_pot_translate(double voltage) {
+ return voltage * Values::kClimberPotRadiansPerVolt();
+}
+
double drivetrain_velocity_translate(double in) {
return (((1.0 / in) / Values::kDrivetrainCyclesPerRevolution()) *
(2.0 * M_PI)) *
@@ -90,6 +94,8 @@
constexpr double kMaxFastEncoderPulsesPerSecond = std::max({
Values::kMaxDrivetrainEncoderPulsesPerSecond(),
+ Values::kMaxIntakePivotEncoderPulsesPerSecond(),
+ Values::kMaxClimberEncoderPulsesPerSecond(),
});
static_assert(kMaxFastEncoderPulsesPerSecond <= 1300000,
"fast encoders are too fast");
@@ -140,6 +146,13 @@
->intake_constants()
->potentiometer_offset());
+ CopyPosition(climber_encoder_, builder->add_climber(),
+ Values::kClimberEncoderCountsPerRevolution(),
+ Values::kClimberEncoderRatio(), climber_pot_translate, true,
+ robot_constants_->robot()
+ ->climber_constants()
+ ->potentiometer_offset());
+
builder->set_transfer_beambreak(transfer_beam_break_->Get());
builder.CheckOk(builder.Send());
}
@@ -198,18 +211,12 @@
}
}
- void set_intake_pivot_encoder(::std::unique_ptr<frc::Encoder> encoder) {
+ void set_intake_pivot(::std::unique_ptr<frc::Encoder> encoder,
+ ::std::unique_ptr<frc::DigitalInput> absolute_pwm,
+ ::std::unique_ptr<frc::AnalogInput> potentiometer) {
fast_encoder_filter_.Add(encoder.get());
intake_pivot_encoder_.set_encoder(::std::move(encoder));
- }
-
- void set_intake_pivot_absolute_pwm(
- ::std::unique_ptr<frc::DigitalInput> absolute_pwm) {
intake_pivot_encoder_.set_absolute_pwm(::std::move(absolute_pwm));
- }
-
- void set_intake_pivot_potentiometer(
- ::std::unique_ptr<frc::AnalogInput> potentiometer) {
intake_pivot_encoder_.set_potentiometer(::std::move(potentiometer));
}
@@ -217,6 +224,15 @@
transfer_beam_break_ = ::std::move(sensor);
}
+ void set_climber(::std::unique_ptr<frc::Encoder> encoder,
+ ::std::unique_ptr<frc::DigitalInput> absolute_pwm,
+ ::std::unique_ptr<frc::AnalogInput> potentiometer) {
+ fast_encoder_filter_.Add(encoder.get());
+ climber_encoder_.set_encoder(::std::move(encoder));
+ climber_encoder_.set_absolute_pwm(::std::move(absolute_pwm));
+ climber_encoder_.set_potentiometer(::std::move(potentiometer));
+ }
+
private:
const Constants *robot_constants_;
@@ -231,6 +247,7 @@
std::unique_ptr<frc::DigitalInput> imu_yaw_rate_input_, transfer_beam_break_;
frc971::wpilib::AbsoluteEncoderAndPotentiometer intake_pivot_encoder_;
+ frc971::wpilib::AbsoluteEncoderAndPotentiometer climber_encoder_;
frc971::wpilib::DMAPulseWidthReader imu_yaw_rate_reader_;
};
@@ -272,13 +289,15 @@
sensor_reader.set_drivetrain_right_encoder(make_encoder(0));
sensor_reader.set_yaw_rate_input(make_unique<frc::DigitalInput>(0));
// TODO: (niko) change values once robot is wired
- sensor_reader.set_intake_pivot_encoder(make_encoder(4));
- sensor_reader.set_intake_pivot_absolute_pwm(
- make_unique<frc::DigitalInput>(4));
- sensor_reader.set_intake_pivot_potentiometer(
- make_unique<frc::AnalogInput>(4));
+ sensor_reader.set_intake_pivot(make_encoder(4),
+ make_unique<frc::DigitalInput>(4),
+ make_unique<frc::AnalogInput>(4));
sensor_reader.set_transfer_beambreak(make_unique<frc::DigitalInput>(7));
+ sensor_reader.set_climber(make_encoder(5),
+ make_unique<frc::DigitalInput>(5),
+ make_unique<frc::AnalogInput>(5));
+
AddLoop(&sensor_reader_event_loop);
// Thread 4.
@@ -290,46 +309,43 @@
std::vector<ctre::phoenix6::BaseStatusSignal *> signals_registry;
+ const CurrentLimits *current_limits =
+ robot_constants->common()->current_limits();
+
std::shared_ptr<TalonFX> right_front = std::make_shared<TalonFX>(
0, false, "Drivetrain Bus", &signals_registry,
- constants::Values::kDrivetrainStatorCurrentLimit(),
- constants::Values::kDrivetrainSupplyCurrentLimit());
+ current_limits->drivetrain_supply_current_limit(),
+ current_limits->drivetrain_stator_current_limit());
std::shared_ptr<TalonFX> right_back = std::make_shared<TalonFX>(
1, false, "Drivetrain Bus", &signals_registry,
- constants::Values::kDrivetrainStatorCurrentLimit(),
- constants::Values::kDrivetrainSupplyCurrentLimit());
+ current_limits->drivetrain_supply_current_limit(),
+ current_limits->drivetrain_stator_current_limit());
std::shared_ptr<TalonFX> left_front = std::make_shared<TalonFX>(
2, false, "Drivetrain Bus", &signals_registry,
- constants::Values::kDrivetrainStatorCurrentLimit(),
- constants::Values::kDrivetrainSupplyCurrentLimit());
+ current_limits->drivetrain_supply_current_limit(),
+ current_limits->drivetrain_stator_current_limit());
std::shared_ptr<TalonFX> left_back = std::make_shared<TalonFX>(
3, false, "Drivetrain Bus", &signals_registry,
- constants::Values::kDrivetrainStatorCurrentLimit(),
- constants::Values::kDrivetrainSupplyCurrentLimit());
- std::shared_ptr<TalonFX> intake_pivot =
- std::make_shared<TalonFX>(4, false, "Drivetrain Bus", &signals_registry,
- robot_constants->common()
- ->current_limits()
- ->intake_pivot_stator_current_limit(),
- robot_constants->common()
- ->current_limits()
- ->intake_pivot_supply_current_limit());
- std::shared_ptr<TalonFX> intake_roller =
- std::make_shared<TalonFX>(5, false, "Drivetrain Bus", &signals_registry,
- robot_constants->common()
- ->current_limits()
- ->intake_roller_stator_current_limit(),
- robot_constants->common()
- ->current_limits()
- ->intake_roller_supply_current_limit());
- std::shared_ptr<TalonFX> transfer_roller =
- std::make_shared<TalonFX>(6, false, "Drivetrain Bus", &signals_registry,
- robot_constants->common()
- ->current_limits()
- ->transfer_roller_stator_current_limit(),
- robot_constants->common()
- ->current_limits()
- ->transfer_roller_supply_current_limit());
+ current_limits->drivetrain_supply_current_limit(),
+ current_limits->drivetrain_stator_current_limit());
+ std::shared_ptr<TalonFX> intake_pivot = std::make_shared<TalonFX>(
+ 4, false, "Drivetrain Bus", &signals_registry,
+ current_limits->intake_pivot_stator_current_limit(),
+ current_limits->intake_pivot_supply_current_limit());
+ std::shared_ptr<TalonFX> intake_roller = std::make_shared<TalonFX>(
+ 5, false, "Drivetrain Bus", &signals_registry,
+ current_limits->intake_roller_stator_current_limit(),
+ current_limits->intake_roller_supply_current_limit());
+ std::shared_ptr<TalonFX> transfer_roller = std::make_shared<TalonFX>(
+ 6, false, "Drivetrain Bus", &signals_registry,
+ current_limits->transfer_roller_stator_current_limit(),
+ current_limits->transfer_roller_supply_current_limit());
+
+ std::shared_ptr<TalonFX> climber = std::make_shared<TalonFX>(
+ 7, false, "Drivetrain Bus", &signals_registry,
+ current_limits->climber_stator_current_limit(),
+ current_limits->climber_supply_current_limit());
+
ctre::phoenix::platform::can::CANComm_SetRxSchedPriority(
constants::Values::kDrivetrainRxPriority, true, "Drivetrain Bus");
ctre::phoenix::platform::can::CANComm_SetTxSchedPriority(
@@ -347,7 +363,8 @@
talonfxs.push_back(talonfx);
}
- for (auto talonfx : {intake_pivot, intake_roller, transfer_roller}) {
+ for (auto talonfx :
+ {intake_pivot, intake_roller, transfer_roller, climber}) {
talonfxs.push_back(talonfx);
}
@@ -366,7 +383,8 @@
frc971::wpilib::CANSensorReader can_sensor_reader(
&can_sensor_reader_event_loop, std::move(signals_registry), talonfxs,
[drivetrain_talonfxs, &intake_pivot, &intake_roller, &transfer_roller,
- &drivetrain_can_position_sender, &superstructure_can_position_sender](
+ &climber, &drivetrain_can_position_sender,
+ &superstructure_can_position_sender](
ctre::phoenix::StatusCode status) {
aos::Sender<frc971::control_loops::drivetrain::CANPositionStatic>::
StaticBuilder drivetrain_can_builder =
@@ -375,6 +393,8 @@
auto drivetrain_falcon_vector =
drivetrain_can_builder->add_talonfxs();
+ CHECK(drivetrain_falcon_vector->reserve(drivetrain_talonfxs.size()));
+
for (auto talonfx : drivetrain_talonfxs) {
talonfx->SerializePosition(
drivetrain_falcon_vector->emplace_back(),
@@ -400,6 +420,9 @@
transfer_roller->SerializePosition(
superstructure_can_builder->add_transfer_roller(),
control_loops::drivetrain::kHighOutputRatio);
+ climber->SerializePosition(
+ superstructure_can_builder->add_climber(),
+ control_loops::drivetrain::kHighOutputRatio);
superstructure_can_builder->set_timestamp(
intake_roller->GetTimestamp());
@@ -428,6 +451,8 @@
->second->WriteVoltage(output.intake_roller_voltage());
talonfx_map.find("transfer_roller")
->second->WriteVoltage(output.transfer_roller_voltage());
+ talonfx_map.find("climber")->second->WriteVoltage(
+ output.climber_voltage());
});
can_drivetrain_writer.set_talonfxs({right_front, right_back},
@@ -436,6 +461,7 @@
can_superstructure_writer.add_talonfx("intake_pivot", intake_pivot);
can_superstructure_writer.add_talonfx("intake_roller", intake_roller);
can_superstructure_writer.add_talonfx("transfer_roller", transfer_roller);
+ can_superstructure_writer.add_talonfx("climber", climber);
can_output_event_loop.MakeWatcher(
"/roborio", [&can_drivetrain_writer, &can_superstructure_writer](
diff --git a/y2024/www/BUILD b/y2024/www/BUILD
index 726a354..5ff91d6 100644
--- a/y2024/www/BUILD
+++ b/y2024/www/BUILD
@@ -11,12 +11,11 @@
visibility = ["//visibility:public"],
)
-#Need to add 2024 field png
genrule(
name = "2024_field_png",
- srcs = ["//third_party/y2023/field:pictures"],
+ srcs = ["//third_party/y2024/field:pictures"],
outs = ["2024.png"],
- cmd = "cp third_party/y2023/field/2023.png $@",
+ cmd = "cp third_party/y2024/field/2024.png $@",
)
ts_project(
diff --git a/y2024/www/field_handler.ts b/y2024/www/field_handler.ts
index 6c5f2e3..f383c08 100644
--- a/y2024/www/field_handler.ts
+++ b/y2024/www/field_handler.ts
@@ -16,10 +16,56 @@
const FIELD_SIDE_Y = FIELD_WIDTH / 2;
const FIELD_EDGE_X = FIELD_LENGTH / 2;
-const ROBOT_WIDTH = 25 * IN_TO_M;
+const ROBOT_WIDTH = 29 * IN_TO_M;
const ROBOT_LENGTH = 32 * IN_TO_M;
export class FieldHandler {
+ private canvas = document.createElement('canvas');
+ private fieldImage: HTMLImageElement = new Image();
constructor(private readonly connection: Connection) {
+ (document.getElementById('field') as HTMLElement).appendChild(this.canvas);
+
+ this.fieldImage.src = '2024.png';
+ }
+
+ drawField(): void {
+ const ctx = this.canvas.getContext('2d');
+ ctx.save();
+ ctx.scale(1.0, -1.0);
+ ctx.drawImage(
+ this.fieldImage, 0, 0, this.fieldImage.width, this.fieldImage.height,
+ -FIELD_EDGE_X, -FIELD_SIDE_Y, FIELD_LENGTH, FIELD_WIDTH);
+ ctx.restore();
+ }
+
+ draw(): void {
+ this.reset();
+ this.drawField();
+
+ window.requestAnimationFrame(() => this.draw());
+ }
+
+ reset(): void {
+ const ctx = this.canvas.getContext('2d');
+ // Empty space from the canvas boundary to the image
+ const IMAGE_PADDING = 10;
+ ctx.setTransform(1, 0, 0, 1, 0, 0);
+ const size = window.innerHeight * 0.9;
+ ctx.canvas.height = size;
+ const width = size / 2 + 20;
+ ctx.canvas.width = width;
+ ctx.clearRect(0, 0, size, width);
+
+ // Translate to center of display.
+ ctx.translate(width / 2, size / 2);
+ // Coordinate system is:
+ // x -> forward.
+ // y -> to the left.
+ ctx.rotate(-Math.PI / 2);
+ ctx.scale(1, -1);
+
+ const M_TO_PX = (size - IMAGE_PADDING) / FIELD_LENGTH;
+ ctx.scale(M_TO_PX, M_TO_PX);
+ ctx.lineWidth = 1 / M_TO_PX;
}
}
diff --git a/y2024/www/field_main.ts b/y2024/www/field_main.ts
index 24bc23a..ef8b99d 100644
--- a/y2024/www/field_main.ts
+++ b/y2024/www/field_main.ts
@@ -8,4 +8,4 @@
const fieldHandler = new FieldHandler(conn);
-
+fieldHandler.draw();
diff --git a/y2024/y2024_orin_template.json b/y2024/y2024_orin_template.json
index 6206cf9..2bb2f46 100644
--- a/y2024/y2024_orin_template.json
+++ b/y2024/y2024_orin_template.json
@@ -110,9 +110,10 @@
"max_size": 208
},
{
- "name": "/orin{{ NUM }}/camera",
+ "name": "/orin{{ NUM }}/camera1",
"type": "frc971.vision.CameraImage",
"source_node": "orin{{ NUM }}",
+ "channel_storage_duration": 1000000000,
"frequency": 65,
"max_size": 4752384,
"num_readers": 6,
@@ -120,21 +121,48 @@
"num_senders": 18
},
{
- "name": "/orin{{ NUM }}/camera",
+ "name": "/orin{{ NUM }}/camera2",
+ "type": "frc971.vision.CameraImage",
+ "source_node": "orin{{ NUM }}",
+ "channel_storage_duration": 1000000000,
+ "frequency": 65,
+ "max_size": 4752384,
+ "num_readers": 6,
+ "read_method": "PIN",
+ "num_senders": 18
+ },
+ {
+ "name": "/orin{{ NUM }}/camera1",
"type": "foxglove.CompressedImage",
"source_node": "orin{{ NUM }}",
+ "channel_storage_duration": 1000000000,
"frequency": 65,
"max_size": 622384
},
{
- "name": "/orin{{ NUM }}/camera",
+ "name": "/orin{{ NUM }}/camera2",
+ "type": "foxglove.CompressedImage",
+ "source_node": "orin{{ NUM }}",
+ "channel_storage_duration": 1000000000,
+ "frequency": 65,
+ "max_size": 622384
+ },
+ {
+ "name": "/orin{{ NUM }}/camera1",
"type": "foxglove.ImageAnnotations",
"source_node": "orin{{ NUM }}",
"frequency": 65,
"max_size": 50000
},
{
- "name": "/orin{{ NUM }}/camera",
+ "name": "/orin{{ NUM }}/camera2",
+ "type": "foxglove.ImageAnnotations",
+ "source_node": "orin{{ NUM }}",
+ "frequency": 65,
+ "max_size": 50000
+ },
+ {
+ "name": "/orin{{ NUM }}/camera1",
"type": "frc971.vision.TargetMap",
"source_node": "orin{{ NUM }}",
"frequency": 65,
@@ -157,7 +185,37 @@
]
},
{
- "name": "/orin{{ NUM }}/aos/remote_timestamps/imu/orin{{ NUM }}/camera/frc971-vision-TargetMap",
+ "name": "/orin{{ NUM }}/camera2",
+ "type": "frc971.vision.TargetMap",
+ "source_node": "orin{{ NUM }}",
+ "frequency": 65,
+ "num_senders": 2,
+ "max_size": 1024,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "imu"
+ ],
+ "destination_nodes": [
+ {
+ "name": "imu",
+ "priority": 4,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "orin{{ NUM }}"
+ ],
+ "time_to_live": 5000000
+ }
+ ]
+ },
+ {
+ "name": "/orin{{ NUM }}/aos/remote_timestamps/imu/orin{{ NUM }}/camera1/frc971-vision-TargetMap",
+ "type": "aos.message_bridge.RemoteMessage",
+ "frequency": 80,
+ "source_node": "orin{{ NUM }}",
+ "max_size": 208
+ },
+ {
+ "name": "/orin{{ NUM }}/aos/remote_timestamps/imu/orin{{ NUM }}/camera2/frc971-vision-TargetMap",
"type": "aos.message_bridge.RemoteMessage",
"frequency": 80,
"source_node": "orin{{ NUM }}",
@@ -238,8 +296,23 @@
]
},
{
- "name": "foxglove_image_converter",
+ "name": "foxglove_image_converter1",
+ "executable_name": "foxglove_image_converter",
"user": "pi",
+ "args": [
+ "--channel", "/camera1"
+ ],
+ "nodes": [
+ "orin{{ NUM }}"
+ ]
+ },
+ {
+ "name": "foxglove_image_converter2",
+ "executable_name": "foxglove_image_converter",
+ "user": "pi",
+ "args": [
+ "--channel", "/camera2"
+ ],
"nodes": [
"orin{{ NUM }}"
]
@@ -253,11 +326,12 @@
]
},
{
- "name": "argus_camera",
+ "name": "argus_camera1",
"executable_name": "argus_camera",
"args": [
"--enable_ftrace",
- "--camera=1",
+ "--camera=0",
+ "--channel=/camera1",
],
"user": "pi",
"nodes": [
@@ -265,10 +339,34 @@
]
},
{
- "name": "apriltag_detector",
+ "name": "argus_camera2",
+ "executable_name": "argus_camera",
+ "args": [
+ "--enable_ftrace",
+ "--camera=1",
+ "--channel=/camera2",
+ ],
+ "user": "pi",
+ "nodes": [
+ "orin{{ NUM }}"
+ ]
+ },
+ {
+ "name": "apriltag_detector1",
"executable_name": "apriltag_detector",
"args": [
- "--channel=/camera",
+ "--channel=/camera1",
+ ],
+ "user": "pi",
+ "nodes": [
+ "orin{{ NUM }}"
+ ]
+ },
+ {
+ "name": "apriltag_detector2",
+ "executable_name": "apriltag_detector",
+ "args": [
+ "--channel=/camera2",
],
"user": "pi",
"nodes": [
diff --git a/y2024_defense/constants.h b/y2024_defense/constants.h
index 7e359f4..d9631d7 100644
--- a/y2024_defense/constants.h
+++ b/y2024_defense/constants.h
@@ -12,8 +12,7 @@
#include "frc971/zeroing/pot_and_absolute_encoder.h"
#include "y2024_defense/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
-namespace y2024_defense {
-namespace constants {
+namespace y2024_defense::constants {
constexpr uint16_t kTeamNumber = 9972;
@@ -60,7 +59,6 @@
// Calls MakeValues with aos::network::GetTeamNumber()
Values MakeValues();
-} // namespace constants
-} // namespace y2024_defense
+} // namespace y2024_defense::constants
#endif // Y2023_CONSTANTS_H_
diff --git a/y2024_defense/control_loops/drivetrain/drivetrain_base.h b/y2024_defense/control_loops/drivetrain/drivetrain_base.h
index 622de4f..776ec93 100644
--- a/y2024_defense/control_loops/drivetrain/drivetrain_base.h
+++ b/y2024_defense/control_loops/drivetrain/drivetrain_base.h
@@ -3,15 +3,11 @@
#include "frc971/control_loops/drivetrain/drivetrain_config.h"
-namespace y2024_defense {
-namespace control_loops {
-namespace drivetrain {
+namespace y2024_defense::control_loops::drivetrain {
const ::frc971::control_loops::drivetrain::DrivetrainConfig<double> &
GetDrivetrainConfig();
-} // namespace drivetrain
-} // namespace control_loops
-} // namespace y2024_defense
+} // namespace y2024_defense::control_loops::drivetrain
#endif // Y2023_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2024_defense/wpilib_interface.cc b/y2024_defense/wpilib_interface.cc
index 1584dbd..6dec3c9 100644
--- a/y2024_defense/wpilib_interface.cc
+++ b/y2024_defense/wpilib_interface.cc
@@ -324,6 +324,8 @@
auto falcon_vector = builder->add_talonfxs();
+ CHECK(falcon_vector->reserve(falcons.size()));
+
for (auto falcon : falcons) {
falcon->SerializePosition(
falcon_vector->emplace_back(),