Merge changes I1af9552a,Ied7ac78c,Icd1f5d9d,I3ddbac7b,I762c62c6
* changes:
Swap SZSDPS to use ProfileParametersT
Make zeroing constants structs flatbuffers
Add flatbuffer Matrix table and library
Add additional error messages to json_to_flatbuffer
Support importing codegen'd files in jinja templates
diff --git a/frc971/control_loops/flywheel/BUILD b/frc971/control_loops/flywheel/BUILD
index 0cf5d00..f077682 100644
--- a/frc971/control_loops/flywheel/BUILD
+++ b/frc971/control_loops/flywheel/BUILD
@@ -1,3 +1,4 @@
+load("//aos:config.bzl", "aos_config")
load("//aos/flatbuffers:generate.bzl", "static_flatbuffer")
load("@com_github_google_flatbuffers//:typescript.bzl", "flatbuffer_ts_library")
@@ -46,3 +47,65 @@
"//frc971/control_loops:profiled_subsystem",
],
)
+
+cc_test(
+ name = "flywheel_controller_test",
+ srcs = ["flywheel_controller_test.cc"],
+ data = [
+ ":flywheel_controller_test_config",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+ deps = [
+ ":flywheel_controller",
+ ":flywheel_controller_test_plants",
+ ":flywheel_test_plant",
+ "//aos/testing:googletest",
+ "//frc971/control_loops:control_loop_test",
+ ],
+)
+
+aos_config(
+ name = "flywheel_controller_test_config",
+ src = "flywheel_controller_test_config_source.json",
+ flatbuffers = [
+ "//frc971/input:joystick_state_fbs",
+ "//frc971/input:robot_state_fbs",
+ "//aos/logging:log_message_fbs",
+ "//aos/events:event_loop_fbs",
+ ":flywheel_controller_status_fbs",
+ ],
+ target_compatible_with = ["@platforms//os:linux"],
+)
+
+genrule(
+ name = "genrule_flywheel_controller_test",
+ outs = [
+ "flywheel_controller_test_plant.h",
+ "flywheel_controller_test_plant.cc",
+ "integral_flywheel_controller_test_plant.h",
+ "integral_flywheel_controller_test_plant.cc",
+ ],
+ cmd = "$(location //frc971/control_loops/python:flywheel_controller_test) $(OUTS)",
+ target_compatible_with = ["@platforms//os:linux"],
+ tools = [
+ "//frc971/control_loops/python:flywheel_controller_test",
+ ],
+)
+
+cc_library(
+ name = "flywheel_controller_test_plants",
+ srcs = [
+ "flywheel_controller_test_plant.cc",
+ "integral_flywheel_controller_test_plant.cc",
+ ],
+ hdrs = [
+ "flywheel_controller_test_plant.h",
+ "integral_flywheel_controller_test_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",
+ ],
+)
diff --git a/frc971/control_loops/flywheel/flywheel_controller.cc b/frc971/control_loops/flywheel/flywheel_controller.cc
index adea0e8..dc82147 100644
--- a/frc971/control_loops/flywheel/flywheel_controller.cc
+++ b/frc971/control_loops/flywheel/flywheel_controller.cc
@@ -48,11 +48,18 @@
// Limit to the battery voltage and the current limit voltage.
mutable_U(0, 0) = std::clamp(U(0, 0), lower_limit, upper_limit);
- if (R(1) > 50.0) {
- mutable_U(0, 0) = std::clamp(U(0, 0), 1.0, 12.0);
- } else {
- mutable_U(0, 0) = std::clamp(U(0, 0), 0.0, 12.0);
+
+ double lower_clamp = (std::abs(R(1)) > 50.0) ? 1.0 : 0.0;
+ double upper_clamp = 12.0;
+
+ if (R(1) < 0.0) {
+ // If R(1) is negative, swap and invert.
+ std::swap(lower_clamp, upper_clamp);
+ lower_clamp *= -1.0;
+ upper_clamp *= -1.0;
}
+
+ mutable_U(0, 0) = std::clamp(U(0, 0), lower_clamp, upper_clamp);
}
private:
@@ -112,7 +119,8 @@
void FlywheelController::Update(bool disabled) {
loop_->mutable_R() = loop_->next_R();
- if (loop_->R(1, 0) < 1.0) {
+
+ if (std::abs(loop_->R(1, 0)) < 1.0) {
// Kill power at low angular velocities.
disabled = true;
}
diff --git a/frc971/control_loops/flywheel/flywheel_controller_status.fbs b/frc971/control_loops/flywheel/flywheel_controller_status.fbs
index 0f95818..5e079e3 100644
--- a/frc971/control_loops/flywheel/flywheel_controller_status.fbs
+++ b/frc971/control_loops/flywheel/flywheel_controller_status.fbs
@@ -20,3 +20,5 @@
// The angular velocity of the flywheel computed using delta x / delta t
dt_angular_velocity:double (id: 5);
}
+
+root_type FlywheelControllerStatus;
diff --git a/frc971/control_loops/flywheel/flywheel_controller_test.cc b/frc971/control_loops/flywheel/flywheel_controller_test.cc
new file mode 100644
index 0000000..26aabc9
--- /dev/null
+++ b/frc971/control_loops/flywheel/flywheel_controller_test.cc
@@ -0,0 +1,103 @@
+#include "frc971/control_loops/flywheel/flywheel_controller.h"
+
+#include "glog/logging.h"
+#include "gtest/gtest.h"
+
+#include "aos/configuration.h"
+#include "frc971/control_loops/control_loop_test.h"
+#include "frc971/control_loops/flywheel/flywheel_controller_test_plant.h"
+#include "frc971/control_loops/flywheel/flywheel_test_plant.h"
+#include "frc971/control_loops/flywheel/integral_flywheel_controller_test_plant.h"
+
+namespace frc971 {
+namespace control_loops {
+namespace flywheel {
+namespace testing {
+class FlywheelTest : public ::frc971::testing::ControlLoopTest {
+ public:
+ FlywheelTest()
+ : ::frc971::testing::ControlLoopTest(
+ aos::configuration::ReadConfig(
+ "frc971/control_loops/flywheel/"
+ "flywheel_controller_test_config.json"),
+ std::chrono::microseconds(5050)),
+ test_event_loop_(MakeEventLoop("test")),
+ flywheel_plant_(
+ new FlywheelPlant(MakeFlywheelTestPlant(), kBemf, kResistance)),
+ flywheel_controller_(MakeIntegralFlywheelTestLoop(), kBemf,
+ kResistance),
+ flywheel_controller_sender_(
+ test_event_loop_->MakeSender<FlywheelControllerStatus>("/loop")) {
+ phased_loop_handle_ =
+ test_event_loop_->AddPhasedLoop([this](int) { Simulate(); }, dt());
+ }
+
+ void Simulate() {
+ const aos::monotonic_clock::time_point timestamp =
+ test_event_loop_->context().monotonic_event_time;
+ ::Eigen::Matrix<double, 1, 1> flywheel_U;
+ flywheel_U << flywheel_voltage_ + flywheel_plant_->voltage_offset();
+
+ // Confirm that we aren't drawing too much current. 2 motors -> twice the
+ // lumped current since our model can't tell them apart.
+ CHECK_NEAR(flywheel_plant_->battery_current(flywheel_U), 0.0, 200.0);
+
+ flywheel_plant_->Update(flywheel_U);
+
+ flywheel_controller_.set_position(flywheel_plant_->Y(0, 0), timestamp);
+
+ flywheel_controller_.set_goal(goal_);
+
+ flywheel_controller_.Update(false);
+ aos::FlatbufferFixedAllocatorArray<FlywheelControllerStatus, 512>
+ flywheel_status_buffer;
+
+ flywheel_status_buffer.Finish(
+ flywheel_controller_.SetStatus(flywheel_status_buffer.fbb()));
+
+ flywheel_voltage_ = flywheel_controller_.voltage();
+
+ last_angular_velocity_ =
+ flywheel_status_buffer.message().angular_velocity();
+ }
+
+ void VerifyNearGoal() { EXPECT_NEAR(last_angular_velocity_, goal_, 0.1); }
+
+ void set_goal(double goal) { goal_ = goal; }
+
+ private:
+ ::std::unique_ptr<::aos::EventLoop> test_event_loop_;
+ ::aos::PhasedLoopHandler *phased_loop_handle_ = nullptr;
+
+ std::unique_ptr<FlywheelPlant> flywheel_plant_;
+ FlywheelController flywheel_controller_;
+
+ aos::Sender<FlywheelControllerStatus> flywheel_controller_sender_;
+
+ double last_angular_velocity_ = 0.0;
+
+ double flywheel_voltage_ = 0.0;
+ double goal_ = 0.0;
+};
+
+TEST_F(FlywheelTest, DoNothing) {
+ set_goal(0);
+ RunFor(std::chrono::seconds(2));
+ VerifyNearGoal();
+}
+
+TEST_F(FlywheelTest, PositiveTest) {
+ set_goal(700.0);
+ RunFor(std::chrono::seconds(4));
+ VerifyNearGoal();
+}
+
+TEST_F(FlywheelTest, NegativeTest) {
+ set_goal(-700.0);
+ RunFor(std::chrono::seconds(8));
+ VerifyNearGoal();
+}
+} // namespace testing
+} // namespace flywheel
+} // namespace control_loops
+} // namespace frc971
diff --git a/frc971/control_loops/flywheel/flywheel_controller_test_config_source.json b/frc971/control_loops/flywheel/flywheel_controller_test_config_source.json
new file mode 100644
index 0000000..1a9b727
--- /dev/null
+++ b/frc971/control_loops/flywheel/flywheel_controller_test_config_source.json
@@ -0,0 +1,27 @@
+{
+ "channels": [
+ {
+ "name": "/aos",
+ "type": "aos.JoystickState"
+ },
+ {
+ "name": "/aos",
+ "type": "aos.logging.LogMessageFbs",
+ "frequency": 400
+ },
+ {
+ "name": "/aos",
+ "type": "aos.RobotState",
+ "frequency": 250
+ },
+ {
+ "name": "/aos",
+ "type": "aos.timing.Report"
+ },
+ {
+ "name": "/loop",
+ "type": "frc971.control_loops.flywheel.FlywheelControllerStatus",
+ "frequency": 200
+ }
+ ]
+}
diff --git a/frc971/control_loops/python/BUILD b/frc971/control_loops/python/BUILD
index 699eb5a..7f458b5 100644
--- a/frc971/control_loops/python/BUILD
+++ b/frc971/control_loops/python/BUILD
@@ -202,7 +202,7 @@
data = glob([
"field_images/*.png",
"field_images/*.svg",
- ]) + ["//third_party/y2023/field:pictures"],
+ ]) + ["//third_party/y2023/field:pictures"] + ["//third_party/y2024/field:pictures"],
legacy_create_init = False,
target_compatible_with = ["@platforms//cpu:x86_64"],
visibility = ["//visibility:public"],
@@ -276,3 +276,19 @@
"@pip//python_gflags",
],
)
+
+py_binary(
+ name = "flywheel_controller_test",
+ srcs = [
+ "flywheel_controller_test.py",
+ ],
+ legacy_create_init = False,
+ target_compatible_with = ["@platforms//cpu:x86_64"],
+ deps = [
+ ":controls",
+ ":flywheel",
+ ":python_init",
+ "@pip//glog",
+ "@pip//python_gflags",
+ ],
+)
diff --git a/frc971/control_loops/python/constants.py b/frc971/control_loops/python/constants.py
index 7bc45db..e4ff6b7 100644
--- a/frc971/control_loops/python/constants.py
+++ b/frc971/control_loops/python/constants.py
@@ -37,6 +37,8 @@
Robot2021 = Robot2020
Robot2022 = RobotType(width=0.8763, length=0.96647)
Robot2023 = RobotType(width=0.6061, length=0.77581)
+#TODO (Nathan): Update 2024 robot dimensions when CAD is done
+Robot2024 = RobotType(width=0.9017, length=0.9525) # 35.5 in x 37.5 in
FIELDS = {
"2019 Field":
@@ -127,9 +129,17 @@
length=8.10895,
robot=Robot2023,
field_id="//third_party/y2023/field/2023.png"),
+ "2024 Field":
+ FieldType("2024 Field",
+ tags=[],
+ year=2024,
+ width=16.54175,
+ length=8.21055,
+ robot=Robot2024,
+ field_id="//third_party/y2024/field/2024.png"),
}
-FIELD = FIELDS["2023 Field"]
+FIELD = FIELDS["2024 Field"]
def get_json_folder(field):
@@ -139,6 +149,7 @@
return "y2022/actors/splines"
elif field.year == 2023:
return "y2023/autonomous/splines"
+ #TODO: Update 2024 spline jsons
else:
return "frc971/control_loops/python/spline_jsons"
diff --git a/frc971/control_loops/python/flywheel_controller_test.py b/frc971/control_loops/python/flywheel_controller_test.py
new file mode 100644
index 0000000..4f4d929
--- /dev/null
+++ b/frc971/control_loops/python/flywheel_controller_test.py
@@ -0,0 +1,48 @@
+#!/usr/bin/python3
+
+# Generates a test flywheel for flywheel_controller_test
+
+from frc971.control_loops.python import control_loop
+from frc971.control_loops.python import flywheel
+
+import numpy
+import sys
+import gflags
+import glog
+
+FLAGS = gflags.FLAGS
+
+try:
+ gflags.DEFINE_bool('plot', False, 'If true, plot the loop response.')
+except gflags.DuplicateFlagError:
+ pass
+
+kFlywheel = flywheel.FlywheelParams(name='FlywheelTest',
+ motor=control_loop.Falcon(),
+ G=(60.0 / 48.0),
+ J=0.0035,
+ q_pos=0.01,
+ q_vel=10.0,
+ q_voltage=4.0,
+ r_pos=0.01,
+ controller_poles=[.95])
+
+
+def main(argv):
+ if FLAGS.plot:
+ R = numpy.matrix([[0.0], [500.0], [0.0]])
+ flywheel.PlotSpinup(params=kFlywheel, goal=R, iterations=400)
+ return 0
+
+ # Write the generated constants out to a file.
+ if len(argv) != 5:
+ glog.fatal('Expected .h file name and .cc file name')
+ else:
+ namespaces = ['frc971', 'control_loops', 'flywheel']
+ flywheel.WriteFlywheel(kFlywheel, argv[1:3], argv[3:5], namespaces)
+
+
+if __name__ == '__main__':
+ argv = FLAGS(sys.argv)
+ glog.init()
+ sys.exit(main(argv))
diff --git a/frc971/wpilib/sensor_reader.h b/frc971/wpilib/sensor_reader.h
index 963cd6e..bf8c96a 100644
--- a/frc971/wpilib/sensor_reader.h
+++ b/frc971/wpilib/sensor_reader.h
@@ -8,7 +8,7 @@
#include "aos/events/shm_event_loop.h"
#include "aos/stl_mutex/stl_mutex.h"
#include "aos/time/time.h"
-#include "frc971/control_loops/control_loops_generated.h"
+#include "frc971/control_loops/control_loops_static.h"
#include "frc971/control_loops/drivetrain/drivetrain_position_static.h"
#include "frc971/input/robot_state_generated.h"
#include "frc971/wpilib/ahal/DigitalGlitchFilter.h"
@@ -65,149 +65,149 @@
// Copies a DMAEncoder to a IndexPosition with the correct unit and direction
// changes.
void CopyPosition(const ::frc971::wpilib::DMAEncoder &encoder,
- ::frc971::IndexPositionT *position,
+ ::frc971::IndexPositionStatic *position,
double encoder_counts_per_revolution, double encoder_ratio,
bool reverse) {
const double multiplier = reverse ? -1.0 : 1.0;
- position->encoder =
- multiplier * encoder_translate(encoder.polled_encoder_value(),
- encoder_counts_per_revolution,
- encoder_ratio);
- position->latched_encoder =
+ position->set_encoder(multiplier *
+ encoder_translate(encoder.polled_encoder_value(),
+ encoder_counts_per_revolution,
+ encoder_ratio));
+ position->set_latched_encoder(
multiplier * encoder_translate(encoder.last_encoder_value(),
encoder_counts_per_revolution,
- encoder_ratio);
- position->index_pulses = encoder.index_posedge_count();
+ encoder_ratio));
+ position->set_index_pulses(encoder.index_posedge_count());
}
// Copies a AbsoluteEncoderAndPotentiometer to a PotAndAbsolutePosition with
// the correct unit and direction changes.
void CopyPosition(
const ::frc971::wpilib::AbsoluteEncoderAndPotentiometer &encoder,
- ::frc971::PotAndAbsolutePositionT *position,
+ ::frc971::PotAndAbsolutePositionStatic *position,
double encoder_counts_per_revolution, double encoder_ratio,
::std::function<double(double)> potentiometer_translate, bool reverse,
double pot_offset) {
const double multiplier = reverse ? -1.0 : 1.0;
- position->pot = multiplier * potentiometer_translate(
- encoder.ReadPotentiometerVoltage()) +
- pot_offset;
- position->encoder =
- multiplier * encoder_translate(encoder.ReadRelativeEncoder(),
- encoder_counts_per_revolution,
- encoder_ratio);
+ position->set_pot(multiplier * potentiometer_translate(
+ encoder.ReadPotentiometerVoltage()) +
+ pot_offset);
+ position->set_encoder(multiplier *
+ encoder_translate(encoder.ReadRelativeEncoder(),
+ encoder_counts_per_revolution,
+ encoder_ratio));
- position->absolute_encoder =
- (reverse ? (1.0 - encoder.ReadAbsoluteEncoder())
- : encoder.ReadAbsoluteEncoder()) *
- encoder_ratio * (2.0 * M_PI);
+ position->set_absolute_encoder((reverse
+ ? (1.0 - encoder.ReadAbsoluteEncoder())
+ : encoder.ReadAbsoluteEncoder()) *
+ encoder_ratio * (2.0 * M_PI));
}
// Copies an AbsoluteEncoderAndPotentiometer to an AbsoluteAndAbsolutePosition
// with the correct unit and direction changes.
void CopyPosition(const ::frc971::wpilib::AbsoluteAndAbsoluteEncoder &encoder,
- ::frc971::AbsoluteAndAbsolutePositionT *position,
+ ::frc971::AbsoluteAndAbsolutePositionStatic *position,
double encoder_counts_per_revolution, double encoder_ratio,
double single_turn_encoder_ratio, bool reverse) {
const double multiplier = reverse ? -1.0 : 1.0;
- position->encoder =
- multiplier * encoder_translate(encoder.ReadRelativeEncoder(),
- encoder_counts_per_revolution,
- encoder_ratio);
+ position->set_encoder(multiplier *
+ encoder_translate(encoder.ReadRelativeEncoder(),
+ encoder_counts_per_revolution,
+ encoder_ratio));
- position->absolute_encoder =
- (reverse ? (1.0 - encoder.ReadAbsoluteEncoder())
- : encoder.ReadAbsoluteEncoder()) *
- encoder_ratio * (2.0 * M_PI);
+ position->set_absolute_encoder((reverse
+ ? (1.0 - encoder.ReadAbsoluteEncoder())
+ : encoder.ReadAbsoluteEncoder()) *
+ encoder_ratio * (2.0 * M_PI));
- position->single_turn_absolute_encoder =
+ position->set_single_turn_absolute_encoder(
(reverse ? (1.0 - encoder.ReadSingleTurnAbsoluteEncoder())
: encoder.ReadSingleTurnAbsoluteEncoder()) *
- single_turn_encoder_ratio * (2.0 * M_PI);
+ single_turn_encoder_ratio * (2.0 * M_PI));
}
// Copies a DMAEdgeCounter to a HallEffectAndPosition with the correct unit
// and direction changes.
void CopyPosition(const ::frc971::wpilib::DMAEdgeCounter &counter,
- ::frc971::HallEffectAndPositionT *position,
+ ::frc971::HallEffectAndPositionStatic *position,
double encoder_counts_per_revolution, double encoder_ratio,
bool reverse) {
const double multiplier = reverse ? -1.0 : 1.0;
- position->encoder =
- multiplier * encoder_translate(counter.polled_encoder(),
- encoder_counts_per_revolution,
- encoder_ratio);
- position->current = !counter.polled_value();
- position->posedge_count = counter.negative_count();
- position->negedge_count = counter.positive_count();
- position->posedge_value =
+ position->set_encoder(multiplier *
+ encoder_translate(counter.polled_encoder(),
+ encoder_counts_per_revolution,
+ encoder_ratio));
+ position->set_current(!counter.polled_value());
+ position->set_posedge_count(counter.negative_count());
+ position->set_negedge_count(counter.positive_count());
+ position->set_posedge_value(
multiplier * encoder_translate(counter.last_negative_encoder_value(),
encoder_counts_per_revolution,
- encoder_ratio);
- position->negedge_value =
+ encoder_ratio));
+ position->set_negedge_value(
multiplier * encoder_translate(counter.last_positive_encoder_value(),
encoder_counts_per_revolution,
- encoder_ratio);
+ encoder_ratio));
}
// Copies a Absolute Encoder with the correct unit
// and direction changes.
void CopyPosition(const ::frc971::wpilib::AbsoluteEncoder &encoder,
- ::frc971::AbsolutePositionT *position,
+ ::frc971::AbsolutePositionStatic *position,
double encoder_counts_per_revolution, double encoder_ratio,
bool reverse) {
const double multiplier = reverse ? -1.0 : 1.0;
- position->encoder =
- multiplier * encoder_translate(encoder.ReadRelativeEncoder(),
- encoder_counts_per_revolution,
- encoder_ratio);
+ position->set_encoder(multiplier *
+ encoder_translate(encoder.ReadRelativeEncoder(),
+ encoder_counts_per_revolution,
+ encoder_ratio));
- position->absolute_encoder =
- (reverse ? (1.0 - encoder.ReadAbsoluteEncoder())
- : encoder.ReadAbsoluteEncoder()) *
- encoder_ratio * (2.0 * M_PI);
+ position->set_absolute_encoder((reverse
+ ? (1.0 - encoder.ReadAbsoluteEncoder())
+ : encoder.ReadAbsoluteEncoder()) *
+ encoder_ratio * (2.0 * M_PI));
}
void CopyPosition(const ::frc971::wpilib::DMAEncoderAndPotentiometer &encoder,
- ::frc971::PotAndIndexPositionT *position,
+ ::frc971::PotAndIndexPositionStatic *position,
::std::function<double(int32_t)> encoder_translate,
::std::function<double(double)> potentiometer_translate,
bool reverse, double pot_offset) {
const double multiplier = reverse ? -1.0 : 1.0;
- position->encoder =
- multiplier * encoder_translate(encoder.polled_encoder_value());
- position->pot = multiplier * potentiometer_translate(
- encoder.polled_potentiometer_voltage()) +
- pot_offset;
- position->latched_encoder =
- multiplier * encoder_translate(encoder.last_encoder_value());
- position->latched_pot =
+ position->set_encoder(multiplier *
+ encoder_translate(encoder.polled_encoder_value()));
+ position->set_pot(multiplier * potentiometer_translate(
+ encoder.polled_potentiometer_voltage()) +
+ pot_offset);
+ position->set_latched_encoder(
+ multiplier * encoder_translate(encoder.last_encoder_value()));
+ position->set_latched_pot(
multiplier *
potentiometer_translate(encoder.last_potentiometer_voltage()) +
- pot_offset;
- position->index_pulses = encoder.index_posedge_count();
+ pot_offset);
+ position->set_index_pulses(encoder.index_posedge_count());
}
// Copies a relative digital encoder.
void CopyPosition(const ::frc::Encoder &encoder,
- ::frc971::RelativePositionT *position,
+ ::frc971::RelativePositionStatic *position,
double encoder_counts_per_revolution, double encoder_ratio,
bool reverse) {
const double multiplier = reverse ? -1.0 : 1.0;
- position->encoder =
- multiplier * encoder_translate(encoder.GetRaw(),
- encoder_counts_per_revolution,
- encoder_ratio);
+ position->set_encoder(multiplier *
+ encoder_translate(encoder.GetRaw(),
+ encoder_counts_per_revolution,
+ encoder_ratio));
}
// Copies a potentiometer
void CopyPosition(const ::frc::AnalogInput &input,
- ::frc971::RelativePositionT *position,
+ ::frc971::RelativePositionStatic *position,
::std::function<double(double)> potentiometer_translate,
bool reverse, double pot_offset) {
const double multiplier = reverse ? -1.0 : 1.0;
- position->encoder =
- multiplier * potentiometer_translate(input.GetVoltage()) + pot_offset;
+ position->set_encoder(
+ multiplier * potentiometer_translate(input.GetVoltage()) + pot_offset);
}
double encoder_translate(int32_t value, double counts_per_revolution,
diff --git a/frc971/wpilib/talonfx.cc b/frc971/wpilib/talonfx.cc
index dd30f9d..5e77618 100644
--- a/frc971/wpilib/talonfx.cc
+++ b/frc971/wpilib/talonfx.cc
@@ -113,26 +113,13 @@
return status;
}
-
-void TalonFX::SerializePosition(flatbuffers::FlatBufferBuilder *fbb,
+void TalonFX::SerializePosition(control_loops::CANTalonFXStatic *can_talonfx,
double gear_ratio) {
- control_loops::CANTalonFX::Builder builder(*fbb);
- builder.add_id(device_id_);
- builder.add_device_temp(device_temp());
- builder.add_supply_voltage(supply_voltage());
- builder.add_supply_current(supply_current());
- builder.add_torque_current(torque_current());
- builder.add_duty_cycle(duty_cycle());
- builder.add_position(position() * gear_ratio);
-
- last_position_offset_ = builder.Finish();
-}
-
-std::optional<flatbuffers::Offset<control_loops::CANTalonFX>>
-TalonFX::TakeOffset() {
- auto option_offset = last_position_offset_;
-
- last_position_offset_.reset();
-
- return option_offset;
+ can_talonfx->set_id(device_id_);
+ can_talonfx->set_device_temp(device_temp());
+ can_talonfx->set_supply_voltage(supply_voltage());
+ can_talonfx->set_supply_current(supply_current());
+ can_talonfx->set_torque_current(torque_current());
+ can_talonfx->set_duty_cycle(duty_cycle());
+ can_talonfx->set_position(position() * gear_ratio);
}
diff --git a/frc971/wpilib/talonfx.h b/frc971/wpilib/talonfx.h
index 603f4a2..c25fa81 100644
--- a/frc971/wpilib/talonfx.h
+++ b/frc971/wpilib/talonfx.h
@@ -11,7 +11,7 @@
#include "aos/commonmath.h"
#include "aos/init.h"
#include "aos/logging/logging.h"
-#include "frc971/control_loops/drivetrain/drivetrain_can_position_generated.h"
+#include "frc971/control_loops/can_talonfx_static.h"
namespace control_loops = ::frc971::control_loops;
@@ -48,11 +48,9 @@
ctre::phoenix6::hardware::TalonFX *talon() { return &talon_; }
// The position of the TalonFX output shaft is multiplied by gear_ratio
- void SerializePosition(flatbuffers::FlatBufferBuilder *fbb,
+ void SerializePosition(control_loops::CANTalonFXStatic *can_falcon,
double gear_ratio);
- std::optional<flatbuffers::Offset<control_loops::CANTalonFX>> TakeOffset();
-
int device_id() const { return device_id_; }
float device_temp() const { return device_temp_.GetValue().value(); }
float supply_voltage() const { return supply_voltage_.GetValue().value(); }
@@ -101,9 +99,6 @@
double stator_current_limit_;
double supply_current_limit_;
-
- std::optional<flatbuffers::Offset<control_loops::CANTalonFX>>
- last_position_offset_;
};
} // namespace wpilib
} // namespace frc971
diff --git a/third_party/y2024/field/2024.png b/third_party/y2024/field/2024.png
new file mode 100644
index 0000000..ae1af58
--- /dev/null
+++ b/third_party/y2024/field/2024.png
Binary files differ
diff --git a/third_party/y2024/field/BUILD b/third_party/y2024/field/BUILD
new file mode 100644
index 0000000..04346f5
--- /dev/null
+++ b/third_party/y2024/field/BUILD
@@ -0,0 +1,10 @@
+filegroup(
+ name = "pictures",
+ srcs = [
+ # Picture from the FIRST inspires field drawings.
+ # https://www.firstinspires.org/robotics/frc/playing-field
+ # Copyright 2024 FIRST
+ "2024.png",
+ ],
+ visibility = ["//visibility:public"],
+)
\ No newline at end of file
diff --git a/y2016/wpilib_interface.cc b/y2016/wpilib_interface.cc
index b658573..0e98085 100644
--- a/y2016/wpilib_interface.cc
+++ b/y2016/wpilib_interface.cc
@@ -50,7 +50,7 @@
#include "y2016/control_loops/shooter/shooter_output_generated.h"
#include "y2016/control_loops/shooter/shooter_position_generated.h"
#include "y2016/control_loops/superstructure/superstructure_output_generated.h"
-#include "y2016/control_loops/superstructure/superstructure_position_generated.h"
+#include "y2016/control_loops/superstructure/superstructure_position_static.h"
#include "y2016/queues/ball_detector_generated.h"
using ::frc971::wpilib::LoopOutputHandler;
@@ -156,7 +156,7 @@
shooter_position_sender_(
event_loop->MakeSender<shooter::Position>("/shooter")),
superstructure_position_sender_(
- event_loop->MakeSender<superstructure::Position>(
+ event_loop->MakeSender<superstructure::PositionStatic>(
"/superstructure")),
drivetrain_position_sender_(
event_loop
@@ -294,34 +294,17 @@
}
{
- auto builder = superstructure_position_sender_.MakeBuilder();
+ aos::Sender<superstructure::PositionStatic>::StaticBuilder builder =
+ superstructure_position_sender_.MakeStaticBuilder();
- frc971::PotAndIndexPositionT intake;
- CopyPosition(intake_encoder_, &intake, intake_translate,
+ CopyPosition(intake_encoder_, builder->add_intake(), intake_translate,
intake_pot_translate, false, values.intake.pot_offset);
- flatbuffers::Offset<frc971::PotAndIndexPosition> intake_offset =
- frc971::PotAndIndexPosition::Pack(*builder.fbb(), &intake);
-
- frc971::PotAndIndexPositionT shoulder;
- CopyPosition(shoulder_encoder_, &shoulder, shoulder_translate,
- shoulder_pot_translate, false, values.shoulder.pot_offset);
- flatbuffers::Offset<frc971::PotAndIndexPosition> shoulder_offset =
- frc971::PotAndIndexPosition::Pack(*builder.fbb(), &shoulder);
-
- frc971::PotAndIndexPositionT wrist;
- CopyPosition(wrist_encoder_, &wrist, wrist_translate, wrist_pot_translate,
- true, values.wrist.pot_offset);
- flatbuffers::Offset<frc971::PotAndIndexPosition> wrist_offset =
- frc971::PotAndIndexPosition::Pack(*builder.fbb(), &wrist);
-
- superstructure::Position::Builder position_builder =
- builder.MakeBuilder<superstructure::Position>();
-
- position_builder.add_intake(intake_offset);
- position_builder.add_shoulder(shoulder_offset);
- position_builder.add_wrist(wrist_offset);
-
- builder.CheckOk(builder.Send(position_builder.Finish()));
+ CopyPosition(shoulder_encoder_, builder->add_shoulder(),
+ shoulder_translate, shoulder_pot_translate, false,
+ values.shoulder.pot_offset);
+ CopyPosition(wrist_encoder_, builder->add_wrist(), wrist_translate,
+ wrist_pot_translate, true, values.wrist.pot_offset);
+ builder.CheckOk(builder.Send());
}
{
@@ -351,7 +334,7 @@
::aos::Sender<::y2016::sensors::BallDetector> ball_detector_sender_;
::aos::Sender<::frc971::autonomous::AutonomousMode> auto_mode_sender_;
::aos::Sender<shooter::Position> shooter_position_sender_;
- ::aos::Sender<superstructure::Position> superstructure_position_sender_;
+ ::aos::Sender<superstructure::PositionStatic> superstructure_position_sender_;
::aos::Sender<::frc971::control_loops::drivetrain::Position>
drivetrain_position_sender_;
diff --git a/y2017/wpilib_interface.cc b/y2017/wpilib_interface.cc
index d299c1d..822c3f4 100644
--- a/y2017/wpilib_interface.cc
+++ b/y2017/wpilib_interface.cc
@@ -54,7 +54,7 @@
#include "frc971/wpilib/wpilib_robot_base.h"
#include "y2017/constants.h"
#include "y2017/control_loops/superstructure/superstructure_output_generated.h"
-#include "y2017/control_loops/superstructure/superstructure_position_generated.h"
+#include "y2017/control_loops/superstructure/superstructure_position_static.h"
#ifndef M_PI
#define M_PI 3.14159265358979323846
@@ -132,7 +132,7 @@
event_loop->MakeSender<::frc971::autonomous::AutonomousMode>(
"/aos")),
superstructure_position_sender_(
- event_loop->MakeSender<superstructure::Position>(
+ event_loop->MakeSender<superstructure::PositionStatic>(
"/superstructure")),
drivetrain_position_sender_(
event_loop
@@ -230,55 +230,31 @@
const auto values = constants::GetValues();
{
- auto builder = superstructure_position_sender_.MakeBuilder();
- frc971::PotAndAbsolutePositionT intake;
- CopyPosition(intake_encoder_, &intake,
+ aos::Sender<superstructure::PositionStatic>::StaticBuilder builder =
+ superstructure_position_sender_.MakeStaticBuilder();
+
+ CopyPosition(intake_encoder_, builder->add_intake(),
Values::kIntakeEncoderCountsPerRevolution,
Values::kIntakeEncoderRatio, intake_pot_translate, true,
values.intake.pot_offset);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> intake_offset =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &intake);
-
- frc971::HallEffectAndPositionT indexer;
- CopyPosition(indexer_counter_, &indexer,
- Values::kIndexerEncoderCountsPerRevolution,
- Values::kIndexerEncoderRatio, true);
- flatbuffers::Offset<frc971::HallEffectAndPosition> indexer_offset =
- frc971::HallEffectAndPosition::Pack(*builder.fbb(), &indexer);
-
- frc971::IndexPositionT hood;
- CopyPosition(hood_encoder_, &hood,
+ CopyPosition(hood_encoder_, builder->add_hood(),
Values::kHoodEncoderCountsPerRevolution,
Values::kHoodEncoderRatio, true);
- flatbuffers::Offset<frc971::IndexPosition> hood_offset =
- frc971::IndexPosition::Pack(*builder.fbb(), &hood);
- frc971::HallEffectAndPositionT turret;
- CopyPosition(turret_counter_, &turret,
+ superstructure::ColumnPositionStatic *column = builder->add_column();
+ CopyPosition(turret_counter_, column->add_turret(),
Values::kTurretEncoderCountsPerRevolution,
Values::kTurretEncoderRatio, false);
- flatbuffers::Offset<frc971::HallEffectAndPosition> turret_offset =
- frc971::HallEffectAndPosition::Pack(*builder.fbb(), &turret);
+ CopyPosition(indexer_counter_, column->add_indexer(),
+ Values::kIndexerEncoderCountsPerRevolution,
+ Values::kIndexerEncoderRatio, true);
- superstructure::ColumnPosition::Builder column_builder =
- builder.MakeBuilder<superstructure::ColumnPosition>();
- column_builder.add_indexer(indexer_offset);
- column_builder.add_turret(turret_offset);
- flatbuffers::Offset<superstructure::ColumnPosition> column_offset =
- column_builder.Finish();
-
- superstructure::Position::Builder position_builder =
- builder.MakeBuilder<superstructure::Position>();
-
- position_builder.add_column(column_offset);
- position_builder.add_hood(hood_offset);
- position_builder.add_intake(intake_offset);
- position_builder.add_theta_shooter(
+ builder->set_theta_shooter(
encoder_translate(shooter_encoder_->GetRaw(),
Values::kShooterEncoderCountsPerRevolution,
Values::kShooterEncoderRatio));
- builder.CheckOk(builder.Send(position_builder.Finish()));
+ builder.CheckOk(builder.Send());
}
{
@@ -299,7 +275,7 @@
private:
::aos::Sender<::frc971::autonomous::AutonomousMode> auto_mode_sender_;
- ::aos::Sender<superstructure::Position> superstructure_position_sender_;
+ ::aos::Sender<superstructure::PositionStatic> superstructure_position_sender_;
::aos::Sender<::frc971::control_loops::drivetrain::Position>
drivetrain_position_sender_;
diff --git a/y2018/wpilib_interface.cc b/y2018/wpilib_interface.cc
index 9f5255d..cf71bdd 100644
--- a/y2018/wpilib_interface.cc
+++ b/y2018/wpilib_interface.cc
@@ -49,7 +49,7 @@
#include "frc971/wpilib/wpilib_robot_base.h"
#include "y2018/constants.h"
#include "y2018/control_loops/superstructure/superstructure_output_generated.h"
-#include "y2018/control_loops/superstructure/superstructure_position_generated.h"
+#include "y2018/control_loops/superstructure/superstructure_position_static.h"
#include "y2018/status_light_generated.h"
#include "y2018/vision/vision_generated.h"
@@ -147,7 +147,7 @@
SensorReader(::aos::ShmEventLoop *event_loop)
: ::frc971::wpilib::SensorReader(event_loop),
superstructure_position_sender_(
- event_loop->MakeSender<superstructure::Position>(
+ event_loop->MakeSender<superstructure::PositionStatic>(
"/superstructure")),
drivetrain_position_sender_(
event_loop
@@ -302,107 +302,60 @@
const auto values = constants::GetValues();
{
- auto builder = superstructure_position_sender_.MakeBuilder();
+ aos::Sender<superstructure::PositionStatic>::StaticBuilder builder =
+ superstructure_position_sender_.MakeStaticBuilder();
+
+ superstructure::ArmPositionStatic *arm_position = builder->add_arm();
// Proximal arm
- frc971::PotAndAbsolutePositionT arm_proximal;
- CopyPosition(proximal_encoder_, &arm_proximal,
+ CopyPosition(proximal_encoder_, arm_position->add_proximal(),
Values::kProximalEncoderCountsPerRevolution(),
Values::kProximalEncoderRatio(), proximal_pot_translate,
true, values.arm_proximal.potentiometer_offset);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> arm_proximal_offset =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &arm_proximal);
// Distal arm
- frc971::PotAndAbsolutePositionT arm_distal;
- CopyPosition(distal_encoder_, &arm_distal,
+ CopyPosition(distal_encoder_, arm_position->add_distal(),
Values::kDistalEncoderCountsPerRevolution(),
Values::kDistalEncoderRatio(), distal_pot_translate, true,
values.arm_distal.potentiometer_offset);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> arm_distal_offset =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &arm_distal);
-
- superstructure::ArmPosition::Builder arm_position_builder =
- builder.MakeBuilder<superstructure::ArmPosition>();
- arm_position_builder.add_proximal(arm_proximal_offset);
- arm_position_builder.add_distal(arm_distal_offset);
-
- flatbuffers::Offset<superstructure::ArmPosition> arm_position_offset =
- arm_position_builder.Finish();
// Left intake
- frc971::PotAndAbsolutePositionT left_intake_motor_position;
- CopyPosition(left_intake_encoder_, &left_intake_motor_position,
+ superstructure::IntakeElasticSensorsStatic *left_intake =
+ builder->add_left_intake();
+
+ CopyPosition(left_intake_encoder_, left_intake->add_motor_position(),
Values::kIntakeMotorEncoderCountsPerRevolution(),
Values::kIntakeMotorEncoderRatio(), intake_pot_translate,
false, values.left_intake.potentiometer_offset);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition>
- left_intake_motor_position_offset =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(),
- &left_intake_motor_position);
+
+ left_intake->set_spring_angle(
+ intake_spring_translate(left_intake_spring_angle_->GetVoltage()) +
+ values.left_intake.spring_offset);
+ left_intake->set_beam_break(!left_intake_cube_detector_->Get());
// Right intake
- frc971::PotAndAbsolutePositionT right_intake_motor_position;
- CopyPosition(right_intake_encoder_, &right_intake_motor_position,
+ superstructure::IntakeElasticSensorsStatic *right_intake =
+ builder->add_right_intake();
+ CopyPosition(right_intake_encoder_, right_intake->add_motor_position(),
Values::kIntakeMotorEncoderCountsPerRevolution(),
Values::kIntakeMotorEncoderRatio(), intake_pot_translate,
true, values.right_intake.potentiometer_offset);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition>
- right_intake_motor_position_offset =
- frc971::PotAndAbsolutePosition::Pack(
- *builder.fbb(), &right_intake_motor_position);
-
- superstructure::IntakeElasticSensors::Builder
- left_intake_sensors_builder =
- builder.MakeBuilder<superstructure::IntakeElasticSensors>();
-
- left_intake_sensors_builder.add_motor_position(
- left_intake_motor_position_offset);
- left_intake_sensors_builder.add_spring_angle(
- intake_spring_translate(left_intake_spring_angle_->GetVoltage()) +
- values.left_intake.spring_offset);
- left_intake_sensors_builder.add_beam_break(
- !left_intake_cube_detector_->Get());
-
- flatbuffers::Offset<superstructure::IntakeElasticSensors>
- left_intake_offset = left_intake_sensors_builder.Finish();
-
- superstructure::IntakeElasticSensors::Builder
- right_intake_sensors_builder =
- builder.MakeBuilder<superstructure::IntakeElasticSensors>();
-
- right_intake_sensors_builder.add_motor_position(
- right_intake_motor_position_offset);
- right_intake_sensors_builder.add_spring_angle(
+ right_intake->set_spring_angle(
-intake_spring_translate(right_intake_spring_angle_->GetVoltage()) +
values.right_intake.spring_offset);
- right_intake_sensors_builder.add_beam_break(
- !right_intake_cube_detector_->Get());
+ right_intake->set_beam_break(!right_intake_cube_detector_->Get());
- flatbuffers::Offset<control_loops::superstructure::IntakeElasticSensors>
- right_intake_offset = right_intake_sensors_builder.Finish();
+ builder->set_claw_beambreak_triggered(!claw_beambreak_->Get());
+ builder->set_box_back_beambreak_triggered(!box_back_beambreak_->Get());
- superstructure::Position::Builder superstructure_builder =
- builder.MakeBuilder<superstructure::Position>();
+ builder->set_box_distance(lidar_lite_.last_width() / 0.00001 / 100.0 / 2);
- superstructure_builder.add_left_intake(left_intake_offset);
- superstructure_builder.add_right_intake(right_intake_offset);
- superstructure_builder.add_arm(arm_position_offset);
-
- superstructure_builder.add_claw_beambreak_triggered(
- !claw_beambreak_->Get());
- superstructure_builder.add_box_back_beambreak_triggered(
- !box_back_beambreak_->Get());
-
- superstructure_builder.add_box_distance(lidar_lite_.last_width() /
- 0.00001 / 100.0 / 2);
-
- builder.CheckOk(builder.Send(superstructure_builder.Finish()));
+ builder.CheckOk(builder.Send());
}
}
private:
- ::aos::Sender<superstructure::Position> superstructure_position_sender_;
+ ::aos::Sender<superstructure::PositionStatic> superstructure_position_sender_;
::aos::Sender<::frc971::control_loops::drivetrain::Position>
drivetrain_position_sender_;
diff --git a/y2019/wpilib_interface.cc b/y2019/wpilib_interface.cc
index e918aaf..b3a5953 100644
--- a/y2019/wpilib_interface.cc
+++ b/y2019/wpilib_interface.cc
@@ -52,7 +52,7 @@
#include "y2019/constants.h"
#include "y2019/control_loops/drivetrain/camera_generated.h"
#include "y2019/control_loops/superstructure/superstructure_output_generated.h"
-#include "y2019/control_loops/superstructure/superstructure_position_generated.h"
+#include "y2019/control_loops/superstructure/superstructure_position_static.h"
#include "y2019/jevois/spi.h"
#include "y2019/status_light_generated.h"
@@ -139,7 +139,7 @@
event_loop->MakeSender<::frc971::autonomous::AutonomousMode>(
"/autonomous")),
superstructure_position_sender_(
- event_loop->MakeSender<superstructure::Position>(
+ event_loop->MakeSender<superstructure::PositionStatic>(
"/superstructure")),
drivetrain_position_sender_(
event_loop
@@ -254,63 +254,40 @@
const auto values = constants::GetValues();
{
- auto builder = superstructure_position_sender_.MakeBuilder();
+ aos::Sender<superstructure::PositionStatic>::StaticBuilder builder =
+ superstructure_position_sender_.MakeStaticBuilder();
// Elevator
- frc971::PotAndAbsolutePositionT elevator;
- CopyPosition(elevator_encoder_, &elevator,
+ CopyPosition(elevator_encoder_, builder->add_elevator(),
Values::kElevatorEncoderCountsPerRevolution(),
Values::kElevatorEncoderRatio(), elevator_pot_translate,
false, values.elevator.potentiometer_offset);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> elevator_offset =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &elevator);
-
// Intake
- frc971::AbsolutePositionT intake_joint;
- CopyPosition(intake_encoder_, &intake_joint,
+ CopyPosition(intake_encoder_, builder->add_intake_joint(),
Values::kIntakeEncoderCountsPerRevolution(),
Values::kIntakeEncoderRatio(), false);
- flatbuffers::Offset<frc971::AbsolutePosition> intake_joint_offset =
- frc971::AbsolutePosition::Pack(*builder.fbb(), &intake_joint);
-
// Wrist
- frc971::PotAndAbsolutePositionT wrist;
- CopyPosition(wrist_encoder_, &wrist,
+ CopyPosition(wrist_encoder_, builder->add_wrist(),
Values::kWristEncoderCountsPerRevolution(),
Values::kWristEncoderRatio(), wrist_pot_translate, false,
values.wrist.potentiometer_offset);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> wrist_offset =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &wrist);
-
// Stilts
- frc971::PotAndAbsolutePositionT stilts;
- CopyPosition(stilts_encoder_, &stilts,
+ CopyPosition(stilts_encoder_, builder->add_stilts(),
Values::kStiltsEncoderCountsPerRevolution(),
Values::kStiltsEncoderRatio(), stilts_pot_translate, false,
values.stilts.potentiometer_offset);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> stilts_offset =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &stilts);
-
- superstructure::Position::Builder position_builder =
- builder.MakeBuilder<superstructure::Position>();
-
- position_builder.add_elevator(elevator_offset);
- position_builder.add_intake_joint(intake_joint_offset);
- position_builder.add_wrist(wrist_offset);
- position_builder.add_stilts(stilts_offset);
// Suction
constexpr float kMinVoltage = 0.5;
constexpr float kMaxVoltage = 2.1;
- position_builder.add_suction_pressure(
+ builder->set_suction_pressure(
(vacuum_sensor_->GetVoltage() - kMinVoltage) /
(kMaxVoltage - kMinVoltage));
- position_builder.add_platform_left_detect(!platform_left_detect_->Get());
- position_builder.add_platform_right_detect(
- !platform_right_detect_->Get());
+ builder->set_platform_left_detect(!platform_left_detect_->Get());
+ builder->set_platform_right_detect(!platform_right_detect_->Get());
- builder.CheckOk(builder.Send(position_builder.Finish()));
+ builder.CheckOk(builder.Send());
}
{
@@ -334,7 +311,7 @@
private:
::aos::Sender<::frc971::autonomous::AutonomousMode> auto_mode_sender_;
- ::aos::Sender<superstructure::Position> superstructure_position_sender_;
+ ::aos::Sender<superstructure::PositionStatic> superstructure_position_sender_;
::aos::Sender<::frc971::control_loops::drivetrain::Position>
drivetrain_position_sender_;
diff --git a/y2020/wpilib_interface.cc b/y2020/wpilib_interface.cc
index 2f7b184..c9cec8a 100644
--- a/y2020/wpilib_interface.cc
+++ b/y2020/wpilib_interface.cc
@@ -53,7 +53,7 @@
#include "y2020/constants.h"
#include "y2020/control_loops/superstructure/shooter/shooter_tuning_readings_generated.h"
#include "y2020/control_loops/superstructure/superstructure_output_generated.h"
-#include "y2020/control_loops/superstructure/superstructure_position_generated.h"
+#include "y2020/control_loops/superstructure/superstructure_position_static.h"
DEFINE_bool(shooter_tuning, true,
"If true, reads from ball beambreak sensors and sends shooter "
@@ -161,7 +161,7 @@
event_loop->MakeSender<::frc971::autonomous::AutonomousMode>(
"/autonomous")),
superstructure_position_sender_(
- event_loop->MakeSender<superstructure::Position>(
+ event_loop->MakeSender<superstructure::PositionStatic>(
"/superstructure")),
drivetrain_position_sender_(
event_loop
@@ -288,65 +288,43 @@
const constants::Values &values = constants::GetValues();
{
- auto builder = superstructure_position_sender_.MakeBuilder();
+ aos::Sender<superstructure::PositionStatic>::StaticBuilder builder =
+ superstructure_position_sender_.MakeStaticBuilder();
// TODO(alex): check new absolute encoder api.
// Hood
- frc971::AbsoluteAndAbsolutePositionT hood;
- CopyPosition(hood_encoder_, &hood,
+ CopyPosition(hood_encoder_, builder->add_hood(),
Values::kHoodEncoderCountsPerRevolution(),
Values::kHoodEncoderRatio(),
Values::kHoodSingleTurnEncoderRatio(), false);
- flatbuffers::Offset<frc971::AbsoluteAndAbsolutePosition> hood_offset =
- frc971::AbsoluteAndAbsolutePosition::Pack(*builder.fbb(), &hood);
-
// Intake
- frc971::AbsolutePositionT intake_joint;
- CopyPosition(intake_joint_encoder_, &intake_joint,
+ CopyPosition(intake_joint_encoder_, builder->add_intake_joint(),
Values::kIntakeEncoderCountsPerRevolution(),
Values::kIntakeEncoderRatio(), false);
- flatbuffers::Offset<frc971::AbsolutePosition> intake_joint_offset =
- frc971::AbsolutePosition::Pack(*builder.fbb(), &intake_joint);
-
// Turret
- frc971::PotAndAbsolutePositionT turret;
- CopyPosition(turret_encoder_, &turret,
+ CopyPosition(turret_encoder_, builder->add_turret(),
Values::kTurretEncoderCountsPerRevolution(),
Values::kTurretEncoderRatio(), turret_pot_translate, true,
values.turret.potentiometer_offset);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> turret_offset =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &turret);
-
// Shooter
- y2020::control_loops::superstructure::ShooterPositionT shooter;
- shooter.theta_finisher =
+ y2020::control_loops::superstructure::ShooterPositionStatic *shooter =
+ builder->add_shooter();
+ shooter->set_theta_finisher(
encoder_translate(-finisher_encoder_->GetRaw(),
Values::kFinisherEncoderCountsPerRevolution(),
- Values::kFinisherEncoderRatio());
+ Values::kFinisherEncoderRatio()));
- shooter.theta_accelerator_left =
+ shooter->set_theta_accelerator_left(
encoder_translate(-left_accelerator_encoder_->GetRaw(),
Values::kAcceleratorEncoderCountsPerRevolution(),
- Values::kAcceleratorEncoderRatio());
- shooter.theta_accelerator_right =
+ Values::kAcceleratorEncoderRatio()));
+ shooter->set_theta_accelerator_right(
encoder_translate(right_accelerator_encoder_->GetRaw(),
Values::kAcceleratorEncoderCountsPerRevolution(),
- Values::kAcceleratorEncoderRatio());
- flatbuffers::Offset<y2020::control_loops::superstructure::ShooterPosition>
- shooter_offset =
- y2020::control_loops::superstructure::ShooterPosition::Pack(
- *builder.fbb(), &shooter);
+ Values::kAcceleratorEncoderRatio()));
+ builder->set_intake_beambreak_triggered(ball_intake_beambreak_->Get());
- superstructure::Position::Builder position_builder =
- builder.MakeBuilder<superstructure::Position>();
- position_builder.add_hood(hood_offset);
- position_builder.add_intake_joint(intake_joint_offset);
- position_builder.add_turret(turret_offset);
- position_builder.add_shooter(shooter_offset);
- position_builder.add_intake_beambreak_triggered(
- ball_intake_beambreak_->Get());
-
- builder.CheckOk(builder.Send(position_builder.Finish()));
+ builder.CheckOk(builder.Send());
}
{
@@ -386,7 +364,7 @@
private:
::aos::Sender<::frc971::autonomous::AutonomousMode> auto_mode_sender_;
- ::aos::Sender<superstructure::Position> superstructure_position_sender_;
+ ::aos::Sender<superstructure::PositionStatic> superstructure_position_sender_;
::aos::Sender<::frc971::control_loops::drivetrain::Position>
drivetrain_position_sender_;
::aos::Sender<superstructure::shooter::TuningReadings>
diff --git a/y2022/wpilib_interface.cc b/y2022/wpilib_interface.cc
index 5b3cd96..55cf510 100644
--- a/y2022/wpilib_interface.cc
+++ b/y2022/wpilib_interface.cc
@@ -55,7 +55,7 @@
#include "y2022/control_loops/superstructure/led_indicator.h"
#include "y2022/control_loops/superstructure/superstructure_can_position_generated.h"
#include "y2022/control_loops/superstructure/superstructure_output_generated.h"
-#include "y2022/control_loops/superstructure/superstructure_position_generated.h"
+#include "y2022/control_loops/superstructure/superstructure_position_static.h"
using ::aos::monotonic_clock;
using ::y2022::constants::Values;
@@ -167,7 +167,7 @@
event_loop->MakeSender<::frc971::autonomous::AutonomousMode>(
"/autonomous")),
superstructure_position_sender_(
- event_loop->MakeSender<superstructure::Position>(
+ event_loop->MakeSender<superstructure::PositionStatic>(
"/superstructure")),
drivetrain_position_sender_(
event_loop
@@ -227,74 +227,44 @@
void RunIteration() override {
superstructure_reading_->Set(true);
{
- auto builder = superstructure_position_sender_.MakeBuilder();
+ aos::Sender<superstructure::PositionStatic>::StaticBuilder builder =
+ superstructure_position_sender_.MakeStaticBuilder();
- frc971::PotAndAbsolutePositionT catapult;
- CopyPosition(catapult_encoder_, &catapult,
+ CopyPosition(catapult_encoder_, builder->add_catapult(),
Values::kCatapultEncoderCountsPerRevolution(),
Values::kCatapultEncoderRatio(), catapult_pot_translate,
false, values_->catapult.potentiometer_offset);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> catapult_offset =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &catapult);
- frc971::RelativePositionT climber;
- CopyPosition(*climber_potentiometer_, &climber, climber_pot_translate,
- false, values_->climber.potentiometer_offset);
- flatbuffers::Offset<frc971::RelativePosition> climber_offset =
- frc971::RelativePosition::Pack(*builder.fbb(), &climber);
+ CopyPosition(*climber_potentiometer_, builder->add_climber(),
+ climber_pot_translate, false,
+ values_->climber.potentiometer_offset);
- frc971::RelativePositionT flipper_arm_left;
- CopyPosition(*flipper_arm_left_potentiometer_, &flipper_arm_left,
- flipper_arms_pot_translate, false,
- values_->flipper_arm_left.potentiometer_offset);
+ CopyPosition(*flipper_arm_left_potentiometer_,
+ builder->add_flipper_arm_left(), flipper_arms_pot_translate,
+ false, values_->flipper_arm_left.potentiometer_offset);
- frc971::RelativePositionT flipper_arm_right;
- CopyPosition(*flipper_arm_right_potentiometer_, &flipper_arm_right,
- flipper_arms_pot_translate, true,
- values_->flipper_arm_right.potentiometer_offset);
+ CopyPosition(*flipper_arm_right_potentiometer_,
+ builder->add_flipper_arm_right(), flipper_arms_pot_translate,
+ true, values_->flipper_arm_right.potentiometer_offset);
// Intake
- frc971::PotAndAbsolutePositionT intake_front;
- CopyPosition(intake_encoder_front_, &intake_front,
+ CopyPosition(intake_encoder_front_, builder->add_intake_front(),
Values::kIntakeEncoderCountsPerRevolution(),
Values::kIntakeEncoderRatio(), intake_pot_translate, true,
values_->intake_front.potentiometer_offset);
- frc971::PotAndAbsolutePositionT intake_back;
- CopyPosition(intake_encoder_back_, &intake_back,
+ CopyPosition(intake_encoder_back_, builder->add_intake_back(),
Values::kIntakeEncoderCountsPerRevolution(),
Values::kIntakeEncoderRatio(), intake_pot_translate, true,
values_->intake_back.potentiometer_offset);
- frc971::PotAndAbsolutePositionT turret;
- CopyPosition(turret_encoder_, &turret,
+ CopyPosition(turret_encoder_, builder->add_turret(),
Values::kTurretEncoderCountsPerRevolution(),
Values::kTurretEncoderRatio(), turret_pot_translate, false,
values_->turret.potentiometer_offset);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> intake_offset_front =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &intake_front);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> intake_offset_back =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &intake_back);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> turret_offset =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &turret);
- flatbuffers::Offset<frc971::RelativePosition> flipper_arm_left_offset =
- frc971::RelativePosition::Pack(*builder.fbb(), &flipper_arm_left);
- flatbuffers::Offset<frc971::RelativePosition> flipper_arm_right_offset =
- frc971::RelativePosition::Pack(*builder.fbb(), &flipper_arm_right);
-
- superstructure::Position::Builder position_builder =
- builder.MakeBuilder<superstructure::Position>();
- position_builder.add_climber(climber_offset);
- position_builder.add_flipper_arm_left(flipper_arm_left_offset);
- position_builder.add_flipper_arm_right(flipper_arm_right_offset);
- position_builder.add_intake_front(intake_offset_front);
- position_builder.add_intake_back(intake_offset_back);
- position_builder.add_turret(turret_offset);
- position_builder.add_intake_beambreak_front(
- intake_beambreak_front_->Get());
- position_builder.add_intake_beambreak_back(intake_beambreak_back_->Get());
- position_builder.add_turret_beambreak(turret_beambreak_->Get());
- position_builder.add_catapult(catapult_offset);
- builder.CheckOk(builder.Send(position_builder.Finish()));
+ builder->set_intake_beambreak_front(intake_beambreak_front_->Get());
+ builder->set_intake_beambreak_back(intake_beambreak_back_->Get());
+ builder->set_turret_beambreak(turret_beambreak_->Get());
+ builder.CheckOk(builder.Send());
}
{
@@ -454,7 +424,7 @@
std::shared_ptr<const Values> values_;
aos::Sender<frc971::autonomous::AutonomousMode> auto_mode_sender_;
- aos::Sender<superstructure::Position> superstructure_position_sender_;
+ aos::Sender<superstructure::PositionStatic> superstructure_position_sender_;
aos::Sender<frc971::control_loops::drivetrain::Position>
drivetrain_position_sender_;
::aos::Sender<::frc971::sensors::GyroReading> gyro_sender_;
diff --git a/y2022_bot3/wpilib_interface.cc b/y2022_bot3/wpilib_interface.cc
index 4641e84..c441f6e 100644
--- a/y2022_bot3/wpilib_interface.cc
+++ b/y2022_bot3/wpilib_interface.cc
@@ -51,7 +51,7 @@
#include "frc971/wpilib/wpilib_robot_base.h"
#include "y2022_bot3/constants.h"
#include "y2022_bot3/control_loops/superstructure/superstructure_output_generated.h"
-#include "y2022_bot3/control_loops/superstructure/superstructure_position_generated.h"
+#include "y2022_bot3/control_loops/superstructure/superstructure_position_static.h"
using ::aos::monotonic_clock;
using ::y2022_bot3::constants::Values;
@@ -112,7 +112,7 @@
event_loop->MakeSender<::frc971::autonomous::AutonomousMode>(
"/autonomous")),
superstructure_position_sender_(
- event_loop->MakeSender<superstructure::Position>(
+ event_loop->MakeSender<superstructure::PositionStatic>(
"/superstructure")),
drivetrain_position_sender_(
event_loop
@@ -195,11 +195,11 @@
void RunIteration() override {
{
- auto builder = superstructure_position_sender_.MakeBuilder();
+ aos::Sender<superstructure::PositionStatic>::StaticBuilder builder =
+ superstructure_position_sender_.MakeStaticBuilder();
// Climbers
- frc971::PotAndAbsolutePositionT climber_right;
- CopyPosition(climber_encoder_right_, &climber_right,
+ CopyPosition(climber_encoder_right_, builder->add_climber_right(),
Values::kClimberEncoderCountsPerRevolution(),
(Values::kClimberEncoderRatio() *
Values::kClimberEncoderCountsPerRevolution()) /
@@ -207,8 +207,7 @@
climber_pot_translate, true,
values_->climber_right.potentiometer_offset);
- frc971::PotAndAbsolutePositionT climber_left;
- CopyPosition(climber_encoder_left_, &climber_left,
+ CopyPosition(climber_encoder_left_, builder->add_climber_left(),
Values::kClimberEncoderCountsPerRevolution(),
(Values::kClimberEncoderRatio() *
Values::kClimberEncoderCountsPerRevolution()) /
@@ -217,25 +216,12 @@
values_->climber_left.potentiometer_offset);
// Intake
- frc971::PotAndAbsolutePositionT intake;
- CopyPosition(intake_encoder_, &intake,
+ CopyPosition(intake_encoder_, builder->add_intake(),
Values::kIntakeEncoderCountsPerRevolution(),
Values::kIntakeEncoderRatio(), intake_pot_translate, true,
values_->intake.potentiometer_offset);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> intake_offset =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &intake);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> climber_offset_right =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &climber_right);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> climber_offset_left =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &climber_left);
-
- superstructure::Position::Builder position_builder =
- builder.MakeBuilder<superstructure::Position>();
- position_builder.add_intake(intake_offset);
- position_builder.add_climber_right(climber_offset_right);
- position_builder.add_climber_left(climber_offset_left);
- builder.CheckOk(builder.Send(position_builder.Finish()));
+ builder.CheckOk(builder.Send());
}
{
@@ -318,7 +304,7 @@
std::shared_ptr<const Values> values_;
aos::Sender<frc971::autonomous::AutonomousMode> auto_mode_sender_;
- aos::Sender<superstructure::Position> superstructure_position_sender_;
+ aos::Sender<superstructure::PositionStatic> superstructure_position_sender_;
aos::Sender<frc971::control_loops::drivetrain::Position>
drivetrain_position_sender_;
::aos::Sender<::frc971::sensors::GyroReading> gyro_sender_;
diff --git a/y2023/wpilib_interface.cc b/y2023/wpilib_interface.cc
index c05062e..3bf6027 100644
--- a/y2023/wpilib_interface.cc
+++ b/y2023/wpilib_interface.cc
@@ -58,7 +58,7 @@
#include "y2023/constants.h"
#include "y2023/control_loops/superstructure/led_indicator.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_position_static.h"
DEFINE_bool(ctre_diag_server, false,
"If true, enable the diagnostics server for interacting with "
@@ -408,7 +408,7 @@
event_loop->MakeSender<::frc971::autonomous::AutonomousMode>(
"/autonomous")),
superstructure_position_sender_(
- event_loop->MakeSender<superstructure::Position>(
+ event_loop->MakeSender<superstructure::PositionStatic>(
"/superstructure")),
drivetrain_position_sender_(
event_loop
@@ -441,62 +441,54 @@
void RunIteration() override {
superstructure_reading_->Set(true);
{
- auto builder = superstructure_position_sender_.MakeBuilder();
- frc971::PotAndAbsolutePositionT proximal;
- CopyPosition(proximal_encoder_, &proximal,
+ aos::Sender<superstructure::PositionStatic>::StaticBuilder builder =
+ superstructure_position_sender_.MakeStaticBuilder();
+
+ superstructure::ArmPositionStatic *arm = builder->add_arm();
+
+ CopyPosition(proximal_encoder_, arm->add_proximal(),
Values::kProximalEncoderCountsPerRevolution(),
Values::kProximalEncoderRatio(), proximal_pot_translate,
true, values_->arm_proximal.potentiometer_offset);
- frc971::PotAndAbsolutePositionT distal;
CopyPosition(
- distal_encoder_, &distal, Values::kDistalEncoderCountsPerRevolution(),
+ distal_encoder_, arm->add_distal(),
+ Values::kDistalEncoderCountsPerRevolution(),
values_->arm_distal.zeroing.one_revolution_distance / (M_PI * 2.0),
distal_pot_translate, true, values_->arm_distal.potentiometer_offset);
- frc971::PotAndAbsolutePositionT roll_joint;
- CopyPosition(roll_joint_encoder_, &roll_joint,
+ CopyPosition(roll_joint_encoder_, arm->add_roll_joint(),
Values::kRollJointEncoderCountsPerRevolution(),
Values::kRollJointEncoderRatio(), roll_joint_pot_translate,
false, values_->roll_joint.potentiometer_offset);
- frc971::AbsolutePositionT wrist;
- CopyPosition(wrist_encoder_, &wrist,
+ CopyPosition(wrist_encoder_, builder->add_wrist(),
Values::kWristEncoderCountsPerRevolution(),
values_->wrist.subsystem_params.zeroing_constants
.one_revolution_distance /
(M_PI * 2.0),
values_->wrist_flipped);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> proximal_offset =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &proximal);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> distal_offset =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &distal);
- flatbuffers::Offset<frc971::PotAndAbsolutePosition> roll_joint_offset =
- frc971::PotAndAbsolutePosition::Pack(*builder.fbb(), &roll_joint);
- flatbuffers::Offset<superstructure::ArmPosition> arm_offset =
- superstructure::CreateArmPosition(*builder.fbb(), proximal_offset,
- distal_offset, roll_joint_offset);
- flatbuffers::Offset<frc971::AbsolutePosition> wrist_offset =
- frc971::AbsolutePosition::Pack(*builder.fbb(), &wrist);
-
flatbuffers::Offset<superstructure::CANFalcon> roller_falcon_offset;
auto optional_roller_falcon = can_sensor_reader_->roller_falcon_data();
if (optional_roller_falcon.has_value()) {
- roller_falcon_offset = superstructure::CANFalcon::Pack(
- *builder.fbb(), &optional_roller_falcon.value());
+ superstructure::CANFalconT roller_falcon_buffer =
+ optional_roller_falcon.value();
+
+ superstructure::CANFalconStatic *roller_falcon =
+ builder->add_roller_falcon();
+ roller_falcon->set_id(roller_falcon_buffer.id);
+ roller_falcon->set_supply_current(roller_falcon_buffer.supply_current);
+ roller_falcon->set_torque_current(roller_falcon_buffer.torque_current);
+ roller_falcon->set_supply_voltage(roller_falcon_buffer.supply_voltage);
+ roller_falcon->set_device_temp(roller_falcon_buffer.device_temp);
+ roller_falcon->set_position(roller_falcon_buffer.position);
+ roller_falcon->set_duty_cycle(roller_falcon_buffer.duty_cycle);
}
- superstructure::Position::Builder position_builder =
- builder.MakeBuilder<superstructure::Position>();
-
- position_builder.add_arm(arm_offset);
- position_builder.add_wrist(wrist_offset);
- position_builder.add_end_effector_cube_beam_break(
+ builder->set_end_effector_cube_beam_break(
end_effector_cube_beam_break_->Get());
- position_builder.add_cone_position(cone_position_sensor_.last_width() /
- cone_position_sensor_.last_period());
- if (!roller_falcon_offset.IsNull()) {
- position_builder.add_roller_falcon(roller_falcon_offset);
- }
- builder.CheckOk(builder.Send(position_builder.Finish()));
+ builder->set_cone_position(cone_position_sensor_.last_width() /
+ cone_position_sensor_.last_period());
+
+ builder.CheckOk(builder.Send());
}
{
@@ -643,7 +635,7 @@
std::shared_ptr<const Values> values_;
aos::Sender<frc971::autonomous::AutonomousMode> auto_mode_sender_;
- aos::Sender<superstructure::Position> superstructure_position_sender_;
+ aos::Sender<superstructure::PositionStatic> superstructure_position_sender_;
aos::Sender<frc971::control_loops::drivetrain::Position>
drivetrain_position_sender_;
::aos::Sender<::frc971::sensors::GyroReading> gyro_sender_;
diff --git a/y2023_bot4/wpilib_interface.cc b/y2023_bot4/wpilib_interface.cc
index 8bac186..9dd3604 100644
--- a/y2023_bot4/wpilib_interface.cc
+++ b/y2023_bot4/wpilib_interface.cc
@@ -10,7 +10,7 @@
#include "frc971/wpilib/talonfx.h"
#include "frc971/wpilib/wpilib_robot_base.h"
#include "y2023_bot4/constants.h"
-#include "y2023_bot4/drivetrain_can_position_generated.h"
+#include "y2023_bot4/drivetrain_can_position_static.h"
#include "y2023_bot4/drivetrain_position_generated.h"
DEFINE_bool(ctre_diag_server, false,
@@ -43,21 +43,13 @@
return builder.Finish();
}
-flatbuffers::Offset<SwerveModuleCANPosition> can_module_offset(
- SwerveModuleCANPosition::Builder builder,
- std::shared_ptr<SwerveModule> module) {
- std::optional<flatbuffers::Offset<control_loops::CANTalonFX>>
- rotation_offset = module->rotation->TakeOffset();
- std::optional<flatbuffers::Offset<control_loops::CANTalonFX>>
- translation_offset = module->translation->TakeOffset();
+void populate_can_module(SwerveModuleCANPositionStatic *can_position,
+ std::shared_ptr<SwerveModule> module) {
+ auto rotation = can_position->add_rotation();
+ module->rotation->SerializePosition(rotation, 1.0);
- CHECK(rotation_offset.has_value());
- CHECK(translation_offset.has_value());
-
- builder.add_rotation(rotation_offset.value());
- builder.add_translation(translation_offset.value());
-
- return builder.Finish();
+ auto translation = can_position->add_translation();
+ module->translation->SerializePosition(translation, 1.0);
}
constexpr double kMaxFastEncoderPulsesPerSecond = std::max({
@@ -225,8 +217,8 @@
falcons.push_back(back_right->rotation);
falcons.push_back(back_right->translation);
- aos::Sender<AbsoluteCANPosition> can_position_sender =
- can_sensor_reader_event_loop.MakeSender<AbsoluteCANPosition>(
+ aos::Sender<AbsoluteCANPositionStatic> can_position_sender =
+ can_sensor_reader_event_loop.MakeSender<AbsoluteCANPositionStatic>(
"/drivetrain");
CANSensorReader can_sensor_reader(
@@ -236,31 +228,24 @@
// TODO(max): use status properly in the flatbuffer.
(void)status;
- auto builder = can_position_sender.MakeBuilder();
+ aos::Sender<AbsoluteCANPositionStatic>::StaticBuilder builder =
+ can_position_sender.MakeStaticBuilder();
for (auto falcon : falcons) {
falcon->RefreshNontimesyncedSignals();
- falcon->SerializePosition(builder.fbb(), 1.0);
}
- auto front_left_offset = can_module_offset(
- builder.MakeBuilder<SwerveModuleCANPosition>(), front_left);
- auto front_right_offset = can_module_offset(
- builder.MakeBuilder<SwerveModuleCANPosition>(), front_right);
- auto back_left_offset = can_module_offset(
- builder.MakeBuilder<SwerveModuleCANPosition>(), back_left);
- auto back_right_offset = can_module_offset(
- builder.MakeBuilder<SwerveModuleCANPosition>(), back_right);
+ auto front_left_flatbuffer = builder->add_front_left();
+ auto front_right_flatbuffer = builder->add_front_right();
+ auto back_left_flatbuffer = builder->add_back_left();
+ auto back_right_flatbuffer = builder->add_back_right();
- AbsoluteCANPosition::Builder can_position_builder =
- builder.MakeBuilder<AbsoluteCANPosition>();
+ populate_can_module(front_left_flatbuffer, front_left);
+ populate_can_module(front_right_flatbuffer, front_right);
+ populate_can_module(back_left_flatbuffer, back_left);
+ populate_can_module(back_right_flatbuffer, back_right);
- can_position_builder.add_front_left(front_left_offset);
- can_position_builder.add_front_right(front_right_offset);
- can_position_builder.add_back_left(back_left_offset);
- can_position_builder.add_back_right(back_right_offset);
-
- builder.CheckOk(builder.Send(can_position_builder.Finish()));
+ builder.CheckOk(builder.Send());
});
AddLoop(&can_sensor_reader_event_loop);
diff --git a/y2024/constants/7971.json b/y2024/constants/7971.json
index 94fc375..0062fa8 100644
--- a/y2024/constants/7971.json
+++ b/y2024/constants/7971.json
@@ -1,5 +1,5 @@
{
- "cameras": [
- ],
+ "robot": {
+ },
{% include 'y2024/constants/common.json' %}
}
diff --git a/y2024/constants/971.json b/y2024/constants/971.json
index 2e6ffa8..0062fa8 100644
--- a/y2024/constants/971.json
+++ b/y2024/constants/971.json
@@ -1,8 +1,5 @@
{
- "cameras": [
- ],
"robot": {
- }
},
{% include 'y2024/constants/common.json' %}
}
diff --git a/y2024/constants/9971.json b/y2024/constants/9971.json
index 2e6ffa8..0062fa8 100644
--- a/y2024/constants/9971.json
+++ b/y2024/constants/9971.json
@@ -1,8 +1,5 @@
{
- "cameras": [
- ],
"robot": {
- }
},
{% include 'y2024/constants/common.json' %}
}
diff --git a/y2024/constants/BUILD b/y2024/constants/BUILD
index 1e8faa4..73e92f0 100644
--- a/y2024/constants/BUILD
+++ b/y2024/constants/BUILD
@@ -76,3 +76,16 @@
"//frc971/constants:constants_sender_lib",
],
)
+
+cc_test(
+ name = "constants_validator_test",
+ srcs = ["constants_validator_test.cc"],
+ data = [":constants.json"],
+ visibility = ["//visibility:public"],
+ deps = [
+ ":constants_list_fbs",
+ "//aos:json_to_flatbuffer",
+ "//aos/testing:googletest",
+ "@com_github_google_glog//:glog",
+ ],
+)
diff --git a/y2024/constants/common.json b/y2024/constants/common.json
index 15894ad..1655127 100644
--- a/y2024/constants/common.json
+++ b/y2024/constants/common.json
@@ -1,5 +1 @@
- "target_map": {% include 'y2024/constants/target_map.json' %},
- "ignore_targets": {
- "red": [4],
- "blue": [5]
- }
+ "target_map": {% include 'y2024/constants/target_map.json' %}
diff --git a/y2024/constants/constants_validator_test.cc b/y2024/constants/constants_validator_test.cc
new file mode 100644
index 0000000..238bfc3
--- /dev/null
+++ b/y2024/constants/constants_validator_test.cc
@@ -0,0 +1,21 @@
+#include "glog/logging.h"
+#include "gtest/gtest.h"
+
+#include "aos/json_to_flatbuffer.h"
+#include "y2024/constants/constants_list_generated.h"
+
+namespace y2024 {
+namespace constants {
+namespace testing {
+class ConstantsValidatorTest : public ::testing::Test {};
+
+TEST_F(ConstantsValidatorTest, CheckConstants) {
+ CHECK_NOTNULL(aos::JsonFileToFlatbuffer<y2024::ConstantsList>(
+ "y2024/constants/constants.json")
+ .message()
+ .constants());
+}
+
+} // namespace testing
+} // namespace constants
+} // namespace y2024
diff --git a/y2024_defense/wpilib_interface.cc b/y2024_defense/wpilib_interface.cc
index f3a0b8f..d599813 100644
--- a/y2024_defense/wpilib_interface.cc
+++ b/y2024_defense/wpilib_interface.cc
@@ -40,6 +40,7 @@
#include "frc971/autonomous/auto_mode_generated.h"
#include "frc971/can_configuration_generated.h"
#include "frc971/control_loops/drivetrain/drivetrain_can_position_generated.h"
+#include "frc971/control_loops/drivetrain/drivetrain_can_position_static.h"
#include "frc971/control_loops/drivetrain/drivetrain_position_generated.h"
#include "frc971/input/robot_state_generated.h"
#include "frc971/queues/gyro_generated.h"
@@ -68,7 +69,7 @@
using ::frc971::CANConfiguration;
using ::y2024_defense::constants::Values;
-using frc971::control_loops::drivetrain::CANPosition;
+using frc971::control_loops::drivetrain::CANPositionStatic;
using frc971::wpilib::TalonFX;
using std::make_unique;
@@ -312,44 +313,28 @@
::aos::ShmEventLoop can_sensor_reader_event_loop(&config.message());
can_sensor_reader_event_loop.set_name("CANSensorReader");
- aos::Sender<CANPosition> can_position_sender =
- can_sensor_reader_event_loop.MakeSender<CANPosition>("/drivetrain");
+ aos::Sender<CANPositionStatic> can_position_sender =
+ can_sensor_reader_event_loop.MakeSender<CANPositionStatic>(
+ "/drivetrain");
frc971::wpilib::CANSensorReader can_sensor_reader(
&can_sensor_reader_event_loop, std::move(signals_registry), falcons,
[falcons, &can_position_sender](ctre::phoenix::StatusCode status) {
- auto builder = can_position_sender.MakeBuilder();
- aos::SizedArray<
- flatbuffers::Offset<frc971::control_loops::CANTalonFX>, 6>
- flatbuffer_falcons;
+ aos::Sender<CANPositionStatic>::StaticBuilder builder =
+ can_position_sender.MakeStaticBuilder();
+
+ auto falcon_vector = builder->add_talonfxs();
for (auto falcon : falcons) {
falcon->SerializePosition(
- builder.fbb(), control_loops::drivetrain::kHighOutputRatio);
- std::optional<
- flatbuffers::Offset<frc971::control_loops::CANTalonFX>>
- falcon_offset = falcon->TakeOffset();
-
- CHECK(falcon_offset.has_value());
-
- flatbuffer_falcons.push_back(falcon_offset.value());
+ falcon_vector->emplace_back(),
+ control_loops::drivetrain::kHighOutputRatio);
}
- auto falcons_list =
- builder.fbb()
- ->CreateVector<
- flatbuffers::Offset<frc971::control_loops::CANTalonFX>>(
- flatbuffer_falcons);
+ builder->set_timestamp(falcons.front()->GetTimestamp());
+ builder->set_status(static_cast<int>(status));
- frc971::control_loops::drivetrain::CANPosition::Builder
- can_position_builder = builder.MakeBuilder<
- frc971::control_loops::drivetrain::CANPosition>();
-
- can_position_builder.add_talonfxs(falcons_list);
- can_position_builder.add_timestamp(falcons.front()->GetTimestamp());
- can_position_builder.add_status(static_cast<int>(status));
-
- builder.CheckOk(builder.Send(can_position_builder.Finish()));
+ builder.CheckOk(builder.Send());
});
AddLoop(&can_sensor_reader_event_loop);