Add y2023 folder
2022 Bot specific things were removed
Change-Id: I6563d477a65bf2eae5d39933003742bd372cf82e
Signed-off-by: Maxwell Henderson <mxwhenderson@gmail.com>
Signed-off-by: Xander Yee <xander.yee@gmail.com>
diff --git a/y2023/BUILD b/y2023/BUILD
index 60764ce..dc3bb67 100644
--- a/y2023/BUILD
+++ b/y2023/BUILD
@@ -5,24 +5,36 @@
robot_downloader(
name = "pi_download",
binaries = [
+ "//y2020/vision:calibration",
"//y2023/vision:viewer",
"//y2022/localizer:imu_main",
"//y2022/localizer:localizer_main",
+ "//aos/network:web_proxy_main",
"//aos/events/logging:log_cat",
],
data = [
":aos_config",
+ ":message_bridge_client.sh",
+ "//y2022/www:www_files",
+ "@ctre_phoenix_api_cpp_athena//:shared_libraries",
+ "@ctre_phoenix_cci_athena//:shared_libraries",
],
dirs = [
- "//y2022/www:www_files",
+ "//y2023/www:www_files",
],
start_binaries = [
- "//aos/events/logging:logger_main",
"//aos/network:message_bridge_client",
"//aos/network:message_bridge_server",
"//aos/network:web_proxy_main",
"//aos/starter:irq_affinity",
"//y2023/vision:camera_reader",
+ "//aos/events/logging:logger_main",
+ ":joystick_reader",
+ ":wpilib_interface",
+ "//y2023/autonomous:binaries",
+ "//y2023/control_loops/drivetrain:drivetrain",
+ "//y2023/control_loops/drivetrain:trajectory_generator",
+ "//y2023/control_loops/superstructure:superstructure",
],
target_compatible_with = ["//tools/platforms/hardware:raspberry_pi"],
target_type = "pi",
@@ -60,7 +72,9 @@
"//aos/network:message_bridge_server_fbs",
"//aos/network:timestamp_fbs",
"//aos/network:remote_message_fbs",
+ "//y2022/localizer:localizer_output_fbs",
"//frc971/vision:vision_fbs",
+ "//y2023/vision:calibration_fbs",
],
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//visibility:public"],
@@ -86,6 +100,9 @@
"//aos/network:message_bridge_server_fbs",
"//aos/network:timestamp_fbs",
"//aos/network:remote_message_fbs",
+ "//y2022/localizer:localizer_status_fbs",
+ "//y2022/localizer:localizer_output_fbs",
+ "//y2022/localizer:localizer_visualization_fbs",
],
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//visibility:public"],
@@ -104,6 +121,7 @@
"//aos/network:timestamp_fbs",
"//aos/network:remote_message_fbs",
"//frc971/vision:vision_fbs",
+ "//y2023/vision:calibration_fbs",
],
target_compatible_with = ["@platforms//os:linux"],
visibility = ["//visibility:public"],
@@ -123,6 +141,10 @@
"//aos/network:message_bridge_server_fbs",
"//aos/network:timestamp_fbs",
"//y2019/control_loops/drivetrain:target_selector_fbs",
+ "//y2023/control_loops/superstructure:superstructure_goal_fbs",
+ "//y2023/control_loops/superstructure:superstructure_output_fbs",
+ "//y2023/control_loops/superstructure:superstructure_position_fbs",
+ "//y2023/control_loops/superstructure:superstructure_status_fbs",
],
target_compatible_with = ["@platforms//os:linux"],
deps = [
@@ -143,3 +165,108 @@
)
for num in range(1, 6)
]
+
+cc_library(
+ name = "constants",
+ srcs = [
+ "constants.cc",
+ ],
+ hdrs = [
+ "constants.h",
+ ],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//aos/mutex",
+ "//aos/network:team_number",
+ "//frc971:constants",
+ "//frc971/control_loops:pose",
+ "//frc971/control_loops:static_zeroing_single_dof_profiled_subsystem",
+ "//frc971/shooter_interpolation:interpolation",
+ "//y2023/control_loops/drivetrain:polydrivetrain_plants",
+ "@com_github_google_glog//:glog",
+ "@com_google_absl//absl/base",
+ ],
+)
+
+cc_binary(
+ name = "wpilib_interface",
+ srcs = [
+ "wpilib_interface.cc",
+ ],
+ target_compatible_with = ["//tools/platforms/hardware:roborio"],
+ deps = [
+ ":constants",
+ "//aos:init",
+ "//aos:math",
+ "//aos/events:shm_event_loop",
+ "//aos/logging",
+ "//aos/stl_mutex",
+ "//aos/time",
+ "//aos/util:log_interval",
+ "//aos/util:phased_loop",
+ "//aos/util:wrapping_counter",
+ "//frc971/autonomous:auto_mode_fbs",
+ "//frc971/control_loops:control_loop",
+ "//frc971/control_loops:control_loops_fbs",
+ "//frc971/control_loops/drivetrain:drivetrain_position_fbs",
+ "//frc971/input:robot_state_fbs",
+ "//frc971/queues:gyro_fbs",
+ "//frc971/wpilib:ADIS16448",
+ "//frc971/wpilib:buffered_pcm",
+ "//frc971/wpilib:drivetrain_writer",
+ "//frc971/wpilib:encoder_and_potentiometer",
+ "//frc971/wpilib:interrupt_edge_counting",
+ "//frc971/wpilib:joystick_sender",
+ "//frc971/wpilib:logging_fbs",
+ "//frc971/wpilib:loop_output_handler",
+ "//frc971/wpilib:pdp_fetcher",
+ "//frc971/wpilib:sensor_reader",
+ "//frc971/wpilib:wpilib_interface",
+ "//frc971/wpilib:wpilib_robot_base",
+ "//third_party:phoenix",
+ "//third_party:wpilib",
+ "//y2023/control_loops/superstructure:superstructure_output_fbs",
+ "//y2023/control_loops/superstructure:superstructure_position_fbs",
+ ],
+)
+
+cc_binary(
+ name = "joystick_reader",
+ srcs = [
+ ":joystick_reader.cc",
+ ],
+ deps = [
+ ":constants",
+ "//aos:init",
+ "//aos/actions:action_lib",
+ "//aos/logging",
+ "//frc971/autonomous:auto_fbs",
+ "//frc971/autonomous:base_autonomous_actor",
+ "//frc971/control_loops:profiled_subsystem_fbs",
+ "//frc971/input:action_joystick_input",
+ "//frc971/input:drivetrain_input",
+ "//frc971/input:joystick_input",
+ "//y2023/control_loops/drivetrain:drivetrain_base",
+ "//y2023/control_loops/superstructure:superstructure_goal_fbs",
+ "//y2023/control_loops/superstructure:superstructure_status_fbs",
+ ],
+)
+
+py_library(
+ name = "python_init",
+ srcs = ["__init__.py"],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+)
+
+sh_binary(
+ name = "log_web_proxy",
+ srcs = ["log_web_proxy.sh"],
+ data = [
+ ":aos_config",
+ "//aos/network:log_web_proxy_main",
+ "//y2023/www:field_main_bundle.min.js",
+ "//y2023/www:files",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+)
diff --git a/y2023/__init__.py b/y2023/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2023/__init__.py
diff --git a/y2023/autonomous/BUILD b/y2023/autonomous/BUILD
new file mode 100644
index 0000000..6d6922b
--- /dev/null
+++ b/y2023/autonomous/BUILD
@@ -0,0 +1,73 @@
+load("//frc971/downloader:downloader.bzl", "aos_downloader_dir")
+
+filegroup(
+ name = "binaries.stripped",
+ srcs = [
+ ":autonomous_action.stripped",
+ ],
+ visibility = ["//visibility:public"],
+)
+
+filegroup(
+ name = "binaries",
+ srcs = [
+ ":autonomous_action",
+ ],
+ visibility = ["//visibility:public"],
+)
+
+filegroup(
+ name = "spline_jsons",
+ srcs = glob([
+ "splines/*.json",
+ ]),
+ visibility = ["//visibility:public"],
+)
+
+aos_downloader_dir(
+ name = "splines",
+ srcs = [
+ ":spline_jsons",
+ ],
+ dir = "splines",
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+)
+
+cc_library(
+ name = "autonomous_action_lib",
+ srcs = [
+ "auto_splines.cc",
+ "autonomous_actor.cc",
+ ],
+ hdrs = [
+ "auto_splines.h",
+ "autonomous_actor.h",
+ ],
+ deps = [
+ "//aos/events:event_loop",
+ "//aos/logging",
+ "//aos/util:phased_loop",
+ "//frc971/autonomous:base_autonomous_actor",
+ "//frc971/control_loops:control_loops_fbs",
+ "//frc971/control_loops:profiled_subsystem_fbs",
+ "//frc971/control_loops/drivetrain:drivetrain_config",
+ "//frc971/control_loops/drivetrain:localizer_fbs",
+ "//y2023/control_loops/drivetrain:drivetrain_base",
+ "//y2023/control_loops/superstructure:superstructure_goal_fbs",
+ "//y2023/control_loops/superstructure:superstructure_status_fbs",
+ ],
+)
+
+cc_binary(
+ name = "autonomous_action",
+ srcs = [
+ "autonomous_actor_main.cc",
+ ],
+ deps = [
+ ":autonomous_action_lib",
+ "//aos:init",
+ "//aos/events:shm_event_loop",
+ "//frc971/autonomous:auto_fbs",
+ ],
+)
diff --git a/y2023/autonomous/auto_splines.cc b/y2023/autonomous/auto_splines.cc
new file mode 100644
index 0000000..07250e4
--- /dev/null
+++ b/y2023/autonomous/auto_splines.cc
@@ -0,0 +1,103 @@
+#include "y2023/autonomous/auto_splines.h"
+
+#include "frc971/control_loops/control_loops_generated.h"
+
+namespace y2023 {
+namespace actors {
+
+void MaybeFlipSpline(
+ aos::Sender<frc971::control_loops::drivetrain::Goal>::Builder *builder,
+ flatbuffers::Offset<flatbuffers::Vector<float>> spline_y_offset,
+ bool is_left) {
+ flatbuffers::Vector<float> *spline_y =
+ GetMutableTemporaryPointer(*builder->fbb(), spline_y_offset);
+
+ if (!is_left) {
+ for (size_t i = 0; i < spline_y->size(); i++) {
+ spline_y->Mutate(i, -spline_y->Get(i));
+ }
+ }
+}
+
+flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::BasicSSpline(
+ aos::Sender<frc971::control_loops::drivetrain::Goal>::Builder *builder) {
+ flatbuffers::Offset<frc971::Constraint> longitudinal_constraint_offset;
+ flatbuffers::Offset<frc971::Constraint> lateral_constraint_offset;
+ flatbuffers::Offset<frc971::Constraint> voltage_constraint_offset;
+
+ {
+ frc971::Constraint::Builder longitudinal_constraint_builder =
+ builder->MakeBuilder<frc971::Constraint>();
+ longitudinal_constraint_builder.add_constraint_type(
+ frc971::ConstraintType::LONGITUDINAL_ACCELERATION);
+ longitudinal_constraint_builder.add_value(1.0);
+ longitudinal_constraint_offset = longitudinal_constraint_builder.Finish();
+ }
+
+ {
+ frc971::Constraint::Builder lateral_constraint_builder =
+ builder->MakeBuilder<frc971::Constraint>();
+ lateral_constraint_builder.add_constraint_type(
+ frc971::ConstraintType::LATERAL_ACCELERATION);
+ lateral_constraint_builder.add_value(1.0);
+ lateral_constraint_offset = lateral_constraint_builder.Finish();
+ }
+
+ {
+ frc971::Constraint::Builder voltage_constraint_builder =
+ builder->MakeBuilder<frc971::Constraint>();
+ voltage_constraint_builder.add_constraint_type(
+ frc971::ConstraintType::VOLTAGE);
+ voltage_constraint_builder.add_value(6.0);
+ voltage_constraint_offset = voltage_constraint_builder.Finish();
+ }
+
+ flatbuffers::Offset<
+ flatbuffers::Vector<flatbuffers::Offset<frc971::Constraint>>>
+ constraints_offset =
+ builder->fbb()->CreateVector<flatbuffers::Offset<frc971::Constraint>>(
+ {longitudinal_constraint_offset, lateral_constraint_offset,
+ voltage_constraint_offset});
+
+ const float startx = 0.4;
+ const float starty = 3.4;
+ flatbuffers::Offset<flatbuffers::Vector<float>> spline_x_offset =
+ builder->fbb()->CreateVector<float>({0.0f + startx, 0.6f + startx,
+ 0.6f + startx, 0.4f + startx,
+ 0.4f + startx, 1.0f + startx});
+ flatbuffers::Offset<flatbuffers::Vector<float>> spline_y_offset =
+ builder->fbb()->CreateVector<float>({starty - 0.0f, starty - 0.0f,
+ starty - 0.3f, starty - 0.7f,
+ starty - 1.0f, starty - 1.0f});
+
+ frc971::MultiSpline::Builder multispline_builder =
+ builder->MakeBuilder<frc971::MultiSpline>();
+
+ multispline_builder.add_spline_count(1);
+ multispline_builder.add_constraints(constraints_offset);
+ multispline_builder.add_spline_x(spline_x_offset);
+ multispline_builder.add_spline_y(spline_y_offset);
+
+ return multispline_builder.Finish();
+}
+
+flatbuffers::Offset<frc971::MultiSpline> AutonomousSplines::StraightLine(
+ aos::Sender<frc971::control_loops::drivetrain::Goal>::Builder *builder) {
+ flatbuffers::Offset<flatbuffers::Vector<float>> spline_x_offset =
+ builder->fbb()->CreateVector<float>(
+ {-12.3, -11.9, -11.5, -11.1, -10.6, -10.0});
+ flatbuffers::Offset<flatbuffers::Vector<float>> spline_y_offset =
+ builder->fbb()->CreateVector<float>({1.25, 1.25, 1.25, 1.25, 1.25, 1.25});
+
+ frc971::MultiSpline::Builder multispline_builder =
+ builder->MakeBuilder<frc971::MultiSpline>();
+
+ multispline_builder.add_spline_count(1);
+ multispline_builder.add_spline_x(spline_x_offset);
+ multispline_builder.add_spline_y(spline_y_offset);
+
+ return multispline_builder.Finish();
+}
+
+} // namespace actors
+} // namespace y2023
diff --git a/y2023/autonomous/auto_splines.h b/y2023/autonomous/auto_splines.h
new file mode 100644
index 0000000..68795e6
--- /dev/null
+++ b/y2023/autonomous/auto_splines.h
@@ -0,0 +1,28 @@
+#ifndef Y2023_ACTORS_AUTO_SPLINES_H_
+#define Y2023_ACTORS_AUTO_SPLINES_H_
+
+#include "aos/events/event_loop.h"
+#include "frc971/control_loops/control_loops_generated.h"
+#include "frc971/control_loops/drivetrain/drivetrain_goal_generated.h"
+/*
+
+ The cooridinate system for the autonomous splines is the same as the spline
+ python generator and drivetrain spline systems.
+
+*/
+
+namespace y2023 {
+namespace actors {
+
+class AutonomousSplines {
+ public:
+ static flatbuffers::Offset<frc971::MultiSpline> BasicSSpline(
+ aos::Sender<frc971::control_loops::drivetrain::Goal>::Builder *builder);
+ static flatbuffers::Offset<frc971::MultiSpline> StraightLine(
+ aos::Sender<frc971::control_loops::drivetrain::Goal>::Builder *builder);
+};
+
+} // namespace actors
+} // namespace y2023
+
+#endif // Y2023_ACTORS_AUTO_SPLINES_H_
diff --git a/y2023/autonomous/autonomous_actor.cc b/y2023/autonomous/autonomous_actor.cc
new file mode 100644
index 0000000..a815b25
--- /dev/null
+++ b/y2023/autonomous/autonomous_actor.cc
@@ -0,0 +1,37 @@
+#include "y2023/autonomous/autonomous_actor.h"
+
+#include <chrono>
+#include <cinttypes>
+#include <cmath>
+
+#include "aos/logging/logging.h"
+#include "frc971/control_loops/drivetrain/localizer_generated.h"
+#include "y2023/control_loops/drivetrain/drivetrain_base.h"
+
+namespace y2023 {
+namespace actors {
+
+using ::aos::monotonic_clock;
+using ::frc971::ProfileParametersT;
+using frc971::control_loops::drivetrain::LocalizerControl;
+namespace chrono = ::std::chrono;
+
+AutonomousActor::AutonomousActor(::aos::EventLoop *event_loop)
+ : frc971::autonomous::BaseAutonomousActor(
+ event_loop, control_loops::drivetrain::GetDrivetrainConfig()) {}
+
+void AutonomousActor::Reset() {
+ InitializeEncoders();
+ ResetDrivetrain();
+}
+
+bool AutonomousActor::RunAction(
+ const ::frc971::autonomous::AutonomousActionParams *params) {
+ Reset();
+
+ AOS_LOG(INFO, "Params are %d\n", params->mode());
+ return true;
+}
+
+} // namespace actors
+} // namespace y2023
diff --git a/y2023/autonomous/autonomous_actor.h b/y2023/autonomous/autonomous_actor.h
new file mode 100644
index 0000000..6eb8f90
--- /dev/null
+++ b/y2023/autonomous/autonomous_actor.h
@@ -0,0 +1,27 @@
+#ifndef Y2023_ACTORS_AUTONOMOUS_ACTOR_H_
+#define Y2023_ACTORS_AUTONOMOUS_ACTOR_H_
+
+#include "aos/actions/actions.h"
+#include "aos/actions/actor.h"
+#include "frc971/autonomous/base_autonomous_actor.h"
+#include "frc971/control_loops/control_loops_generated.h"
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+
+namespace y2023 {
+namespace actors {
+
+class AutonomousActor : public ::frc971::autonomous::BaseAutonomousActor {
+ public:
+ explicit AutonomousActor(::aos::EventLoop *event_loop);
+
+ bool RunAction(
+ const ::frc971::autonomous::AutonomousActionParams *params) override;
+
+ private:
+ void Reset();
+};
+
+} // namespace actors
+} // namespace y2023
+
+#endif // Y2023_ACTORS_AUTONOMOUS_ACTOR_H_
diff --git a/y2023/autonomous/autonomous_actor_main.cc b/y2023/autonomous/autonomous_actor_main.cc
new file mode 100644
index 0000000..1ee3c15
--- /dev/null
+++ b/y2023/autonomous/autonomous_actor_main.cc
@@ -0,0 +1,19 @@
+#include <cstdio>
+
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "y2023/autonomous/autonomous_actor.h"
+
+int main(int argc, char *argv[]) {
+ ::aos::InitGoogle(&argc, &argv);
+
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig("aos_config.json");
+
+ ::aos::ShmEventLoop event_loop(&config.message());
+ ::y2023::actors::AutonomousActor autonomous(&event_loop);
+
+ event_loop.Run();
+
+ return 0;
+}
diff --git a/y2023/constants.cc b/y2023/constants.cc
new file mode 100644
index 0000000..843af2b
--- /dev/null
+++ b/y2023/constants.cc
@@ -0,0 +1,49 @@
+#include "y2023/constants.h"
+
+#include <cinttypes>
+#include <map>
+
+#if __has_feature(address_sanitizer)
+#include "sanitizer/lsan_interface.h"
+#endif
+
+#include "absl/base/call_once.h"
+#include "aos/mutex/mutex.h"
+#include "aos/network/team_number.h"
+#include "glog/logging.h"
+
+namespace y2023 {
+namespace constants {
+
+const int Values::kZeroingSampleSize;
+
+Values MakeValues(uint16_t team) {
+ LOG(INFO) << "creating a Constants for team: " << team;
+
+ Values r;
+
+ switch (team) {
+ // A set of constants for tests.
+ case 1:
+ break;
+
+ case kCompTeamNumber:
+ break;
+
+ case kPracticeTeamNumber:
+ break;
+
+ case kCodingRobotTeamNumber:
+ break;
+
+ default:
+ LOG(FATAL) << "unknown team: " << team;
+ }
+
+ return r;
+}
+
+Values MakeValues() { return MakeValues(aos::network::GetTeamNumber()); }
+
+} // namespace constants
+} // namespace y2023
diff --git a/y2023/constants.h b/y2023/constants.h
new file mode 100644
index 0000000..03a6cae
--- /dev/null
+++ b/y2023/constants.h
@@ -0,0 +1,68 @@
+#ifndef Y2023_CONSTANTS_H_
+#define Y2023_CONSTANTS_H_
+
+#include <array>
+#include <cmath>
+#include <cstdint>
+
+#include "frc971/constants.h"
+#include "frc971/control_loops/pose.h"
+#include "frc971/control_loops/static_zeroing_single_dof_profiled_subsystem.h"
+#include "y2023/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+
+namespace y2023 {
+namespace constants {
+
+constexpr uint16_t kCompTeamNumber = 971;
+constexpr uint16_t kPracticeTeamNumber = 9971;
+constexpr uint16_t kCodingRobotTeamNumber = 7971;
+
+struct Values {
+ static const int kZeroingSampleSize = 200;
+
+ static constexpr double kDrivetrainCyclesPerRevolution() { return 512.0; }
+ static constexpr double kDrivetrainEncoderCountsPerRevolution() {
+ return kDrivetrainCyclesPerRevolution() * 4;
+ }
+ static constexpr double kDrivetrainEncoderRatio() { return 1.0; }
+ static constexpr double kMaxDrivetrainEncoderPulsesPerSecond() {
+ return control_loops::drivetrain::kFreeSpeed / (2.0 * M_PI) *
+ control_loops::drivetrain::kHighOutputRatio /
+ constants::Values::kDrivetrainEncoderRatio() *
+ kDrivetrainEncoderCountsPerRevolution();
+ }
+
+ static double DrivetrainEncoderToMeters(int32_t in) {
+ return ((static_cast<double>(in) /
+ kDrivetrainEncoderCountsPerRevolution()) *
+ (2.0 * M_PI)) *
+ kDrivetrainEncoderRatio() * control_loops::drivetrain::kWheelRadius;
+ }
+
+ struct PotConstants {
+ ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemParams<
+ ::frc971::zeroing::RelativeEncoderZeroingEstimator>
+ subsystem_params;
+ double potentiometer_offset;
+ };
+
+ struct PotAndAbsEncoderConstants {
+ ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemParams<
+ ::frc971::zeroing::PotAndAbsoluteEncoderZeroingEstimator>
+ subsystem_params;
+ double potentiometer_offset;
+ };
+};
+
+// Creates and returns a Values instance for the constants.
+// Should be called before realtime because this allocates memory.
+// Only the first call to either of these will be used.
+Values MakeValues(uint16_t team);
+
+// Calls MakeValues with aos::network::GetTeamNumber()
+Values MakeValues();
+
+} // namespace constants
+} // namespace y2023
+
+#endif // Y2023_CONSTANTS_H_
diff --git a/y2023/control_loops/BUILD b/y2023/control_loops/BUILD
new file mode 100644
index 0000000..817f9c4
--- /dev/null
+++ b/y2023/control_loops/BUILD
@@ -0,0 +1,7 @@
+py_library(
+ name = "python_init",
+ srcs = ["__init__.py"],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = ["//y2023:python_init"],
+)
diff --git a/y2023/control_loops/__init__.py b/y2023/control_loops/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2023/control_loops/__init__.py
diff --git a/y2023/control_loops/drivetrain/BUILD b/y2023/control_loops/drivetrain/BUILD
new file mode 100644
index 0000000..8a06d00
--- /dev/null
+++ b/y2023/control_loops/drivetrain/BUILD
@@ -0,0 +1,113 @@
+load("//aos:config.bzl", "aos_config")
+
+genrule(
+ name = "genrule_drivetrain",
+ outs = [
+ "drivetrain_dog_motor_plant.h",
+ "drivetrain_dog_motor_plant.cc",
+ "kalman_drivetrain_motor_plant.h",
+ "kalman_drivetrain_motor_plant.cc",
+ ],
+ cmd = "$(location //y2023/control_loops/python:drivetrain) $(OUTS)",
+ target_compatible_with = ["@platforms//os:linux"],
+ tools = [
+ "//y2023/control_loops/python:drivetrain",
+ ],
+)
+
+genrule(
+ name = "genrule_polydrivetrain",
+ outs = [
+ "polydrivetrain_dog_motor_plant.h",
+ "polydrivetrain_dog_motor_plant.cc",
+ "polydrivetrain_cim_plant.h",
+ "polydrivetrain_cim_plant.cc",
+ "hybrid_velocity_drivetrain.h",
+ "hybrid_velocity_drivetrain.cc",
+ ],
+ cmd = "$(location //y2023/control_loops/python:polydrivetrain) $(OUTS)",
+ target_compatible_with = ["@platforms//os:linux"],
+ tools = [
+ "//y2023/control_loops/python:polydrivetrain",
+ ],
+)
+
+cc_library(
+ name = "polydrivetrain_plants",
+ srcs = [
+ "drivetrain_dog_motor_plant.cc",
+ "hybrid_velocity_drivetrain.cc",
+ "kalman_drivetrain_motor_plant.cc",
+ "polydrivetrain_dog_motor_plant.cc",
+ ],
+ hdrs = [
+ "drivetrain_dog_motor_plant.h",
+ "hybrid_velocity_drivetrain.h",
+ "kalman_drivetrain_motor_plant.h",
+ "polydrivetrain_dog_motor_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",
+ ],
+)
+
+cc_library(
+ name = "drivetrain_base",
+ srcs = [
+ "drivetrain_base.cc",
+ ],
+ hdrs = [
+ "drivetrain_base.h",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ ":polydrivetrain_plants",
+ "//frc971:shifter_hall_effect",
+ "//frc971/control_loops/drivetrain:drivetrain_config",
+ ],
+)
+
+cc_binary(
+ name = "drivetrain",
+ srcs = [
+ "drivetrain_main.cc",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ ":drivetrain_base",
+ "//aos:init",
+ "//aos/events:shm_event_loop",
+ "//frc971/control_loops/drivetrain:drivetrain_lib",
+ ],
+)
+
+aos_config(
+ name = "simulation_config",
+ src = "drivetrain_simulation_config.json",
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//frc971/control_loops/drivetrain:simulation_channels",
+ "//y2023:aos_config",
+ ],
+)
+
+cc_binary(
+ name = "trajectory_generator",
+ srcs = [
+ "trajectory_generator_main.cc",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = [
+ ":drivetrain_base",
+ "//aos:init",
+ "//aos/events:shm_event_loop",
+ "//frc971/control_loops/drivetrain:trajectory_generator",
+ ],
+)
diff --git a/y2023/control_loops/drivetrain/drivetrain_base.cc b/y2023/control_loops/drivetrain/drivetrain_base.cc
new file mode 100644
index 0000000..cdb5a61
--- /dev/null
+++ b/y2023/control_loops/drivetrain/drivetrain_base.cc
@@ -0,0 +1,71 @@
+#include "y2023/control_loops/drivetrain/drivetrain_base.h"
+
+#include <chrono>
+
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+#include "frc971/control_loops/state_feedback_loop.h"
+#include "y2023/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "y2023/control_loops/drivetrain/hybrid_velocity_drivetrain.h"
+#include "y2023/control_loops/drivetrain/kalman_drivetrain_motor_plant.h"
+#include "y2023/control_loops/drivetrain/polydrivetrain_dog_motor_plant.h"
+
+using ::frc971::control_loops::drivetrain::DownEstimatorConfig;
+using ::frc971::control_loops::drivetrain::DrivetrainConfig;
+
+namespace chrono = ::std::chrono;
+
+namespace y2023 {
+namespace control_loops {
+namespace drivetrain {
+
+using ::frc971::constants::ShifterHallEffect;
+
+const ShifterHallEffect kThreeStateDriveShifter{0.0, 0.0, 0.25, 0.75};
+
+const DrivetrainConfig<double> &GetDrivetrainConfig() {
+ // Yaw of the IMU relative to the robot frame.
+ static constexpr double kImuYaw = 0.0;
+ static DrivetrainConfig<double> kDrivetrainConfig{
+ ::frc971::control_loops::drivetrain::ShifterType::SIMPLE_SHIFTER,
+ ::frc971::control_loops::drivetrain::LoopType::CLOSED_LOOP,
+ ::frc971::control_loops::drivetrain::GyroType::SPARTAN_GYRO,
+ ::frc971::control_loops::drivetrain::IMUType::IMU_FLIPPED_X,
+
+ drivetrain::MakeDrivetrainLoop,
+ drivetrain::MakeVelocityDrivetrainLoop,
+ drivetrain::MakeKFDrivetrainLoop,
+ drivetrain::MakeHybridVelocityDrivetrainLoop,
+
+ chrono::duration_cast<chrono::nanoseconds>(
+ chrono::duration<double>(drivetrain::kDt)),
+ drivetrain::kRobotRadius,
+ drivetrain::kWheelRadius,
+ drivetrain::kV,
+
+ drivetrain::kHighGearRatio,
+ drivetrain::kLowGearRatio,
+ drivetrain::kJ,
+ drivetrain::kMass,
+ kThreeStateDriveShifter,
+ kThreeStateDriveShifter,
+ true /* default_high_gear */,
+ 0 /* down_offset if using constants use
+ constants::GetValues().down_error */
+ ,
+ 0.7 /* wheel_non_linearity */,
+ 1.2 /* quickturn_wheel_multiplier */,
+ 1.2 /* wheel_multiplier */,
+ true /*pistol_grip_shift_enables_line_follow*/,
+ (Eigen::Matrix<double, 3, 3>() << std::cos(kImuYaw), -std::sin(kImuYaw),
+ 0.0, std::sin(kImuYaw), std::cos(kImuYaw), 0.0, 0.0, 0.0, 1.0)
+ .finished(),
+ false /*is_simulated*/,
+ DownEstimatorConfig{.gravity_threshold = 0.015,
+ .do_accel_corrections = 1000}};
+
+ return kDrivetrainConfig;
+};
+
+} // namespace drivetrain
+} // namespace control_loops
+} // namespace y2023
diff --git a/y2023/control_loops/drivetrain/drivetrain_base.h b/y2023/control_loops/drivetrain/drivetrain_base.h
new file mode 100644
index 0000000..6404081
--- /dev/null
+++ b/y2023/control_loops/drivetrain/drivetrain_base.h
@@ -0,0 +1,17 @@
+#ifndef Y2023_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
+#define Y2023_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
+
+#include "frc971/control_loops/drivetrain/drivetrain_config.h"
+
+namespace y2023 {
+namespace control_loops {
+namespace drivetrain {
+
+const ::frc971::control_loops::drivetrain::DrivetrainConfig<double>
+ &GetDrivetrainConfig();
+
+} // namespace drivetrain
+} // namespace control_loops
+} // namespace y2023
+
+#endif // Y2023_CONTROL_LOOPS_DRIVETRAIN_DRIVETRAIN_BASE_H_
diff --git a/y2023/control_loops/drivetrain/drivetrain_main.cc b/y2023/control_loops/drivetrain/drivetrain_main.cc
new file mode 100644
index 0000000..cf8aa8a
--- /dev/null
+++ b/y2023/control_loops/drivetrain/drivetrain_main.cc
@@ -0,0 +1,26 @@
+#include <memory>
+
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "frc971/control_loops/drivetrain/drivetrain.h"
+#include "y2023/control_loops/drivetrain/drivetrain_base.h"
+
+using ::frc971::control_loops::drivetrain::DrivetrainLoop;
+
+int main(int argc, char **argv) {
+ aos::InitGoogle(&argc, &argv);
+
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig("aos_config.json");
+
+ aos::ShmEventLoop event_loop(&config.message());
+ std::unique_ptr<::frc971::control_loops::drivetrain::DeadReckonEkf>
+ localizer =
+ std::make_unique<::frc971::control_loops::drivetrain::DeadReckonEkf>(
+ &event_loop,
+ ::y2023::control_loops::drivetrain::GetDrivetrainConfig());
+
+ event_loop.Run();
+
+ return 0;
+}
diff --git a/y2023/control_loops/drivetrain/drivetrain_simulation_config.json b/y2023/control_loops/drivetrain/drivetrain_simulation_config.json
new file mode 100644
index 0000000..27aee10
--- /dev/null
+++ b/y2023/control_loops/drivetrain/drivetrain_simulation_config.json
@@ -0,0 +1,6 @@
+{
+ "imports": [
+ "../../y2023.json",
+ "../../../frc971/control_loops/drivetrain/drivetrain_simulation_channels.json"
+ ]
+}
diff --git a/y2023/control_loops/drivetrain/trajectory_generator_main.cc b/y2023/control_loops/drivetrain/trajectory_generator_main.cc
new file mode 100644
index 0000000..03731e8
--- /dev/null
+++ b/y2023/control_loops/drivetrain/trajectory_generator_main.cc
@@ -0,0 +1,39 @@
+#include <sys/resource.h>
+#include <sys/time.h>
+
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "frc971/control_loops/drivetrain/trajectory_generator.h"
+#include "y2023/control_loops/drivetrain/drivetrain_base.h"
+
+using ::frc971::control_loops::drivetrain::TrajectoryGenerator;
+
+DEFINE_bool(skip_renicing, false,
+ "If true, skip renicing the trajectory generator.");
+
+int main(int argc, char *argv[]) {
+ ::aos::InitGoogle(&argc, &argv);
+
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig("aos_config.json");
+
+ ::aos::ShmEventLoop event_loop(&config.message());
+ TrajectoryGenerator generator(
+ &event_loop, ::y2023::control_loops::drivetrain::GetDrivetrainConfig());
+
+ event_loop.OnRun([]() {
+ if (FLAGS_skip_renicing) {
+ LOG(WARNING) << "Ignoring request to renice to -20 due to "
+ "--skip_renicing.";
+ } else {
+ errno = 0;
+ setpriority(PRIO_PROCESS, 0, -20);
+ PCHECK(errno == 0)
+ << ": Renicing to -20 failed, use --skip_renicing to skip renicing.";
+ }
+ });
+
+ event_loop.Run();
+
+ return 0;
+}
diff --git a/y2023/control_loops/python/BUILD b/y2023/control_loops/python/BUILD
new file mode 100644
index 0000000..b024676
--- /dev/null
+++ b/y2023/control_loops/python/BUILD
@@ -0,0 +1,57 @@
+package(default_visibility = ["//y2023:__subpackages__"])
+
+py_binary(
+ name = "drivetrain",
+ srcs = [
+ "drivetrain.py",
+ ],
+ legacy_create_init = False,
+ target_compatible_with = ["@platforms//cpu:x86_64"],
+ deps = [
+ ":python_init",
+ "//frc971/control_loops/python:drivetrain",
+ "@pip//glog",
+ "@pip//python_gflags",
+ ],
+)
+
+py_binary(
+ name = "polydrivetrain",
+ srcs = [
+ "drivetrain.py",
+ "polydrivetrain.py",
+ ],
+ legacy_create_init = False,
+ target_compatible_with = ["@platforms//cpu:x86_64"],
+ deps = [
+ ":python_init",
+ "//frc971/control_loops/python:polydrivetrain",
+ "@pip//glog",
+ "@pip//python_gflags",
+ ],
+)
+
+py_library(
+ name = "polydrivetrain_lib",
+ srcs = [
+ "drivetrain.py",
+ "polydrivetrain.py",
+ ],
+ target_compatible_with = ["@platforms//cpu:x86_64"],
+ visibility = ["//visibility:public"],
+ deps = [
+ "//frc971/control_loops/python:controls",
+ "//frc971/control_loops/python:drivetrain",
+ "//frc971/control_loops/python:polydrivetrain",
+ "@pip//glog",
+ "@pip//python_gflags",
+ ],
+)
+
+py_library(
+ name = "python_init",
+ srcs = ["__init__.py"],
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+ deps = ["//y2023/control_loops:python_init"],
+)
diff --git a/y2023/control_loops/python/__init__.py b/y2023/control_loops/python/__init__.py
new file mode 100644
index 0000000..e69de29
--- /dev/null
+++ b/y2023/control_loops/python/__init__.py
diff --git a/y2023/control_loops/python/drivetrain.py b/y2023/control_loops/python/drivetrain.py
new file mode 100644
index 0000000..863684c
--- /dev/null
+++ b/y2023/control_loops/python/drivetrain.py
@@ -0,0 +1,47 @@
+#!/usr/bin/python3
+
+from __future__ import print_function
+from frc971.control_loops.python import drivetrain
+from frc971.control_loops.python import control_loop
+import sys
+
+import gflags
+import glog
+
+FLAGS = gflags.FLAGS
+
+gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+
+kDrivetrain = drivetrain.DrivetrainParams(
+ J=6.0,
+ mass=58.0,
+ # TODO(austin): Measure radius a bit better.
+ robot_radius=0.39,
+ wheel_radius=2.5 * 0.0254,
+ motor_type=control_loop.Falcon(),
+ num_motors=3,
+ G=(14.0 / 54.0) * (22.0 / 56.0),
+ q_pos=0.24,
+ q_vel=2.5,
+ efficiency=0.80,
+ has_imu=True,
+ force=True,
+ kf_q_voltage=1.0,
+ controller_poles=[0.82, 0.82])
+
+
+def main(argv):
+ argv = FLAGS(argv)
+ glog.init()
+
+ if FLAGS.plot:
+ drivetrain.PlotDrivetrainMotions(kDrivetrain)
+ elif len(argv) != 5:
+ print("Expected .h file name and .cc file name")
+ else:
+ # Write the generated constants out to a file.
+ drivetrain.WriteDrivetrain(argv[1:3], argv[3:5], 'y2023', kDrivetrain)
+
+
+if __name__ == '__main__':
+ sys.exit(main(sys.argv))
diff --git a/y2023/control_loops/python/polydrivetrain.py b/y2023/control_loops/python/polydrivetrain.py
new file mode 100644
index 0000000..2f2346d
--- /dev/null
+++ b/y2023/control_loops/python/polydrivetrain.py
@@ -0,0 +1,33 @@
+#!/usr/bin/python3
+
+import sys
+from y2023.control_loops.python import drivetrain
+from frc971.control_loops.python import polydrivetrain
+
+import gflags
+import glog
+
+__author__ = 'Austin Schuh (austin.linux@gmail.com)'
+
+FLAGS = gflags.FLAGS
+
+try:
+ gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+except gflags.DuplicateFlagError:
+ pass
+
+
+def main(argv):
+ if FLAGS.plot:
+ polydrivetrain.PlotPolyDrivetrainMotions(drivetrain.kDrivetrain)
+ elif len(argv) != 7:
+ glog.fatal('Expected .h file name and .cc file name')
+ else:
+ polydrivetrain.WritePolyDrivetrain(argv[1:3], argv[3:5], argv[5:7],
+ 'y2023', drivetrain.kDrivetrain)
+
+
+if __name__ == '__main__':
+ argv = FLAGS(sys.argv)
+ glog.init()
+ sys.exit(main(argv))
diff --git a/y2023/control_loops/superstructure/BUILD b/y2023/control_loops/superstructure/BUILD
new file mode 100644
index 0000000..5246b3e
--- /dev/null
+++ b/y2023/control_loops/superstructure/BUILD
@@ -0,0 +1,145 @@
+load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
+load("@com_github_google_flatbuffers//:typescript.bzl", "flatbuffer_ts_library")
+load("@npm//@bazel/typescript:index.bzl", "ts_library")
+
+package(default_visibility = ["//visibility:public"])
+
+flatbuffer_cc_library(
+ name = "superstructure_goal_fbs",
+ srcs = [
+ "superstructure_goal.fbs",
+ ],
+ gen_reflections = 1,
+ includes = [
+ "//frc971/control_loops:control_loops_fbs_includes",
+ "//frc971/control_loops:profiled_subsystem_fbs_includes",
+ ],
+)
+
+flatbuffer_cc_library(
+ name = "superstructure_output_fbs",
+ srcs = [
+ "superstructure_output.fbs",
+ ],
+ gen_reflections = 1,
+)
+
+flatbuffer_cc_library(
+ name = "superstructure_status_fbs",
+ srcs = [
+ "superstructure_status.fbs",
+ ],
+ gen_reflections = 1,
+ includes = [
+ "//frc971/control_loops:control_loops_fbs_includes",
+ "//frc971/control_loops:profiled_subsystem_fbs_includes",
+ ],
+)
+
+flatbuffer_ts_library(
+ name = "superstructure_status_ts_fbs",
+ srcs = [
+ "superstructure_status.fbs",
+ ],
+ deps = [
+ "//frc971/control_loops:control_loops_ts_fbs",
+ "//frc971/control_loops:profiled_subsystem_ts_fbs",
+ ],
+)
+
+flatbuffer_cc_library(
+ name = "superstructure_position_fbs",
+ srcs = [
+ "superstructure_position.fbs",
+ ],
+ gen_reflections = 1,
+ includes = [
+ "//frc971/control_loops:control_loops_fbs_includes",
+ "//frc971/control_loops:profiled_subsystem_fbs_includes",
+ ],
+)
+
+cc_library(
+ name = "superstructure_lib",
+ srcs = [
+ "superstructure.cc",
+ ],
+ hdrs = [
+ "superstructure.h",
+ ],
+ deps = [
+ # ":collision_avoidance_lib",
+ ":superstructure_goal_fbs",
+ ":superstructure_output_fbs",
+ ":superstructure_position_fbs",
+ ":superstructure_status_fbs",
+ "//aos:flatbuffer_merge",
+ "//aos/events:event_loop",
+ "//frc971/control_loops:control_loop",
+ "//frc971/control_loops/drivetrain:drivetrain_status_fbs",
+ "//y2023:constants",
+ ],
+)
+
+cc_binary(
+ name = "superstructure",
+ srcs = [
+ "superstructure_main.cc",
+ ],
+ deps = [
+ ":superstructure_lib",
+ "//aos:init",
+ "//aos/events:shm_event_loop",
+ ],
+)
+
+cc_test(
+ name = "superstructure_lib_test",
+ srcs = [
+ "superstructure_lib_test.cc",
+ ],
+ data = [
+ "//y2023:aos_config",
+ ],
+ deps = [
+ ":superstructure_goal_fbs",
+ ":superstructure_lib",
+ ":superstructure_output_fbs",
+ ":superstructure_position_fbs",
+ ":superstructure_status_fbs",
+ "//aos:math",
+ "//aos/events/logging:log_writer",
+ "//aos/testing:googletest",
+ "//aos/time",
+ "//frc971/control_loops:capped_test_plant",
+ "//frc971/control_loops:control_loop_test",
+ "//frc971/control_loops:position_sensor_sim",
+ "//frc971/control_loops:subsystem_simulator",
+ "//frc971/control_loops:team_number_test_environment",
+ "//frc971/control_loops/drivetrain:drivetrain_status_fbs",
+ ],
+)
+
+cc_binary(
+ name = "superstructure_replay",
+ srcs = ["superstructure_replay.cc"],
+ deps = [
+ ":superstructure_lib",
+ "//aos:configuration",
+ "//aos:init",
+ "//aos/events:simulated_event_loop",
+ "//aos/events/logging:log_reader",
+ "//aos/network:team_number",
+ ],
+)
+
+ts_library(
+ name = "superstructure_plotter",
+ srcs = ["superstructure_plotter.ts"],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ "//aos/network/www:aos_plotter",
+ "//aos/network/www:colors",
+ "//aos/network/www:proxy",
+ ],
+)
diff --git a/y2023/control_loops/superstructure/superstructure.cc b/y2023/control_loops/superstructure/superstructure.cc
new file mode 100644
index 0000000..1125e21
--- /dev/null
+++ b/y2023/control_loops/superstructure/superstructure.cc
@@ -0,0 +1,66 @@
+#include "y2023/control_loops/superstructure/superstructure.h"
+
+#include "aos/events/event_loop.h"
+#include "aos/flatbuffer_merge.h"
+#include "aos/network/team_number.h"
+#include "frc971/zeroing/wrap.h"
+
+DEFINE_bool(ignore_distance, false,
+ "If true, ignore distance when shooting and obay joystick_reader");
+
+namespace y2023 {
+namespace control_loops {
+namespace superstructure {
+
+using frc971::control_loops::AbsoluteEncoderProfiledJointStatus;
+using frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus;
+using frc971::control_loops::RelativeEncoderProfiledJointStatus;
+
+Superstructure::Superstructure(::aos::EventLoop *event_loop,
+ std::shared_ptr<const constants::Values> values,
+ const ::std::string &name)
+ : frc971::controls::ControlLoop<Goal, Position, Status, Output>(event_loop,
+ name),
+ values_(values),
+ drivetrain_status_fetcher_(
+ event_loop->MakeFetcher<frc971::control_loops::drivetrain::Status>(
+ "/drivetrain")),
+ joystick_state_fetcher_(
+ event_loop->MakeFetcher<aos::JoystickState>("/aos")) {
+ (void)values;
+}
+
+void Superstructure::RunIteration(const Goal *unsafe_goal,
+ const Position *position,
+ aos::Sender<Output>::Builder *output,
+ aos::Sender<Status>::Builder *status) {
+ (void)unsafe_goal;
+ (void)position;
+
+ if (WasReset()) {
+ AOS_LOG(ERROR, "WPILib reset, restarting\n");
+ }
+
+ OutputT output_struct;
+ if (joystick_state_fetcher_.Fetch() &&
+ joystick_state_fetcher_->has_alliance()) {
+ alliance_ = joystick_state_fetcher_->alliance();
+ }
+ drivetrain_status_fetcher_.Fetch();
+ output->CheckOk(output->Send(Output::Pack(*output->fbb(), &output_struct)));
+
+ Status::Builder status_builder = status->MakeBuilder<Status>();
+ status_builder.add_zeroed(true);
+ status_builder.add_estopped(false);
+ (void)status->Send(status_builder.Finish());
+}
+
+double Superstructure::robot_velocity() const {
+ return (drivetrain_status_fetcher_.get() != nullptr
+ ? drivetrain_status_fetcher_->robot_speed()
+ : 0.0);
+}
+
+} // namespace superstructure
+} // namespace control_loops
+} // namespace y2023
diff --git a/y2023/control_loops/superstructure/superstructure.h b/y2023/control_loops/superstructure/superstructure.h
new file mode 100644
index 0000000..0740de3
--- /dev/null
+++ b/y2023/control_loops/superstructure/superstructure.h
@@ -0,0 +1,57 @@
+#ifndef Y2023_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
+#define Y2023_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
+
+#include "aos/events/event_loop.h"
+#include "frc971/control_loops/control_loop.h"
+#include "frc971/control_loops/drivetrain/drivetrain_status_generated.h"
+#include "y2023/constants.h"
+#include "y2023/control_loops/superstructure/superstructure_goal_generated.h"
+#include "y2023/control_loops/superstructure/superstructure_output_generated.h"
+#include "y2023/control_loops/superstructure/superstructure_position_generated.h"
+#include "y2023/control_loops/superstructure/superstructure_status_generated.h"
+
+namespace y2023 {
+namespace control_loops {
+namespace superstructure {
+
+class Superstructure
+ : public ::frc971::controls::ControlLoop<Goal, Position, Status, Output> {
+ public:
+ using RelativeEncoderSubsystem =
+ ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystem<
+ ::frc971::zeroing::RelativeEncoderZeroingEstimator,
+ ::frc971::control_loops::RelativeEncoderProfiledJointStatus>;
+
+ using PotAndAbsoluteEncoderSubsystem =
+ ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystem<
+ ::frc971::zeroing::PotAndAbsoluteEncoderZeroingEstimator,
+ ::frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus>;
+
+ explicit Superstructure(::aos::EventLoop *event_loop,
+ std::shared_ptr<const constants::Values> values,
+ const ::std::string &name = "/superstructure");
+
+ double robot_velocity() const;
+
+ protected:
+ virtual void RunIteration(const Goal *unsafe_goal, const Position *position,
+ aos::Sender<Output>::Builder *output,
+ aos::Sender<Status>::Builder *status) override;
+
+ private:
+ std::shared_ptr<const constants::Values> values_;
+
+ aos::Fetcher<frc971::control_loops::drivetrain::Status>
+ drivetrain_status_fetcher_;
+ aos::Fetcher<aos::JoystickState> joystick_state_fetcher_;
+
+ aos::Alliance alliance_ = aos::Alliance::kInvalid;
+
+ DISALLOW_COPY_AND_ASSIGN(Superstructure);
+};
+
+} // namespace superstructure
+} // namespace control_loops
+} // namespace y2023
+
+#endif // Y2023_CONTROL_LOOPS_SUPERSTRUCTURE_SUPERSTRUCTURE_H_
diff --git a/y2023/control_loops/superstructure/superstructure_goal.fbs b/y2023/control_loops/superstructure/superstructure_goal.fbs
new file mode 100644
index 0000000..412abbd
--- /dev/null
+++ b/y2023/control_loops/superstructure/superstructure_goal.fbs
@@ -0,0 +1,11 @@
+include "frc971/control_loops/profiled_subsystem.fbs";
+
+namespace y2023.control_loops.superstructure;
+
+
+table Goal {
+}
+
+
+
+root_type Goal;
diff --git a/y2023/control_loops/superstructure/superstructure_lib_test.cc b/y2023/control_loops/superstructure/superstructure_lib_test.cc
new file mode 100644
index 0000000..0b9fb7d
--- /dev/null
+++ b/y2023/control_loops/superstructure/superstructure_lib_test.cc
@@ -0,0 +1,295 @@
+#include <chrono>
+#include <memory>
+
+#include "aos/events/logging/log_writer.h"
+#include "frc971/control_loops/capped_test_plant.h"
+#include "frc971/control_loops/control_loop_test.h"
+#include "frc971/control_loops/position_sensor_sim.h"
+#include "frc971/control_loops/subsystem_simulator.h"
+#include "frc971/control_loops/team_number_test_environment.h"
+#include "gtest/gtest.h"
+#include "y2023/control_loops/drivetrain/drivetrain_dog_motor_plant.h"
+#include "y2023/control_loops/superstructure/superstructure.h"
+
+DEFINE_string(output_folder, "",
+ "If set, logs all channels to the provided logfile.");
+
+namespace y2023 {
+namespace control_loops {
+namespace superstructure {
+namespace testing {
+namespace chrono = std::chrono;
+
+using ::aos::monotonic_clock;
+using ::frc971::CreateProfileParameters;
+using ::frc971::control_loops::CappedTestPlant;
+using ::frc971::control_loops::
+ CreateStaticZeroingSingleDOFProfiledSubsystemGoal;
+using ::frc971::control_loops::PositionSensorSimulator;
+using ::frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
+typedef Superstructure::PotAndAbsoluteEncoderSubsystem
+ PotAndAbsoluteEncoderSubsystem;
+typedef Superstructure::RelativeEncoderSubsystem RelativeEncoderSubsystem;
+using DrivetrainStatus = ::frc971::control_loops::drivetrain::Status;
+using PotAndAbsoluteEncoderSimulator =
+ frc971::control_loops::SubsystemSimulator<
+ frc971::control_loops::PotAndAbsoluteEncoderProfiledJointStatus,
+ PotAndAbsoluteEncoderSubsystem::State,
+ constants::Values::PotAndAbsEncoderConstants>;
+using RelativeEncoderSimulator = frc971::control_loops::SubsystemSimulator<
+ frc971::control_loops::RelativeEncoderProfiledJointStatus,
+ RelativeEncoderSubsystem::State, constants::Values::PotConstants>;
+
+// Class which simulates the superstructure and sends out queue messages with
+// the position.
+class SuperstructureSimulation {
+ public:
+ SuperstructureSimulation(::aos::EventLoop *event_loop,
+ std::shared_ptr<const constants::Values> values,
+ chrono::nanoseconds dt)
+ : event_loop_(event_loop),
+ dt_(dt),
+ superstructure_position_sender_(
+ event_loop_->MakeSender<Position>("/superstructure")),
+ superstructure_status_fetcher_(
+ event_loop_->MakeFetcher<Status>("/superstructure")),
+ superstructure_output_fetcher_(
+ event_loop_->MakeFetcher<Output>("/superstructure")) {
+ (void)values;
+ (void)dt_;
+
+ phased_loop_handle_ = event_loop_->AddPhasedLoop(
+ [this](int) {
+ // Skip this the first time.
+ if (!first_) {
+ EXPECT_TRUE(superstructure_output_fetcher_.Fetch());
+ EXPECT_TRUE(superstructure_status_fetcher_.Fetch());
+ }
+ first_ = false;
+ SendPositionMessage();
+ },
+ dt);
+ }
+
+ // Sends a queue message with the position of the superstructure.
+ void SendPositionMessage() {
+ ::aos::Sender<Position>::Builder builder =
+ superstructure_position_sender_.MakeBuilder();
+
+ Position::Builder position_builder = builder.MakeBuilder<Position>();
+
+ CHECK_EQ(builder.Send(position_builder.Finish()),
+ aos::RawSender::Error::kOk);
+ }
+
+ private:
+ ::aos::EventLoop *event_loop_;
+ const chrono::nanoseconds dt_;
+ ::aos::PhasedLoopHandler *phased_loop_handle_ = nullptr;
+
+ ::aos::Sender<Position> superstructure_position_sender_;
+ ::aos::Fetcher<Status> superstructure_status_fetcher_;
+ ::aos::Fetcher<Output> superstructure_output_fetcher_;
+
+ bool first_ = true;
+};
+
+class SuperstructureTest : public ::frc971::testing::ControlLoopTest {
+ public:
+ SuperstructureTest()
+ : ::frc971::testing::ControlLoopTest(
+ aos::configuration::ReadConfig("y2023/aos_config.json"),
+ std::chrono::microseconds(5050)),
+ values_(std::make_shared<constants::Values>(constants::MakeValues())),
+ roborio_(aos::configuration::GetNode(configuration(), "roborio")),
+ logger_pi_(aos::configuration::GetNode(configuration(), "logger")),
+ superstructure_event_loop(MakeEventLoop("Superstructure", roborio_)),
+ superstructure_(superstructure_event_loop.get(), values_),
+ test_event_loop_(MakeEventLoop("test", roborio_)),
+ superstructure_goal_fetcher_(
+ test_event_loop_->MakeFetcher<Goal>("/superstructure")),
+ superstructure_goal_sender_(
+ test_event_loop_->MakeSender<Goal>("/superstructure")),
+ superstructure_status_fetcher_(
+ test_event_loop_->MakeFetcher<Status>("/superstructure")),
+ superstructure_output_fetcher_(
+ test_event_loop_->MakeFetcher<Output>("/superstructure")),
+ superstructure_position_fetcher_(
+ test_event_loop_->MakeFetcher<Position>("/superstructure")),
+ superstructure_position_sender_(
+ test_event_loop_->MakeSender<Position>("/superstructure")),
+ drivetrain_status_sender_(
+ test_event_loop_->MakeSender<DrivetrainStatus>("/drivetrain")),
+ superstructure_plant_event_loop_(MakeEventLoop("plant", roborio_)),
+ superstructure_plant_(superstructure_plant_event_loop_.get(), values_,
+ dt()) {
+ (void)values_;
+ set_team_id(frc971::control_loops::testing::kTeamNumber);
+
+ SetEnabled(true);
+
+ if (!FLAGS_output_folder.empty()) {
+ unlink(FLAGS_output_folder.c_str());
+ logger_event_loop_ = MakeEventLoop("logger", roborio_);
+ logger_ = std::make_unique<aos::logger::Logger>(logger_event_loop_.get());
+ logger_->StartLoggingOnRun(FLAGS_output_folder);
+ }
+ }
+
+ void VerifyNearGoal() {
+ superstructure_goal_fetcher_.Fetch();
+ superstructure_status_fetcher_.Fetch();
+ }
+
+ void CheckIfZeroed() {
+ superstructure_status_fetcher_.Fetch();
+ ASSERT_TRUE(superstructure_status_fetcher_.get()->zeroed());
+ }
+
+ void WaitUntilZeroed() {
+ int i = 0;
+ do {
+ i++;
+ RunFor(dt());
+ superstructure_status_fetcher_.Fetch();
+ // 2 Seconds
+ ASSERT_LE(i, 2.0 / ::aos::time::DurationInSeconds(dt()));
+
+ // Since there is a delay when sending running, make sure we have a
+ // status before checking it.
+ } while (superstructure_status_fetcher_.get() == nullptr ||
+ !superstructure_status_fetcher_.get()->zeroed());
+ }
+
+ void SendRobotVelocity(double robot_velocity) {
+ SendDrivetrainStatus(robot_velocity, {0.0, 0.0}, 0.0);
+ }
+
+ void SendDrivetrainStatus(double robot_velocity, Eigen::Vector2d pos,
+ double theta) {
+ // Send a robot velocity to test compensation
+ auto builder = drivetrain_status_sender_.MakeBuilder();
+ auto drivetrain_status_builder = builder.MakeBuilder<DrivetrainStatus>();
+ drivetrain_status_builder.add_robot_speed(robot_velocity);
+ drivetrain_status_builder.add_estimated_left_velocity(robot_velocity);
+ drivetrain_status_builder.add_estimated_right_velocity(robot_velocity);
+ drivetrain_status_builder.add_x(pos.x());
+ drivetrain_status_builder.add_y(pos.y());
+ drivetrain_status_builder.add_theta(theta);
+ builder.CheckOk(builder.Send(drivetrain_status_builder.Finish()));
+ }
+
+ std::shared_ptr<const constants::Values> values_;
+
+ const aos::Node *const roborio_;
+ const aos::Node *const logger_pi_;
+
+ ::std::unique_ptr<::aos::EventLoop> superstructure_event_loop;
+ ::y2023::control_loops::superstructure::Superstructure superstructure_;
+ ::std::unique_ptr<::aos::EventLoop> test_event_loop_;
+ ::aos::PhasedLoopHandler *phased_loop_handle_ = nullptr;
+
+ ::aos::Fetcher<Goal> superstructure_goal_fetcher_;
+ ::aos::Sender<Goal> superstructure_goal_sender_;
+ ::aos::Fetcher<Status> superstructure_status_fetcher_;
+ ::aos::Fetcher<Output> superstructure_output_fetcher_;
+ ::aos::Fetcher<Position> superstructure_position_fetcher_;
+ ::aos::Sender<Position> superstructure_position_sender_;
+ ::aos::Sender<DrivetrainStatus> drivetrain_status_sender_;
+
+ ::std::unique_ptr<::aos::EventLoop> superstructure_plant_event_loop_;
+ SuperstructureSimulation superstructure_plant_;
+
+ std::unique_ptr<aos::EventLoop> logger_event_loop_;
+ std::unique_ptr<aos::logger::Logger> logger_;
+}; // namespace testing
+
+// Tests that the superstructure does nothing when the goal is to remain
+// still.
+TEST_F(SuperstructureTest, DoesNothing) {
+ SetEnabled(true);
+
+ WaitUntilZeroed();
+
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+
+ ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
+ }
+ RunFor(chrono::seconds(10));
+ VerifyNearGoal();
+
+ EXPECT_TRUE(superstructure_output_fetcher_.Fetch());
+}
+
+// Tests that loops can reach a goal.
+TEST_F(SuperstructureTest, ReachesGoal) {
+ SetEnabled(true);
+
+ WaitUntilZeroed();
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+
+ ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
+ }
+
+ // Give it a lot of time to get there.
+ RunFor(chrono::seconds(15));
+
+ VerifyNearGoal();
+}
+
+// Makes sure that the voltage on a motor is properly pulled back after
+// saturation such that we don't get weird or bad (e.g. oscillating)
+// behaviour.
+TEST_F(SuperstructureTest, SaturationTest) {
+ SetEnabled(true);
+
+ // Zero it before we move.
+ WaitUntilZeroed();
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+
+ ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
+ }
+ RunFor(chrono::seconds(20));
+ VerifyNearGoal();
+
+ // Try a low acceleration move with a high max velocity and verify the
+ // acceleration is capped like expected.
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+
+ Goal::Builder goal_builder = builder.MakeBuilder<Goal>();
+
+ ASSERT_EQ(builder.Send(goal_builder.Finish()), aos::RawSender::Error::kOk);
+ }
+
+ // Intake needs over 9 seconds to reach the goal
+ // TODO(Milo): Make this a sane time
+ RunFor(chrono::seconds(20));
+ VerifyNearGoal();
+}
+
+// Tests that the loop zeroes when run for a while without a goal.
+TEST_F(SuperstructureTest, ZeroNoGoal) {
+ SetEnabled(true);
+ WaitUntilZeroed();
+ RunFor(chrono::seconds(2));
+}
+
+// Tests that running disabled works
+TEST_F(SuperstructureTest, DisableTest) {
+ RunFor(chrono::seconds(2));
+ CheckIfZeroed();
+}
+
+} // namespace testing
+} // namespace superstructure
+} // namespace control_loops
+} // namespace y2023
diff --git a/y2023/control_loops/superstructure/superstructure_main.cc b/y2023/control_loops/superstructure/superstructure_main.cc
new file mode 100644
index 0000000..bb25ad8
--- /dev/null
+++ b/y2023/control_loops/superstructure/superstructure_main.cc
@@ -0,0 +1,21 @@
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "y2023/control_loops/superstructure/superstructure.h"
+
+int main(int argc, char **argv) {
+ ::aos::InitGoogle(&argc, &argv);
+
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig("aos_config.json");
+
+ ::aos::ShmEventLoop event_loop(&config.message());
+ std::shared_ptr<const y2023::constants::Values> values =
+ std::make_shared<const y2023::constants::Values>(
+ y2023::constants::MakeValues());
+ ::y2023::control_loops::superstructure::Superstructure superstructure(
+ &event_loop, values);
+
+ event_loop.Run();
+
+ return 0;
+}
diff --git a/y2023/control_loops/superstructure/superstructure_output.fbs b/y2023/control_loops/superstructure/superstructure_output.fbs
new file mode 100644
index 0000000..43de3d2
--- /dev/null
+++ b/y2023/control_loops/superstructure/superstructure_output.fbs
@@ -0,0 +1,6 @@
+namespace y2023.control_loops.superstructure;
+
+table Output {
+}
+
+root_type Output;
diff --git a/y2023/control_loops/superstructure/superstructure_plotter.ts b/y2023/control_loops/superstructure/superstructure_plotter.ts
new file mode 100644
index 0000000..ae20119
--- /dev/null
+++ b/y2023/control_loops/superstructure/superstructure_plotter.ts
@@ -0,0 +1,115 @@
+// Provides a plot for debugging robot state-related issues.
+import {AosPlotter} from 'org_frc971/aos/network/www/aos_plotter';
+import {BLUE, BROWN, CYAN, GREEN, PINK, RED, WHITE} from 'org_frc971/aos/network/www/colors';
+import * as proxy from 'org_frc971/aos/network/www/proxy';
+
+import Connection = proxy.Connection;
+
+const TIME = AosPlotter.TIME;
+const DEFAULT_WIDTH = AosPlotter.DEFAULT_WIDTH * 2;
+const DEFAULT_HEIGHT = AosPlotter.DEFAULT_HEIGHT * 3;
+
+export function plotSuperstructure(conn: Connection, element: Element): void {
+ const aosPlotter = new AosPlotter(conn);
+ const goal = aosPlotter.addMessageSource(
+ '/superstructure', 'y2023.control_loops.superstructure.Goal');
+ const output = aosPlotter.addMessageSource(
+ '/superstructure', 'y2023.control_loops.superstructure.Output');
+ const status = aosPlotter.addMessageSource(
+ '/superstructure', 'y2023.control_loops.superstructure.Status');
+ const position = aosPlotter.addMessageSource(
+ '/superstructure', 'y2023.control_loops.superstructure.Position');
+ const robotState = aosPlotter.addMessageSource('/aos', 'aos.RobotState');
+
+ const positionPlot =
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ positionPlot.plot.getAxisLabels().setTitle('States');
+ positionPlot.plot.getAxisLabels().setXLabel(TIME);
+ positionPlot.plot.getAxisLabels().setYLabel('wonky state units');
+ positionPlot.plot.setDefaultYRange([-1.0, 2.0]);
+
+ positionPlot.addMessageLine(position, ['turret_beambreak'])
+ .setColor(RED)
+ .setPointSize(4.0);
+ positionPlot.addMessageLine(status, ['state'])
+ .setColor(PINK)
+ .setPointSize(4.0);
+ positionPlot.addMessageLine(status, ['flippers_open'])
+ .setColor(WHITE)
+ .setPointSize(1.0);
+ positionPlot.addMessageLine(status, ['reseating_in_catapult'])
+ .setColor(BLUE)
+ .setPointSize(1.0);
+ positionPlot.addMessageLine(status, ['fire'])
+ .setColor(BROWN)
+ .setPointSize(1.0);
+ positionPlot.addMessageLine(status, ['ready_to_fire'])
+ .setColor(GREEN)
+ .setPointSize(1.0);
+ positionPlot.addMessageLine(status, ['collided'])
+ .setColor(PINK)
+ .setPointSize(1.0);
+
+ const goalPlot =
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ goalPlot.plot.getAxisLabels().setTitle('Goal');
+ goalPlot.plot.getAxisLabels().setXLabel(TIME);
+ goalPlot.plot.getAxisLabels().setYLabel('value');
+ goalPlot.plot.setDefaultYRange([-1.0, 2.0]);
+ goalPlot.addMessageLine(goal, ['fire']).setColor(RED).setPointSize(1.0);
+ goalPlot.addMessageLine(goal, ['auto_aim']).setColor(BLUE).setPointSize(1.0);
+
+
+ const shotCountPlot =
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ shotCountPlot.plot.getAxisLabels().setTitle('Shot Count');
+ shotCountPlot.plot.getAxisLabels().setXLabel(TIME);
+ shotCountPlot.plot.getAxisLabels().setYLabel('balls');
+ shotCountPlot.plot.setDefaultYRange([-1.0, 2.0]);
+ shotCountPlot.addMessageLine(status, ['shot_count'])
+ .setColor(RED)
+ .setPointSize(1.0);
+
+ const intakePlot =
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ intakePlot.plot.getAxisLabels().setTitle('Intake');
+ intakePlot.plot.getAxisLabels().setXLabel(TIME);
+ intakePlot.plot.getAxisLabels().setYLabel('wonky state units');
+ intakePlot.plot.setDefaultYRange([-1.0, 2.0]);
+ intakePlot.addMessageLine(status, ['intake_state'])
+ .setColor(RED)
+ .setPointSize(1.0);
+ intakePlot.addMessageLine(position, ['intake_beambreak_front'])
+ .setColor(GREEN)
+ .setPointSize(4.0);
+ intakePlot.addMessageLine(position, ['intake_beambreak_back'])
+ .setColor(PINK)
+ .setPointSize(1.0);
+ intakePlot.addMessageLine(output, ['transfer_roller_voltage'])
+ .setColor(BROWN)
+ .setPointSize(3.0);
+
+
+ const otherPlot =
+ aosPlotter.addPlot(element, [DEFAULT_WIDTH, DEFAULT_HEIGHT / 2]);
+ otherPlot.plot.getAxisLabels().setTitle('Position');
+ otherPlot.plot.getAxisLabels().setXLabel(TIME);
+ otherPlot.plot.getAxisLabels().setYLabel('rad');
+ otherPlot.plot.setDefaultYRange([-1.0, 2.0]);
+
+ otherPlot.addMessageLine(status, ['catapult', 'position'])
+ .setColor(PINK)
+ .setPointSize(4.0);
+ otherPlot.addMessageLine(status, ['turret', 'position'])
+ .setColor(WHITE)
+ .setPointSize(4.0);
+ otherPlot.addMessageLine(position, ['flipper_arm_left', 'encoder'])
+ .setColor(BLUE)
+ .setPointSize(4.0);
+ otherPlot.addMessageLine(position, ['flipper_arm_right', 'encoder'])
+ .setColor(CYAN)
+ .setPointSize(4.0);
+ otherPlot.addMessageLine(output, ['flipper_arms_voltage'])
+ .setColor(BROWN)
+ .setPointSize(4.0);
+}
diff --git a/y2023/control_loops/superstructure/superstructure_position.fbs b/y2023/control_loops/superstructure/superstructure_position.fbs
new file mode 100644
index 0000000..49abd28
--- /dev/null
+++ b/y2023/control_loops/superstructure/superstructure_position.fbs
@@ -0,0 +1,8 @@
+include "frc971/control_loops/control_loops.fbs";
+
+namespace y2023.control_loops.superstructure;
+
+table Position {
+}
+
+root_type Position;
diff --git a/y2023/control_loops/superstructure/superstructure_replay.cc b/y2023/control_loops/superstructure/superstructure_replay.cc
new file mode 100644
index 0000000..ed97966
--- /dev/null
+++ b/y2023/control_loops/superstructure/superstructure_replay.cc
@@ -0,0 +1,74 @@
+// This binary allows us to replay the superstructure code over existing
+// logfile. When you run this code, it generates a new logfile with the data all
+// replayed, so that it can then be run through the plotting tool or analyzed
+// in some other way. The original superstructure status data will be on the
+// /original/superstructure channel.
+#include "aos/events/logging/log_reader.h"
+#include "aos/events/logging/log_writer.h"
+#include "aos/events/simulated_event_loop.h"
+#include "aos/init.h"
+#include "aos/json_to_flatbuffer.h"
+#include "aos/logging/log_message_generated.h"
+#include "aos/network/team_number.h"
+#include "gflags/gflags.h"
+#include "y2023/constants.h"
+#include "y2023/control_loops/superstructure/superstructure.h"
+
+DEFINE_int32(team, 971, "Team number to use for logfile replay.");
+DEFINE_string(output_folder, "/tmp/superstructure_replay/",
+ "Logs all channels to the provided logfile.");
+
+int main(int argc, char **argv) {
+ aos::InitGoogle(&argc, &argv);
+
+ aos::network::OverrideTeamNumber(FLAGS_team);
+
+ // open logfiles
+ aos::logger::LogReader reader(
+ aos::logger::SortParts(aos::logger::FindLogs(argc, argv)));
+ // TODO(james): Actually enforce not sending on the same buses as the logfile
+ // spews out.
+ reader.RemapLoggedChannel("/superstructure",
+ "y2023.control_loops.superstructure.Status");
+ reader.RemapLoggedChannel("/superstructure",
+ "y2023.control_loops.superstructure.Output");
+
+ aos::SimulatedEventLoopFactory factory(reader.configuration());
+ reader.Register(&factory);
+
+ aos::NodeEventLoopFactory *roborio =
+ factory.GetNodeEventLoopFactory("roborio");
+
+ unlink(FLAGS_output_folder.c_str());
+ std::unique_ptr<aos::EventLoop> logger_event_loop =
+ roborio->MakeEventLoop("logger");
+ auto logger = std::make_unique<aos::logger::Logger>(logger_event_loop.get());
+ logger->StartLoggingOnRun(FLAGS_output_folder);
+
+ roborio->OnStartup([roborio]() {
+ roborio->AlwaysStart<y2023::control_loops::superstructure::Superstructure>(
+ "superstructure", std::make_shared<y2023::constants::Values>(
+ y2023::constants::MakeValues()));
+ });
+
+ std::unique_ptr<aos::EventLoop> print_loop = roborio->MakeEventLoop("print");
+ print_loop->SkipAosLog();
+ print_loop->MakeWatcher(
+ "/aos", [&print_loop](const aos::logging::LogMessageFbs &msg) {
+ LOG(INFO) << print_loop->context().monotonic_event_time << " "
+ << aos::FlatbufferToJson(&msg);
+ });
+ print_loop->MakeWatcher(
+ "/superstructure",
+ [&](const y2023::control_loops::superstructure::Status &status) {
+ if (status.estopped()) {
+ LOG(ERROR) << "Estopped";
+ }
+ });
+
+ factory.Run();
+
+ reader.Deregister();
+
+ return 0;
+}
diff --git a/y2023/control_loops/superstructure/superstructure_status.fbs b/y2023/control_loops/superstructure/superstructure_status.fbs
new file mode 100644
index 0000000..ef9667d
--- /dev/null
+++ b/y2023/control_loops/superstructure/superstructure_status.fbs
@@ -0,0 +1,15 @@
+include "frc971/control_loops/control_loops.fbs";
+include "frc971/control_loops/profiled_subsystem.fbs";
+
+namespace y2023.control_loops.superstructure;
+
+
+table Status {
+ // All subsystems know their location.
+ zeroed:bool (id: 0);
+
+ // If true, we have aborted. This is the or of all subsystem estops.
+ estopped:bool (id: 1);
+}
+
+root_type Status;
diff --git a/y2023/joystick_reader.cc b/y2023/joystick_reader.cc
new file mode 100644
index 0000000..a1a42f4
--- /dev/null
+++ b/y2023/joystick_reader.cc
@@ -0,0 +1,99 @@
+#include <unistd.h>
+
+#include <cmath>
+#include <cstdio>
+#include <cstring>
+
+#include "aos/actions/actions.h"
+#include "aos/init.h"
+#include "aos/logging/logging.h"
+#include "aos/network/team_number.h"
+#include "aos/util/log_interval.h"
+#include "frc971/autonomous/base_autonomous_actor.h"
+#include "frc971/control_loops/drivetrain/localizer_generated.h"
+#include "frc971/control_loops/profiled_subsystem_generated.h"
+#include "frc971/input/action_joystick_input.h"
+#include "frc971/input/driver_station_data.h"
+#include "frc971/input/drivetrain_input.h"
+#include "frc971/input/joystick_input.h"
+#include "frc971/zeroing/wrap.h"
+#include "y2023/constants.h"
+#include "y2023/control_loops/drivetrain/drivetrain_base.h"
+#include "y2023/control_loops/superstructure/superstructure_goal_generated.h"
+#include "y2023/control_loops/superstructure/superstructure_status_generated.h"
+
+using frc971::CreateProfileParameters;
+using frc971::control_loops::CreateStaticZeroingSingleDOFProfiledSubsystemGoal;
+using frc971::control_loops::StaticZeroingSingleDOFProfiledSubsystemGoal;
+using frc971::input::driver_station::ButtonLocation;
+using frc971::input::driver_station::ControlBit;
+using frc971::input::driver_station::JoystickAxis;
+using frc971::input::driver_station::POVLocation;
+
+namespace y2023 {
+namespace input {
+namespace joysticks {
+
+namespace superstructure = y2023::control_loops::superstructure;
+
+class Reader : public ::frc971::input::ActionJoystickInput {
+ public:
+ Reader(::aos::EventLoop *event_loop)
+ : ::frc971::input::ActionJoystickInput(
+ event_loop,
+ ::y2023::control_loops::drivetrain::GetDrivetrainConfig(),
+ ::frc971::input::DrivetrainInputReader::InputType::kPistol, {}),
+ superstructure_goal_sender_(
+ event_loop->MakeSender<superstructure::Goal>("/superstructure")),
+ superstructure_status_fetcher_(
+ event_loop->MakeFetcher<superstructure::Status>(
+ "/superstructure")) {}
+
+ void AutoEnded() override { AOS_LOG(INFO, "Auto ended.\n"); }
+
+ void HandleTeleop(
+ const ::frc971::input::driver_station::Data &data) override {
+ superstructure_status_fetcher_.Fetch();
+ if (!superstructure_status_fetcher_.get()) {
+ AOS_LOG(ERROR, "Got no superstructure status message.\n");
+ return;
+ }
+
+ (void)data;
+ // TODO(Xander): Use driverstaion data to provide instructions.
+ {
+ auto builder = superstructure_goal_sender_.MakeBuilder();
+
+ superstructure::Goal::Builder superstructure_goal_builder =
+ builder.MakeBuilder<superstructure::Goal>();
+
+ if (builder.Send(superstructure_goal_builder.Finish()) !=
+ aos::RawSender::Error::kOk) {
+ AOS_LOG(ERROR, "Sending superstructure goal failed.\n");
+ }
+ }
+ }
+
+ private:
+ ::aos::Sender<superstructure::Goal> superstructure_goal_sender_;
+
+ ::aos::Fetcher<superstructure::Status> superstructure_status_fetcher_;
+};
+
+} // namespace joysticks
+} // namespace input
+} // namespace y2023
+
+int main(int argc, char **argv) {
+ ::aos::InitGoogle(&argc, &argv);
+
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig("aos_config.json");
+
+ ::aos::ShmEventLoop event_loop(&config.message());
+ ::y2023::input::joysticks::Reader reader(&event_loop);
+
+ event_loop.Run();
+
+ return 0;
+}
diff --git a/y2023/log_web_proxy.sh b/y2023/log_web_proxy.sh
new file mode 100755
index 0000000..9bc589a
--- /dev/null
+++ b/y2023/log_web_proxy.sh
@@ -0,0 +1 @@
+./aos/network/log_web_proxy_main --data_dir=y2023/www $@
diff --git a/y2023/message_bridge_client.sh b/y2023/message_bridge_client.sh
new file mode 100755
index 0000000..733905e
--- /dev/null
+++ b/y2023/message_bridge_client.sh
@@ -0,0 +1,41 @@
+#!/bin/bash
+
+while true;
+do
+ ping -c 1 pi1 -W 1 && break;
+ sleep 1
+done
+while true;
+do
+ ping -c 1 pi2 -W 1 && break;
+ sleep 1
+done
+while true;
+do
+ ping -c 1 pi3 -W 1 && break;
+ sleep 1
+done
+while true;
+do
+ ping -c 1 pi4 -W 1 && break;
+ sleep 1
+done
+while true;
+do
+ ping -c 1 pi5 -W 1 && break;
+ sleep 1
+done
+while true;
+do
+ ping -c 1 pi6 -W 1 && break;
+ sleep 1
+done
+while true;
+do
+ ping -c 1 roborio -W 1 && break;
+ sleep 1
+done
+
+echo Pinged
+
+exec message_bridge_client "$@"
diff --git a/y2023/vision/BUILD b/y2023/vision/BUILD
index 2f93b16..106ee5d 100644
--- a/y2023/vision/BUILD
+++ b/y2023/vision/BUILD
@@ -1,3 +1,13 @@
+load("@com_github_google_flatbuffers//:build_defs.bzl", "flatbuffer_cc_library")
+
+flatbuffer_cc_library(
+ name = "calibration_fbs",
+ srcs = ["calibration.fbs"],
+ gen_reflections = 1,
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//y2023:__subpackages__"],
+)
+
cc_binary(
name = "camera_reader",
srcs = [
diff --git a/y2023/vision/calibration.fbs b/y2023/vision/calibration.fbs
new file mode 100644
index 0000000..f5e30a6
--- /dev/null
+++ b/y2023/vision/calibration.fbs
@@ -0,0 +1,55 @@
+namespace frc971.vision.calibration;
+
+table TransformationMatrix {
+ // The matrix data for a row-major 4x4 homogeneous transformation matrix.
+ // This implies the bottom row is (0, 0, 0, 1).
+ data:[float] (id: 0);
+}
+
+// Calibration information for a given camera on a given robot.
+table CameraCalibration {
+ // The name of the camera node which this calibration data applies to.
+ node_name:string (id: 0);
+ // The team number of the robot which this calibration data applies to.
+ team_number:int (id: 1);
+
+ // Intrinsics for the camera.
+ //
+ // This is the standard OpenCV intrinsics matrix in row major order (3x3).
+ intrinsics:[float] (id: 2);
+
+ // Fixed extrinsics for the camera. This transforms from camera coordinates to
+ // robot coordinates. For example: multiplying (0, 0, 0, 1) by this results in
+ // the position of the camera aperture in robot coordinates.
+ fixed_extrinsics:TransformationMatrix (id: 3);
+
+ // Extrinsics for a camera on a turret. This will only be filled out for
+ // applicable cameras. For turret-mounted cameras, fixed_extrinsics defines
+ // a position for the center of rotation of the turret, and this field defines
+ // a position for the camera on the turret.
+ //
+ // The combination of the two transformations is underdefined, so nothing can
+ // distinguish between the two parts of the final extrinsics for a given
+ // turret position.
+ //
+ // To get the final extrinsics for a camera using this transformation,
+ // multiply (in order):
+ // fixed_extrinsics
+ // rotation around the Z axis by the turret angle
+ // turret_extrinsics
+ turret_extrinsics:TransformationMatrix (id: 4);
+
+ // This is the standard OpenCV 5 parameter distortion coefficients
+ dist_coeffs:[float] (id: 5);
+
+ // Timestamp for when the calibration was taken on the realtime clock.
+ calibration_timestamp:int64 (id: 6);
+}
+
+// Calibration information for all the cameras we know about.
+table CalibrationData {
+ camera_calibrations:[CameraCalibration] (id: 0);
+}
+
+
+root_type CalibrationData;
diff --git a/y2023/vision/camera_reader.cc b/y2023/vision/camera_reader.cc
index 3466c83..7004225 100644
--- a/y2023/vision/camera_reader.cc
+++ b/y2023/vision/camera_reader.cc
@@ -8,7 +8,7 @@
DEFINE_string(config, "aos_config.json", "Path to the config file to use.");
-namespace y2022 {
+namespace y2023 {
namespace vision {
namespace {
@@ -102,9 +102,9 @@
} // namespace
} // namespace vision
-} // namespace y2022
+} // namespace y2023
int main(int argc, char **argv) {
aos::InitGoogle(&argc, &argv);
- y2022::vision::CameraReaderMain();
+ y2023::vision::CameraReaderMain();
}
diff --git a/y2023/wpilib_interface.cc b/y2023/wpilib_interface.cc
new file mode 100644
index 0000000..77ff5af
--- /dev/null
+++ b/y2023/wpilib_interface.cc
@@ -0,0 +1,310 @@
+#include <unistd.h>
+
+#include <array>
+#include <chrono>
+#include <cinttypes>
+#include <cmath>
+#include <cstdio>
+#include <cstring>
+#include <functional>
+#include <memory>
+#include <mutex>
+#include <thread>
+
+#include "ctre/phoenix/CANifier.h"
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/Counter.h"
+#include "frc971/wpilib/ahal/DigitalGlitchFilter.h"
+#include "frc971/wpilib/ahal/DriverStation.h"
+#include "frc971/wpilib/ahal/Encoder.h"
+#include "frc971/wpilib/ahal/Servo.h"
+#include "frc971/wpilib/ahal/TalonFX.h"
+#include "frc971/wpilib/ahal/VictorSP.h"
+#undef ERROR
+
+#include "aos/commonmath.h"
+#include "aos/events/event_loop.h"
+#include "aos/events/shm_event_loop.h"
+#include "aos/init.h"
+#include "aos/logging/logging.h"
+#include "aos/realtime.h"
+#include "aos/time/time.h"
+#include "aos/util/log_interval.h"
+#include "aos/util/phased_loop.h"
+#include "aos/util/wrapping_counter.h"
+#include "ctre/phoenix/motorcontrol/can/TalonFX.h"
+#include "ctre/phoenix/motorcontrol/can/TalonSRX.h"
+#include "frc971/autonomous/auto_mode_generated.h"
+#include "frc971/control_loops/drivetrain/drivetrain_position_generated.h"
+#include "frc971/input/robot_state_generated.h"
+#include "frc971/queues/gyro_generated.h"
+#include "frc971/wpilib/ADIS16448.h"
+#include "frc971/wpilib/buffered_pcm.h"
+#include "frc971/wpilib/buffered_solenoid.h"
+#include "frc971/wpilib/dma.h"
+#include "frc971/wpilib/drivetrain_writer.h"
+#include "frc971/wpilib/encoder_and_potentiometer.h"
+#include "frc971/wpilib/joystick_sender.h"
+#include "frc971/wpilib/logging_generated.h"
+#include "frc971/wpilib/loop_output_handler.h"
+#include "frc971/wpilib/pdp_fetcher.h"
+#include "frc971/wpilib/sensor_reader.h"
+#include "frc971/wpilib/wpilib_robot_base.h"
+#include "y2023/constants.h"
+#include "y2023/control_loops/superstructure/superstructure_output_generated.h"
+#include "y2023/control_loops/superstructure/superstructure_position_generated.h"
+
+using ::aos::monotonic_clock;
+using ::y2023::constants::Values;
+namespace superstructure = ::y2023::control_loops::superstructure;
+namespace chrono = ::std::chrono;
+using std::make_unique;
+
+namespace y2023 {
+namespace wpilib {
+namespace {
+
+constexpr double kMaxBringupPower = 12.0;
+
+// TODO(Brian): Fix the interpretation of the result of GetRaw here and in the
+// DMA stuff and then removing the * 2.0 in *_translate.
+// The low bit is direction.
+
+double drivetrain_velocity_translate(double in) {
+ return (((1.0 / in) / Values::kDrivetrainCyclesPerRevolution()) *
+ (2.0 * M_PI)) *
+ Values::kDrivetrainEncoderRatio() *
+ control_loops::drivetrain::kWheelRadius;
+}
+
+constexpr double kMaxFastEncoderPulsesPerSecond =
+ /*std::max({*/ Values::kMaxDrivetrainEncoderPulsesPerSecond() /*,
+ Values::kMaxIntakeEncoderPulsesPerSecond()})*/
+ ;
+/*static_assert(kMaxFastEncoderPulsesPerSecond <= 1300000,
+ "fast encoders are too fast");*/
+
+} // namespace
+
+// Class to send position messages with sensor readings to our loops.
+class SensorReader : public ::frc971::wpilib::SensorReader {
+ public:
+ SensorReader(::aos::ShmEventLoop *event_loop,
+ std::shared_ptr<const Values> values)
+ : ::frc971::wpilib::SensorReader(event_loop),
+ values_(std::move(values)),
+ auto_mode_sender_(
+ event_loop->MakeSender<::frc971::autonomous::AutonomousMode>(
+ "/autonomous")),
+ superstructure_position_sender_(
+ event_loop->MakeSender<superstructure::Position>(
+ "/superstructure")),
+ drivetrain_position_sender_(
+ event_loop
+ ->MakeSender<::frc971::control_loops::drivetrain::Position>(
+ "/drivetrain")),
+ gyro_sender_(event_loop->MakeSender<::frc971::sensors::GyroReading>(
+ "/drivetrain")) {
+ // Set to filter out anything shorter than 1/4 of the minimum pulse width
+ // we should ever see.
+ UpdateFastEncoderFilterHz(kMaxFastEncoderPulsesPerSecond);
+ }
+
+ void Start() override {
+ // TODO(Ravago): Figure out why adding multiple DMA readers results in weird
+ // behavior
+ // AddToDMA(&imu_heading_reader_);
+ AddToDMA(&imu_yaw_rate_reader_);
+ }
+
+ // Auto mode switches.
+ void set_autonomous_mode(int i, ::std::unique_ptr<frc::DigitalInput> sensor) {
+ autonomous_modes_.at(i) = ::std::move(sensor);
+ }
+
+ void RunIteration() override {
+ superstructure_reading_->Set(true);
+ { auto builder = superstructure_position_sender_.MakeBuilder(); }
+
+ {
+ auto builder = drivetrain_position_sender_.MakeBuilder();
+ frc971::control_loops::drivetrain::Position::Builder drivetrain_builder =
+ builder.MakeBuilder<frc971::control_loops::drivetrain::Position>();
+ drivetrain_builder.add_left_encoder(
+ constants::Values::DrivetrainEncoderToMeters(
+ drivetrain_left_encoder_->GetRaw()));
+ drivetrain_builder.add_left_speed(
+ drivetrain_velocity_translate(drivetrain_left_encoder_->GetPeriod()));
+
+ drivetrain_builder.add_right_encoder(
+ -constants::Values::DrivetrainEncoderToMeters(
+ drivetrain_right_encoder_->GetRaw()));
+ drivetrain_builder.add_right_speed(-drivetrain_velocity_translate(
+ drivetrain_right_encoder_->GetPeriod()));
+
+ builder.CheckOk(builder.Send(drivetrain_builder.Finish()));
+ }
+
+ {
+ auto builder = gyro_sender_.MakeBuilder();
+ ::frc971::sensors::GyroReading::Builder gyro_reading_builder =
+ builder.MakeBuilder<::frc971::sensors::GyroReading>();
+ // +/- 2000 deg / sec
+ constexpr double kMaxVelocity = 4000; // degrees / second
+ constexpr double kVelocityRadiansPerSecond =
+ kMaxVelocity / 360 * (2.0 * M_PI);
+
+ // Only part of the full range is used to prevent being 100% on or off.
+ constexpr double kScaledRangeLow = 0.1;
+ constexpr double kScaledRangeHigh = 0.9;
+
+ constexpr double kPWMFrequencyHz = 200;
+ double heading_duty_cycle =
+ imu_heading_reader_.last_width() * kPWMFrequencyHz;
+ double velocity_duty_cycle =
+ imu_yaw_rate_reader_.last_width() * kPWMFrequencyHz;
+
+ constexpr double kDutyCycleScale =
+ 1 / (kScaledRangeHigh - kScaledRangeLow);
+ // scale from 0.1 - 0.9 to 0 - 1
+ double rescaled_heading_duty_cycle =
+ (heading_duty_cycle - kScaledRangeLow) * kDutyCycleScale;
+ double rescaled_velocity_duty_cycle =
+ (velocity_duty_cycle - kScaledRangeLow) * kDutyCycleScale;
+
+ if (!std::isnan(rescaled_heading_duty_cycle)) {
+ gyro_reading_builder.add_angle(rescaled_heading_duty_cycle *
+ (2.0 * M_PI));
+ }
+ if (!std::isnan(rescaled_velocity_duty_cycle)) {
+ gyro_reading_builder.add_velocity((rescaled_velocity_duty_cycle - 0.5) *
+ kVelocityRadiansPerSecond);
+ }
+ builder.CheckOk(builder.Send(gyro_reading_builder.Finish()));
+ }
+
+ {
+ auto builder = auto_mode_sender_.MakeBuilder();
+
+ uint32_t mode = 0;
+ for (size_t i = 0; i < autonomous_modes_.size(); ++i) {
+ if (autonomous_modes_[i] && autonomous_modes_[i]->Get()) {
+ mode |= 1 << i;
+ }
+ }
+
+ auto auto_mode_builder =
+ builder.MakeBuilder<frc971::autonomous::AutonomousMode>();
+
+ auto_mode_builder.add_mode(mode);
+
+ builder.CheckOk(builder.Send(auto_mode_builder.Finish()));
+ }
+ }
+
+ std::shared_ptr<frc::DigitalOutput> superstructure_reading_;
+
+ void set_superstructure_reading(
+ std::shared_ptr<frc::DigitalOutput> superstructure_reading) {
+ superstructure_reading_ = superstructure_reading;
+ }
+
+ private:
+ std::shared_ptr<const Values> values_;
+
+ aos::Sender<frc971::autonomous::AutonomousMode> auto_mode_sender_;
+ aos::Sender<superstructure::Position> superstructure_position_sender_;
+ aos::Sender<frc971::control_loops::drivetrain::Position>
+ drivetrain_position_sender_;
+ ::aos::Sender<::frc971::sensors::GyroReading> gyro_sender_;
+
+ std::array<std::unique_ptr<frc::DigitalInput>, 2> autonomous_modes_;
+
+ frc971::wpilib::DMAPulseWidthReader imu_heading_reader_, imu_yaw_rate_reader_;
+};
+
+class SuperstructureWriter
+ : public ::frc971::wpilib::LoopOutputHandler<superstructure::Output> {
+ public:
+ SuperstructureWriter(aos::EventLoop *event_loop)
+ : frc971::wpilib::LoopOutputHandler<superstructure::Output>(
+ event_loop, "/superstructure") {}
+
+ std::shared_ptr<frc::DigitalOutput> superstructure_reading_;
+
+ void set_superstructure_reading(
+ std::shared_ptr<frc::DigitalOutput> superstructure_reading) {
+ superstructure_reading_ = superstructure_reading;
+ }
+
+ private:
+ void Stop() override { AOS_LOG(WARNING, "Superstructure output too old.\n"); }
+
+ void Write(const superstructure::Output &output) override { (void)output; }
+
+ static void WriteCan(const double voltage,
+ ::ctre::phoenix::motorcontrol::can::TalonFX *falcon) {
+ falcon->Set(
+ ctre::phoenix::motorcontrol::ControlMode::PercentOutput,
+ std::clamp(voltage, -kMaxBringupPower, kMaxBringupPower) / 12.0);
+ }
+
+ template <typename T>
+ static void WritePwm(const double voltage, T *motor) {
+ motor->SetSpeed(std::clamp(voltage, -kMaxBringupPower, kMaxBringupPower) /
+ 12.0);
+ }
+};
+
+
+class WPILibRobot : public ::frc971::wpilib::WPILibRobotBase {
+ public:
+ ::std::unique_ptr<frc::Encoder> make_encoder(int index) {
+ return make_unique<frc::Encoder>(10 + index * 2, 11 + index * 2, false,
+ frc::Encoder::k4X);
+ }
+
+ void Run() override {
+ std::shared_ptr<const Values> values =
+ std::make_shared<const Values>(constants::MakeValues());
+
+ aos::FlatbufferDetachedBuffer<aos::Configuration> config =
+ aos::configuration::ReadConfig("aos_config.json");
+
+ // Thread 1.
+ // Thread 2.
+ ::aos::ShmEventLoop pdp_fetcher_event_loop(&config.message());
+ ::frc971::wpilib::PDPFetcher pdp_fetcher(&pdp_fetcher_event_loop);
+ AddLoop(&pdp_fetcher_event_loop);
+
+ std::shared_ptr<frc::DigitalOutput> superstructure_reading =
+ make_unique<frc::DigitalOutput>(25);
+
+ // Thread 3.
+ ::aos::ShmEventLoop sensor_reader_event_loop(&config.message());
+ SensorReader sensor_reader(&sensor_reader_event_loop, values);
+ sensor_reader.set_pwm_trigger(true);
+ sensor_reader.set_drivetrain_left_encoder(make_encoder(1));
+ sensor_reader.set_drivetrain_right_encoder(make_encoder(0));
+ sensor_reader.set_superstructure_reading(superstructure_reading);
+
+ AddLoop(&sensor_reader_event_loop);
+
+ // Thread 4.
+ ::aos::ShmEventLoop output_event_loop(&config.message());
+ ::frc971::wpilib::DrivetrainWriter drivetrain_writer(&output_event_loop);
+
+ SuperstructureWriter superstructure_writer(&output_event_loop);
+
+ superstructure_writer.set_superstructure_reading(superstructure_reading);
+
+ AddLoop(&output_event_loop);
+
+ RunLoops();
+ }
+};
+
+} // namespace wpilib
+} // namespace y2023
+
+AOS_ROBOT_CLASS(::y2023::wpilib::WPILibRobot);
diff --git a/y2023/www/2022.png b/y2023/www/2022.png
new file mode 100644
index 0000000..68087bd
--- /dev/null
+++ b/y2023/www/2022.png
Binary files differ
diff --git a/y2023/www/BUILD b/y2023/www/BUILD
new file mode 100644
index 0000000..5dae3c6
--- /dev/null
+++ b/y2023/www/BUILD
@@ -0,0 +1,53 @@
+load("@npm//@bazel/typescript:index.bzl", "ts_library")
+load("//tools/build_rules:js.bzl", "rollup_bundle")
+load("//frc971/downloader:downloader.bzl", "aos_downloader_dir")
+
+filegroup(
+ name = "files",
+ srcs = glob([
+ "**/*.html",
+ "**/*.css",
+ "**/*.png",
+ ]),
+ visibility = ["//visibility:public"],
+)
+
+ts_library(
+ name = "field_main",
+ srcs = [
+ "constants.ts",
+ "field_handler.ts",
+ "field_main.ts",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ "//aos/network:connect_ts_fbs",
+ "//aos/network:web_proxy_ts_fbs",
+ "//aos/network/www:proxy",
+ "//frc971/control_loops/drivetrain:drivetrain_status_ts_fbs",
+ "//y2023/control_loops/superstructure:superstructure_status_ts_fbs",
+ "@com_github_google_flatbuffers//ts:flatbuffers_ts",
+ ],
+)
+
+rollup_bundle(
+ name = "field_main_bundle",
+ entry_point = "field_main.ts",
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//y2023:__subpackages__"],
+ deps = [
+ ":field_main",
+ ],
+)
+
+aos_downloader_dir(
+ name = "www_files",
+ srcs = [
+ ":field_main_bundle.min.js",
+ ":files",
+ "//frc971/analysis:plot_index_bundle.min.js",
+ ],
+ dir = "www",
+ target_compatible_with = ["@platforms//os:linux"],
+ visibility = ["//visibility:public"],
+)
diff --git a/y2023/www/constants.ts b/y2023/www/constants.ts
new file mode 100644
index 0000000..b94d7a7
--- /dev/null
+++ b/y2023/www/constants.ts
@@ -0,0 +1,7 @@
+// Conversion constants to meters
+export const IN_TO_M = 0.0254;
+export const FT_TO_M = 0.3048;
+// Dimensions of the field in meters
+export const FIELD_WIDTH = 26 * FT_TO_M + 11.25 * IN_TO_M;
+export const FIELD_LENGTH = 52 * FT_TO_M + 5.25 * IN_TO_M;
+
diff --git a/y2023/www/field.html b/y2023/www/field.html
new file mode 100644
index 0000000..f39c1a4
--- /dev/null
+++ b/y2023/www/field.html
@@ -0,0 +1,126 @@
+<html>
+ <head>
+ <script src="field_main_bundle.min.js" defer></script>
+ <link rel="stylesheet" href="styles.css">
+ </head>
+ <body>
+ <div id="field"> </div>
+ <div id="legend"> </div>
+ <div id="readouts">
+ <table>
+ <tr>
+ <th colspan="2">Robot State</th>
+ </tr>
+ <tr>
+ <td>X</td>
+ <td id="x"> NA </td>
+ </tr>
+ <tr>
+ <td>Y</td>
+ <td id="y"> NA </td>
+ </tr>
+ <tr>
+ <td>Theta</td>
+ <td id="theta"> NA </td>
+ </tr>
+ </table>
+
+ <table>
+ <tr>
+ <th colspan="2">Aiming</th>
+ </tr>
+ <tr>
+ <td>Shot distance</td>
+ <td id="shot_distance"> NA </td>
+ </tr>
+ <tr>
+ <td>Turret</td>
+ <td id="turret"> NA </td>
+ </tr>
+ </table>
+
+ <table>
+ <tr>
+ <th colspan="2">Catapult</th>
+ </tr>
+ <tr>
+ <td>Fire</td>
+ <td id="fire"> NA </td>
+ </tr>
+ <tr>
+ <td>Solve Time</td>
+ <td id="mpc_solve_time"> NA </td>
+ </tr>
+ <tr>
+ <td>MPC Active</td>
+ <td id="mpc_horizon"> NA </td>
+ </tr>
+ <tr>
+ <td>Shot Count</td>
+ <td id="shot_count"> NA </td>
+ </tr>
+ <tr>
+ <td>Position</td>
+ <td id="catapult"> NA </td>
+ </tr>
+ </table>
+
+ <table>
+ <tr>
+ <th colspan="2">Superstructure</th>
+ </tr>
+ <tr>
+ <td>State</td>
+ <td id="superstructure_state"> NA </td>
+ </tr>
+ <tr>
+ <td>Intake State</td>
+ <td id="intake_state"> NA </td>
+ </tr>
+ <tr>
+ <td>Reseating</td>
+ <td id="reseating_in_catapult"> NA </td>
+ </tr>
+ <tr>
+ <td>Flippers Open</td>
+ <td id="flippers_open"> NA </td>
+ </tr>
+ <tr>
+ <td>Climber</td>
+ <td id="climber"> NA </td>
+ </tr>
+ </table>
+
+ <table>
+ <tr>
+ <th colspan="2">Intakes</th>
+ </tr>
+ <tr>
+ <td>Front Intake</td>
+ <td id="front_intake"> NA </td>
+ </tr>
+ <tr>
+ <td>Back Intake</td>
+ <td id="back_intake"> NA </td>
+ </tr>
+ </table>
+
+ <table>
+ <tr>
+ <th colspan="2">Images</th>
+ </tr>
+ <tr>
+ <td> Images Accepted </td>
+ <td id="images_accepted"> NA </td>
+ </tr>
+ <tr>
+ <td> Images Rejected </td>
+ <td id="images_rejected"> NA </td>
+ </tr>
+ </table>
+ </div>
+ <div id="vision_readouts">
+ </div>
+ </body>
+</html>
+
diff --git a/y2023/www/field_handler.ts b/y2023/www/field_handler.ts
new file mode 100644
index 0000000..67566ea
--- /dev/null
+++ b/y2023/www/field_handler.ts
@@ -0,0 +1,210 @@
+import {ByteBuffer} from 'flatbuffers';
+import {Connection} from '../../aos/network/www/proxy';
+import {Status as SuperstructureStatus} from '../control_loops/superstructure/superstructure_status_generated'
+import {Status as DrivetrainStatus} from '../../frc971/control_loops/drivetrain/drivetrain_status_generated';
+
+import {FIELD_LENGTH, FIELD_WIDTH, FT_TO_M, IN_TO_M} from './constants';
+
+// (0,0) is field center, +X is toward red DS
+const FIELD_SIDE_Y = FIELD_WIDTH / 2;
+const FIELD_EDGE_X = FIELD_LENGTH / 2;
+
+const ROBOT_WIDTH = 34 * IN_TO_M;
+const ROBOT_LENGTH = 36 * IN_TO_M;
+
+const PI_COLORS = ['#ff00ff', '#ffff00', '#00ffff', '#ffa500'];
+
+export class FieldHandler {
+ private canvas = document.createElement('canvas');
+ private drivetrainStatus: DrivetrainStatus|null = null;
+ private superstructureStatus: SuperstructureStatus|null = null;
+
+ // Image information indexed by timestamp (seconds since the epoch), so that
+ // we can stop displaying images after a certain amount of time.
+ private x: HTMLElement = (document.getElementById('x') as HTMLElement);
+ private y: HTMLElement = (document.getElementById('y') as HTMLElement);
+ private theta: HTMLElement =
+ (document.getElementById('theta') as HTMLElement);
+ private superstructureState: HTMLElement =
+ (document.getElementById('superstructure_state') as HTMLElement);
+ private imagesAcceptedCounter: HTMLElement =
+ (document.getElementById('images_accepted') as HTMLElement);
+ private imagesRejectedCounter: HTMLElement =
+ (document.getElementById('images_rejected') as HTMLElement);
+ private fieldImage: HTMLImageElement = new Image();
+
+ constructor(private readonly connection: Connection) {
+ (document.getElementById('field') as HTMLElement).appendChild(this.canvas);
+
+ this.fieldImage.src = "2022.png";
+
+ for (let ii = 0; ii < PI_COLORS.length; ++ii) {
+ const legendEntry = document.createElement('div');
+ legendEntry.style.color = PI_COLORS[ii];
+ legendEntry.innerHTML = 'PI' + (ii + 1).toString()
+ document.getElementById('legend').appendChild(legendEntry);
+ }
+
+ this.connection.addConfigHandler(() => {
+ // Visualization message is reliable so that we can see *all* the vision
+ // matches.
+ this.connection.addHandler(
+ '/drivetrain', "frc971.control_loops.drivetrain.Status", (data) => {
+ this.handleDrivetrainStatus(data);
+ });
+ this.connection.addHandler(
+ '/superstructure', "y2023.control_loops.superstructure.Status",
+ (data) => {
+ this.handleSuperstructureStatus(data);
+ });
+ });
+ }
+
+ private handleDrivetrainStatus(data: Uint8Array): void {
+ const fbBuffer = new ByteBuffer(data);
+ this.drivetrainStatus = DrivetrainStatus.getRootAsStatus(fbBuffer);
+ }
+
+ private handleSuperstructureStatus(data: Uint8Array): void {
+ const fbBuffer = new ByteBuffer(data);
+ this.superstructureStatus = SuperstructureStatus.getRootAsStatus(fbBuffer);
+ }
+
+ drawField(): void {
+ const ctx = this.canvas.getContext('2d');
+ ctx.save();
+ ctx.scale(-1.0, 1.0);
+ ctx.drawImage(
+ this.fieldImage, 0, 0, this.fieldImage.width, this.fieldImage.height,
+ -FIELD_EDGE_X, -FIELD_SIDE_Y, FIELD_LENGTH, FIELD_WIDTH);
+ ctx.restore();
+ }
+
+ drawCamera(
+ x: number, y: number, theta: number, color: string = 'blue',
+ extendLines: boolean = true): void {
+ const ctx = this.canvas.getContext('2d');
+ ctx.save();
+ ctx.translate(x, y);
+ ctx.rotate(theta);
+ ctx.strokeStyle = color;
+ ctx.beginPath();
+ ctx.moveTo(0.5, 0.5);
+ ctx.lineTo(0, 0);
+ if (extendLines) {
+ ctx.lineTo(100.0, 0);
+ ctx.lineTo(0, 0);
+ }
+ ctx.lineTo(0.5, -0.5);
+ ctx.stroke();
+ ctx.beginPath();
+ ctx.arc(0, 0, 0.25, -Math.PI / 4, Math.PI / 4);
+ ctx.stroke();
+ ctx.restore();
+ }
+
+ drawRobot(
+ x: number, y: number, theta: number, turret: number|null,
+ color: string = 'blue', dashed: boolean = false,
+ extendLines: boolean = true): void {
+ const ctx = this.canvas.getContext('2d');
+ ctx.save();
+ ctx.translate(x, y);
+ ctx.rotate(theta);
+ ctx.strokeStyle = color;
+ ctx.lineWidth = ROBOT_WIDTH / 10.0;
+ if (dashed) {
+ ctx.setLineDash([0.05, 0.05]);
+ } else {
+ // Empty array = solid line.
+ ctx.setLineDash([]);
+ }
+ ctx.rect(-ROBOT_LENGTH / 2, -ROBOT_WIDTH / 2, ROBOT_LENGTH, ROBOT_WIDTH);
+ ctx.stroke();
+
+ // Draw line indicating which direction is forwards on the robot.
+ ctx.beginPath();
+ ctx.moveTo(0, 0);
+ if (extendLines) {
+ ctx.lineTo(1000.0, 0);
+ } else {
+ ctx.lineTo(ROBOT_LENGTH / 2.0, 0);
+ }
+ ctx.stroke();
+
+ ctx.restore();
+ }
+
+ setZeroing(div: HTMLElement): void {
+ div.innerHTML = 'zeroing';
+ div.classList.remove('faulted');
+ div.classList.add('zeroing');
+ div.classList.remove('near');
+ }
+
+ setEstopped(div: HTMLElement): void {
+ div.innerHTML = 'estopped';
+ div.classList.add('faulted');
+ div.classList.remove('zeroing');
+ div.classList.remove('near');
+ }
+
+ setTargetValue(
+ div: HTMLElement, target: number, val: number, tolerance: number): void {
+ div.innerHTML = val.toFixed(4);
+ div.classList.remove('faulted');
+ div.classList.remove('zeroing');
+ if (Math.abs(target - val) < tolerance) {
+ div.classList.add('near');
+ } else {
+ div.classList.remove('near');
+ }
+ }
+
+ setValue(div: HTMLElement, val: number): void {
+ div.innerHTML = val.toFixed(4);
+ div.classList.remove('faulted');
+ div.classList.remove('zeroing');
+ div.classList.remove('near');
+ }
+
+ draw(): void {
+ this.reset();
+ this.drawField();
+
+ // Draw the matches with debugging information from the localizer.
+ const now = Date.now() / 1000.0;
+
+ if (this.drivetrainStatus && this.drivetrainStatus.trajectoryLogging()) {
+ this.drawRobot(
+ this.drivetrainStatus.trajectoryLogging().x(),
+ this.drivetrainStatus.trajectoryLogging().y(),
+ this.drivetrainStatus.trajectoryLogging().theta(), null, "#000000FF",
+ false);
+ }
+
+ window.requestAnimationFrame(() => this.draw());
+ }
+
+ reset(): void {
+ const ctx = this.canvas.getContext('2d');
+ ctx.setTransform(1, 0, 0, 1, 0, 0);
+ const size = window.innerHeight * 0.9;
+ ctx.canvas.height = size;
+ const width = size / 2 + 20;
+ ctx.canvas.width = width;
+ ctx.clearRect(0, 0, size, width);
+
+ // Translate to center of display.
+ ctx.translate(width / 2, size / 2);
+ // Coordinate system is:
+ // x -> forward.
+ // y -> to the left.
+ ctx.rotate(-Math.PI / 2);
+ ctx.scale(1, -1);
+
+ const M_TO_PX = (size - 10) / FIELD_LENGTH;
+ ctx.scale(M_TO_PX, M_TO_PX);
+ ctx.lineWidth = 1 / M_TO_PX;
+ }
+}
diff --git a/y2023/www/field_main.ts b/y2023/www/field_main.ts
new file mode 100644
index 0000000..7e2e392
--- /dev/null
+++ b/y2023/www/field_main.ts
@@ -0,0 +1,12 @@
+import {Connection} from 'org_frc971/aos/network/www/proxy';
+
+import {FieldHandler} from './field_handler';
+
+const conn = new Connection();
+
+conn.connect();
+
+const fieldHandler = new FieldHandler(conn);
+
+fieldHandler.draw();
+
diff --git a/y2023/www/index.html b/y2023/www/index.html
new file mode 100644
index 0000000..e4e185e
--- /dev/null
+++ b/y2023/www/index.html
@@ -0,0 +1,6 @@
+<html>
+ <body>
+ <a href="field.html">Field Visualization</a><br>
+ <a href="plotter.html">Plots</a>
+ </body>
+</html>
diff --git a/y2023/www/plotter.html b/y2023/www/plotter.html
new file mode 100644
index 0000000..629ceaa
--- /dev/null
+++ b/y2023/www/plotter.html
@@ -0,0 +1,7 @@
+<html>
+ <head>
+ <script src="plot_index_bundle.min.js" defer></script>
+ </head>
+ <body>
+ </body>
+</html>
diff --git a/y2023/www/styles.css b/y2023/www/styles.css
new file mode 100644
index 0000000..c486115
--- /dev/null
+++ b/y2023/www/styles.css
@@ -0,0 +1,81 @@
+.channel {
+ display: flex;
+ border-bottom: 1px solid;
+ font-size: 24px;
+}
+#field {
+ display: inline-block
+}
+
+#targets,
+#readouts,
+#vision_readouts {
+ display: inline-block;
+ vertical-align: top;
+ float: right;
+}
+
+#legend {
+ display: inline-block;
+}
+
+#outer_target {
+ border: 1px solid black;
+ width: 140px;
+ background-color: white;
+}
+
+#inner_target {
+ width: 60px;
+ height: 60px;
+ margin: 40px;
+ border: 1px solid black;
+ background-color: white;
+}
+
+#outer_target.targetted,
+#inner_target.targetted {
+ background-color: green;
+}
+
+table, th, td {
+ border: 1px solid black;
+ border-collapse: collapse;
+ padding: 5px;
+ margin: 10px;
+}
+
+th, td {
+ text-align: right;
+ width: 70px;
+}
+
+td:first-child {
+ width: 150px;
+}
+
+.near {
+ background-color: LightGreen;
+ border-radius: 10px;
+}
+
+.zeroing {
+ background-color: yellow;
+ border-radius: 10px;
+}
+
+.faulted {
+ background-color: red;
+ border-radius: 10px;
+}
+
+#vision_readouts > div {
+ display: table-row;
+ padding: 5px;
+}
+
+#vision_readouts > div > div {
+ display: table-cell;
+ padding: 5px;
+ text-align: right;
+}
diff --git a/y2023/y2023_imu.json b/y2023/y2023_imu.json
index 6b2ca7a..cc02067 100644
--- a/y2023/y2023_imu.json
+++ b/y2023/y2023_imu.json
@@ -303,7 +303,7 @@
"applications": [
{
"name": "message_bridge_client",
- "executable_name": "message_bridge_client",
+ "executable_name": "message_bridge_client.sh",
"nodes": [
"imu"
]
diff --git a/y2023/y2023_logger.json b/y2023/y2023_logger.json
index 6ddc19f..09038ae 100644
--- a/y2023/y2023_logger.json
+++ b/y2023/y2023_logger.json
@@ -13,12 +13,72 @@
"name": "logger",
"priority": 1,
"time_to_live": 5000000,
- "timestamp_logger" : "LOCAL_AND_REMOTE_LOGGER",
- "timestamp_logger_nodes" : ["roborio"]
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ]
}
]
},
{
+ "name": "/drivetrain",
+ "type": "frc971.control_loops.drivetrain.Position",
+ "source_node": "roborio",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "logger",
+ "priority": 2,
+ "time_to_live": 500000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ]
+ }
+ ]
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/logger/drivetrain/frc971-control_loops-drivetrain-Position",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "roborio",
+ "logger": "NOT_LOGGED",
+ "frequency": 400,
+ "num_senders": 2,
+ "max_size": 200
+ },
+ {
+ "name": "/drivetrain",
+ "type": "frc971.control_loops.drivetrain.Output",
+ "source_node": "roborio",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "logger"
+ ],
+ "destination_nodes": [
+ {
+ "name": "logger",
+ "priority": 2,
+ "time_to_live": 500000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "roborio"
+ ]
+ }
+ ]
+ },
+ {
+ "name": "/roborio/aos/remote_timestamps/logger/drivetrain/frc971-control_loops-drivetrain-Output",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "roborio",
+ "logger": "NOT_LOGGED",
+ "frequency": 400,
+ "num_senders": 2,
+ "max_size": 400
+ },
+ {
"name": "/pi1/aos",
"type": "aos.message_bridge.Timestamp",
"source_node": "pi1",
@@ -319,8 +379,8 @@
{
"name": "/localizer",
"type": "frc971.IMUValuesBatch",
- "logger": "LOCAL_AND_REMOTE_LOGGER",
"source_node": "imu",
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
"logger_nodes": [
"logger"
],
@@ -352,14 +412,16 @@
"name": "/logger/camera"
}
}
-
],
"applications": [
{
"name": "logger_message_bridge_client",
- "executable_name": "message_bridge_client",
"autostart": false,
- "args": ["--rmem=8388608", "--rt_priority=16"],
+ "executable_name": "message_bridge_client.sh",
+ "args": [
+ "--rmem=8388608",
+ "--rt_priority=16"
+ ],
"nodes": [
"logger"
]
@@ -368,7 +430,9 @@
"name": "logger_message_bridge_server",
"executable_name": "message_bridge_server",
"autostart": false,
- "args": ["--rt_priority=16"],
+ "args": [
+ "--rt_priority=16"
+ ],
"nodes": [
"logger"
]
@@ -377,7 +441,14 @@
"name": "image_logger",
"executable_name": "logger_main",
"autostart": false,
- "args": ["--snappy_compress", "--logging_folder", "", "--snappy_compress", "--rotate_every", "60.0"],
+ "args": [
+ "--snappy_compress",
+ "--logging_folder",
+ "",
+ "--snappy_compress",
+ "--rotate_every",
+ "60.0"
+ ],
"nodes": [
"logger"
]
diff --git a/y2023/y2023_pi_template.json b/y2023/y2023_pi_template.json
index 2bf45bb..1430753 100644
--- a/y2023/y2023_pi_template.json
+++ b/y2023/y2023_pi_template.json
@@ -273,9 +273,9 @@
"applications": [
{
"name": "message_bridge_client",
- "executable_name": "message_bridge_client",
"args": ["--rt_priority=16"],
"user": "pi",
+ "executable_name": "message_bridge_client.sh",
"nodes": [
"pi{{ NUM }}"
]
diff --git a/y2023/y2023_roborio.json b/y2023/y2023_roborio.json
index f10d901..4c5b282 100644
--- a/y2023/y2023_roborio.json
+++ b/y2023/y2023_roborio.json
@@ -256,6 +256,36 @@
]
},
{
+ "name": "/superstructure",
+ "type": "y2023.control_loops.superstructure.Goal",
+ "source_node": "roborio",
+ "frequency": 200,
+ "max_size": 512
+ },
+ {
+ "name": "/superstructure",
+ "type": "y2023.control_loops.superstructure.Status",
+ "source_node": "roborio",
+ "frequency": 400,
+ "num_senders": 2
+ },
+ {
+ "name": "/superstructure",
+ "type": "y2023.control_loops.superstructure.Output",
+ "source_node": "roborio",
+ "frequency": 200,
+ "num_senders": 2,
+ "max_size": 224
+ },
+ {
+ "name": "/superstructure",
+ "type": "y2023.control_loops.superstructure.Position",
+ "source_node": "roborio",
+ "frequency": 200,
+ "num_senders": 2,
+ "max_size": 448
+ },
+ {
"name": "/drivetrain",
"type": "frc971.sensors.GyroReading",
"source_node": "roborio",
@@ -423,6 +453,13 @@
]
},
{
+ "name": "superstructure",
+ "executable_name": "superstructure",
+ "nodes": [
+ "roborio"
+ ]
+ },
+ {
"name": "joystick_reader",
"executable_name": "joystick_reader",
"nodes": [
@@ -453,7 +490,7 @@
},
{
"name": "roborio_message_bridge_client",
- "executable_name": "message_bridge_client",
+ "executable_name": "message_bridge_client.sh",
"args": ["--rt_priority=16"],
"nodes": [
"roborio"