Merge changes Ie0fc08c6,I798d937a
* changes:
Make profile type a template parameter
Support decoupling acceleration and deceleration in TrapezoidProfile
diff --git a/documentation/tutorials/rio-gdb.md b/documentation/tutorials/rio-gdb.md
new file mode 100644
index 0000000..eb7bc16
--- /dev/null
+++ b/documentation/tutorials/rio-gdb.md
@@ -0,0 +1,29 @@
+# Roborio GDB
+
+The roborio has a gdb-server command so we need to set the rio as our server and connect to it with some host device.
+
+## Steps
+
+### Rio
+This command will start the gdb-server program on the rio.
+```bash
+gdbserver localhost:8898 program
+```
+
+### Host
+```bash
+# this is the gdb-multiarch package on debian. Its needed because your host machine
+# likely isn't using the architecture the rio uses.
+gdb-multiarch
+# This connects us using an extended remote to the roborio, which lets us use the run command.
+target extended-remote ip:8898
+# Here we specify the name of program from the rio side
+set remote exec-file program
+# This makes it so we don't stop when getting realtime signals
+handle SIG33 pass nostop noprint
+# From here on you can use gdb like you normally would
+# So we can run our program with some args
+r args
+# To exit the gdb-server program on the rio side we need to run this command.
+monitor exit
+```
diff --git a/frc971/control_loops/aiming/aiming.cc b/frc971/control_loops/aiming/aiming.cc
index 4cf9255..572ed1c 100644
--- a/frc971/control_loops/aiming/aiming.cc
+++ b/frc971/control_loops/aiming/aiming.cc
@@ -54,6 +54,8 @@
} // namespace
TurretGoal AimerGoal(const ShotConfig &config, const RobotState &state) {
+ CHECK(config.ball_speed_over_ground > 0.0)
+ << ": Ball speed must be positive.";
TurretGoal result;
// This code manages compensating the goal turret heading for the robot's
// current velocity, to allow for shooting on-the-fly.
diff --git a/frc971/control_loops/aiming/aiming_test.cc b/frc971/control_loops/aiming/aiming_test.cc
index 4ec7eb9..a4f7bf2 100644
--- a/frc971/control_loops/aiming/aiming_test.cc
+++ b/frc971/control_loops/aiming/aiming_test.cc
@@ -158,4 +158,17 @@
EXPECT_FLOAT_EQ(0.0, goal.velocity);
}
+// Tests that we fail if the ballspeed is zero. Can't hit anything if the ball
+// isn't moving.
+TEST(AimerDeathTest, ZeroBallSpeed) {
+ const Pose target({0.0, 0.0, 0.0}, 0.0);
+ Pose robot_pose({1.0, 1.0, 1.0}, 0.0);
+ const constants::Range range{-2.36, 2.36, -2.16, 2.16};
+ const double kBallSpeed = 0.0;
+ EXPECT_DEATH(AimerGoal(ShotConfig{target, ShotMode::kShootOnTheFly, range,
+ kBallSpeed, 0.0, 0.0},
+ RobotState{robot_pose, {0.0, 0.0}, 0.0, 0.0}),
+ "Ball speed must be positive.");
+}
+
} // namespace frc971::control_loops::aiming::testing
diff --git a/frc971/wpilib/encoder_and_potentiometer.h b/frc971/wpilib/encoder_and_potentiometer.h
index a5eac24..84bfb64 100644
--- a/frc971/wpilib/encoder_and_potentiometer.h
+++ b/frc971/wpilib/encoder_and_potentiometer.h
@@ -9,6 +9,7 @@
#include "aos/time/time.h"
#include "frc971/wpilib/ahal/AnalogInput.h"
#include "frc971/wpilib/ahal/Counter.h"
+#include "frc971/wpilib/ahal/DigitalInput.h"
#include "frc971/wpilib/ahal/DigitalSource.h"
#include "frc971/wpilib/ahal/Encoder.h"
#include "frc971/wpilib/dma.h"
@@ -168,6 +169,38 @@
::std::unique_ptr<::frc::DigitalInput> input_;
};
+class DMAAbsoluteEncoderAndPotentiometer {
+ public:
+ void set_absolute_pwm(::std::unique_ptr<frc::DigitalInput> input) {
+ duty_cycle_input_ = ::std::move(input);
+ duty_cycle_reader_.set_input(duty_cycle_input_.get());
+ }
+
+ void set_encoder(::std::unique_ptr<frc::Encoder> encoder) {
+ encoder_ = ::std::move(encoder);
+ }
+
+ void set_potentiometer(::std::unique_ptr<frc::AnalogInput> potentiometer) {
+ potentiometer_ = ::std::move(potentiometer);
+ }
+
+ double ReadAbsoluteEncoder() const {
+ return duty_cycle_reader_.last_width() / duty_cycle_reader_.last_period();
+ }
+ int32_t ReadRelativeEncoder() const { return encoder_->GetRaw(); }
+ double ReadPotentiometerVoltage() const {
+ return potentiometer_->GetVoltage();
+ }
+
+ DMAPulseWidthReader &reader() { return duty_cycle_reader_; }
+
+ private:
+ DMAPulseWidthReader duty_cycle_reader_;
+ ::std::unique_ptr<::frc::DigitalInput> duty_cycle_input_;
+ ::std::unique_ptr<frc::Encoder> encoder_;
+ ::std::unique_ptr<frc::AnalogInput> potentiometer_;
+};
+
// Class to hold a CTRE encoder with absolute angle pwm and potentiometer pair.
class AbsoluteEncoderAndPotentiometer {
public:
diff --git a/frc971/wpilib/sensor_reader.h b/frc971/wpilib/sensor_reader.h
index 455ed0e..da650a5 100644
--- a/frc971/wpilib/sensor_reader.h
+++ b/frc971/wpilib/sensor_reader.h
@@ -102,6 +102,27 @@
encoder_ratio * (2.0 * M_PI));
}
+ void CopyPosition(
+ const ::frc971::wpilib::DMAAbsoluteEncoderAndPotentiometer &encoder,
+ ::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->set_pot(multiplier * potentiometer_translate(
+ encoder.ReadPotentiometerVoltage()) +
+ pot_offset);
+ position->set_encoder(multiplier *
+ encoder_translate(encoder.ReadRelativeEncoder(),
+ encoder_counts_per_revolution,
+ encoder_ratio));
+
+ 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,
diff --git a/y2024/BUILD b/y2024/BUILD
index 4aec7d2..d96fd71 100644
--- a/y2024/BUILD
+++ b/y2024/BUILD
@@ -19,7 +19,9 @@
":aos_config",
"//aos/starter:roborio_irq_config.json",
"//y2024/constants:constants.json",
+ "@ctre_phoenix6_api_cpp_athena//:shared_libraries",
"@ctre_phoenix6_tools_athena//:shared_libraries",
+ "@ctre_phoenix_api_cpp_athena//:shared_libraries",
"@ctre_phoenix_cci_athena//:shared_libraries",
],
dirs = [
@@ -112,6 +114,7 @@
"//aos/network:message_bridge_client_fbs",
"//aos/network:message_bridge_server_fbs",
"//y2024/constants:constants_fbs",
+ "//frc971/control_loops/drivetrain/localization:localizer_output_fbs",
"//frc971/can_logger:can_logging_fbs",
"//aos/network:timestamp_fbs",
"//aos/network:remote_message_fbs",
@@ -132,6 +135,7 @@
"//aos/network:remote_message_fbs",
"//aos/network:message_bridge_client_fbs",
"//aos/network:message_bridge_server_fbs",
+ "//frc971/wpilib:pdp_values_fbs",
#y2019 stuff shouldn't be here (e.g. target selector)
"//y2024/constants:constants_fbs",
"//aos/network:timestamp_fbs",
diff --git a/y2024/control_loops/drivetrain/drivetrain_main.cc b/y2024/control_loops/drivetrain/drivetrain_main.cc
index e0b2eb7..82629de 100644
--- a/y2024/control_loops/drivetrain/drivetrain_main.cc
+++ b/y2024/control_loops/drivetrain/drivetrain_main.cc
@@ -18,14 +18,15 @@
frc971::constants::WaitForConstants<y2024::Constants>(&config.message());
aos::ShmEventLoop event_loop(&config.message());
+ const auto drivetrain_config =
+ ::y2024::control_loops::drivetrain::GetDrivetrainConfig(&event_loop);
+
std::unique_ptr<::frc971::control_loops::drivetrain::PuppetLocalizer>
localizer = std::make_unique<
::frc971::control_loops::drivetrain::PuppetLocalizer>(
- &event_loop,
- ::y2024::control_loops::drivetrain::GetDrivetrainConfig(&event_loop));
+ &event_loop, drivetrain_config);
std::unique_ptr<DrivetrainLoop> drivetrain = std::make_unique<DrivetrainLoop>(
- y2024::control_loops::drivetrain::GetDrivetrainConfig(&event_loop),
- &event_loop, localizer.get());
+ drivetrain_config, &event_loop, localizer.get());
event_loop.Run();
diff --git a/y2024/wpilib_interface.cc b/y2024/wpilib_interface.cc
index bce5451..4e61940 100644
--- a/y2024/wpilib_interface.cc
+++ b/y2024/wpilib_interface.cc
@@ -135,8 +135,15 @@
::frc971::control_loops::drivetrain::PositionStatic>(
"/drivetrain")),
gyro_sender_(event_loop->MakeSender<::frc971::sensors::GyroReading>(
- "/drivetrain")){};
- void Start() override { AddToDMA(&imu_yaw_rate_reader_); }
+ "/drivetrain")) {
+ UpdateFastEncoderFilterHz(kMaxFastEncoderPulsesPerSecond);
+ event_loop->SetRuntimeAffinity(aos::MakeCpusetFromCpus({0}));
+ };
+ void Start() override {
+ AddToDMA(&imu_yaw_rate_reader_);
+ AddToDMA(&turret_encoder_.reader());
+ AddToDMA(&altitude_encoder_.reader());
+ }
// Auto mode switches.
void set_autonomous_mode(int i, ::std::unique_ptr<frc::DigitalInput> sensor) {
@@ -325,9 +332,12 @@
frc971::wpilib::AbsoluteEncoder intake_pivot_encoder_;
frc971::wpilib::AbsoluteEncoderAndPotentiometer climber_encoder_,
- catapult_encoder_, turret_encoder_, altitude_encoder_, extend_encoder_;
+ catapult_encoder_, extend_encoder_;
frc971::wpilib::DMAPulseWidthReader imu_yaw_rate_reader_;
+
+ frc971::wpilib::DMAAbsoluteEncoderAndPotentiometer turret_encoder_,
+ altitude_encoder_;
};
class WPILibRobot : public ::frc971::wpilib::WPILibRobotBase {
@@ -401,7 +411,7 @@
robot_constants->common()->current_limits();
std::shared_ptr<TalonFX> right_front = std::make_shared<TalonFX>(
- 0, false, "Drivetrain Bus", &canivore_signal_registry,
+ 2, false, "Drivetrain Bus", &canivore_signal_registry,
current_limits->drivetrain_supply_current_limit(),
current_limits->drivetrain_stator_current_limit());
std::shared_ptr<TalonFX> right_back = std::make_shared<TalonFX>(
@@ -409,35 +419,36 @@
current_limits->drivetrain_supply_current_limit(),
current_limits->drivetrain_stator_current_limit());
std::shared_ptr<TalonFX> left_front = std::make_shared<TalonFX>(
- 2, false, "Drivetrain Bus", &canivore_signal_registry,
+ 4, false, "Drivetrain Bus", &canivore_signal_registry,
current_limits->drivetrain_supply_current_limit(),
current_limits->drivetrain_stator_current_limit());
std::shared_ptr<TalonFX> left_back = std::make_shared<TalonFX>(
- 3, false, "Drivetrain Bus", &canivore_signal_registry,
+ 5, false, "Drivetrain Bus", &canivore_signal_registry,
current_limits->drivetrain_supply_current_limit(),
current_limits->drivetrain_stator_current_limit());
std::shared_ptr<TalonFX> intake_pivot = std::make_shared<TalonFX>(
- 4, false, "Drivetrain Bus", &canivore_signal_registry,
+ 3, false, "Drivetrain Bus", &canivore_signal_registry,
current_limits->intake_pivot_stator_current_limit(),
current_limits->intake_pivot_supply_current_limit());
+ // TODO(max): Assign these proper ids
std::shared_ptr<TalonFX> altitude = std::make_shared<TalonFX>(
- 5, false, "Drivetrain Bus", &canivore_signal_registry,
+ 6, false, "Drivetrain Bus", &canivore_signal_registry,
current_limits->altitude_stator_current_limit(),
current_limits->altitude_supply_current_limit());
std::shared_ptr<TalonFX> turret = std::make_shared<TalonFX>(
- 6, false, "Drivetrain Bus", &canivore_signal_registry,
+ 7, false, "Drivetrain Bus", &canivore_signal_registry,
current_limits->turret_stator_current_limit(),
current_limits->turret_supply_current_limit());
std::shared_ptr<TalonFX> intake_roller = std::make_shared<TalonFX>(
- 7, false, "rio", &rio_signal_registry,
+ 8, false, "rio", &rio_signal_registry,
current_limits->intake_roller_stator_current_limit(),
current_limits->intake_roller_supply_current_limit());
std::shared_ptr<TalonFX> transfer_roller = std::make_shared<TalonFX>(
- 8, false, "rio", &rio_signal_registry,
+ 9, false, "rio", &rio_signal_registry,
current_limits->transfer_roller_stator_current_limit(),
current_limits->transfer_roller_supply_current_limit());
std::shared_ptr<TalonFX> climber = std::make_shared<TalonFX>(
- 9, false, "rio", &rio_signal_registry,
+ 10, false, "rio", &rio_signal_registry,
current_limits->climber_stator_current_limit(),
current_limits->climber_supply_current_limit());
@@ -504,9 +515,7 @@
drivetrain_can_position_sender.MakeStaticBuilder();
auto drivetrain_falcon_vector =
- drivetrain_can_builder->add_talonfxs();
-
- CHECK(drivetrain_falcon_vector->reserve(drivetrain_talonfxs.size()));
+ CHECK_NOTNULL(drivetrain_can_builder->add_talonfxs());
for (auto talonfx : drivetrain_talonfxs) {
talonfx->SerializePosition(
diff --git a/y2024/www/field.html b/y2024/www/field.html
index 8c3b291..ac94060 100644
--- a/y2024/www/field.html
+++ b/y2024/www/field.html
@@ -81,6 +81,22 @@
<td> Right Encoder Position</td>
<td id="right_drivetrain_encoder"> NA </td>
</tr>
+ <tr>
+ <td> Right Front Falcon CAN Position</td>
+ <td id="falcon_right_front"> NA </td>
+ </tr>
+ <tr>
+ <td> Right Back Falcon CAN Position</td>
+ <td id="falcon_right_back"> NA </td>
+ </tr>
+ <tr>
+ <td> Left Front Falcon CAN Position</td>
+ <td id="falcon_left_front"> NA </td>
+ </tr>
+ <tr>
+ <td> Left Back Falcon CAN Position</td>
+ <td id="falcon_left_back"> NA </td>
+ </tr>
</table>
</body>
</html>
diff --git a/y2024/www/field_handler.ts b/y2024/www/field_handler.ts
index f383c08..81050dd 100644
--- a/y2024/www/field_handler.ts
+++ b/y2024/www/field_handler.ts
@@ -21,11 +21,75 @@
export class FieldHandler {
private canvas = document.createElement('canvas');
+ private localizerOutput: LocalizerOutput|null = null;
+ private drivetrainStatus: DrivetrainStatus|null = null;
+ private drivetrainPosition: DrivetrainPosition|null = null;
+ private drivetrainCANPosition: DrivetrainCANPosition|null = null;
+
+ 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 fieldImage: HTMLImageElement = new Image();
+
+ private leftDrivetrainEncoder: HTMLElement =
+ (document.getElementById('left_drivetrain_encoder') as HTMLElement);
+ private rightDrivetrainEncoder: HTMLElement =
+ (document.getElementById('right_drivetrain_encoder') as HTMLElement);
+ private falconRightFrontPosition: HTMLElement =
+ (document.getElementById('falcon_right_front') as HTMLElement);
+ private falconRightBackPosition: HTMLElement =
+ (document.getElementById('falcon_right_back') as HTMLElement);
+ private falconLeftFrontPosition: HTMLElement =
+ (document.getElementById('falcon_left_front') as HTMLElement);
+ private falconLeftBackPosition: HTMLElement =
+ (document.getElementById('falcon_left_back') as HTMLElement);
+
constructor(private readonly connection: Connection) {
(document.getElementById('field') as HTMLElement).appendChild(this.canvas);
this.fieldImage.src = '2024.png';
+
+ this.connection.addConfigHandler(() => {
+
+ this.connection.addHandler(
+ '/drivetrain', 'frc971.control_loops.drivetrain.Status', (data) => {
+ this.handleDrivetrainStatus(data);
+ });
+ this.connection.addHandler(
+ '/drivetrain', 'frc971.control_loops.drivetrain.Position', (data) => {
+ this.handleDrivetrainPosition(data);
+ });
+ this.connection.addHandler(
+ '/drivetrain', 'frc971.control_loops.drivetrain.CANPosition', (data) => {
+ this.handleDrivetrainCANPosition(data);
+ });
+ this.connection.addHandler(
+ '/localizer', 'frc971.controls.LocalizerOutput', (data) => {
+ this.handleLocalizerOutput(data);
+ });
+ });
+ }
+
+ private handleDrivetrainStatus(data: Uint8Array): void {
+ const fbBuffer = new ByteBuffer(data);
+ this.drivetrainStatus = DrivetrainStatus.getRootAsStatus(fbBuffer);
+ }
+
+ private handleDrivetrainPosition(data: Uint8Array): void {
+ const fbBuffer = new ByteBuffer(data);
+ this.drivetrainPosition = DrivetrainPosition.getRootAsPosition(fbBuffer);
+ }
+
+ private handleDrivetrainCANPosition(data: Uint8Array): void {
+ const fbBuffer = new ByteBuffer(data);
+ this.drivetrainCANPosition = DrivetrainCANPosition.getRootAsCANPosition(fbBuffer);
+ }
+
+ private handleLocalizerOutput(data: Uint8Array): void {
+ const fbBuffer = new ByteBuffer(data);
+ this.localizerOutput = LocalizerOutput.getRootAsLocalizerOutput(fbBuffer);
}
drawField(): void {
@@ -38,10 +102,95 @@
ctx.restore();
}
+ drawRobot(
+ x: number, y: number, theta: number, color: string = 'blue',
+ dashed: boolean = false): void {
+ const ctx = this.canvas.getContext('2d');
+ ctx.save();
+ ctx.translate(x, y);
+ ctx.rotate(theta);
+ ctx.strokeStyle = color;
+ ctx.lineWidth = ROBOT_WIDTH / 10.0;
+ if (dashed) {
+ ctx.setLineDash([0.05, 0.05]);
+ } else {
+ // Empty array = solid line.
+ ctx.setLineDash([]);
+ }
+ ctx.rect(-ROBOT_LENGTH / 2, -ROBOT_WIDTH / 2, ROBOT_LENGTH, ROBOT_WIDTH);
+ ctx.stroke();
+
+ // Draw line indicating which direction is forwards on the robot.
+ ctx.beginPath();
+ ctx.moveTo(0, 0);
+ ctx.lineTo(ROBOT_LENGTH / 2.0, 0);
+ ctx.stroke();
+
+ ctx.restore();
+}
+
+ setZeroing(div: HTMLElement): void {
+ div.innerHTML = 'zeroing';
+ div.classList.remove('faulted');
+ div.classList.add('zeroing');
+ div.classList.remove('near');
+}
+
+ 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();
+ if (this.drivetrainPosition) {
+ this.leftDrivetrainEncoder.innerHTML =
+ this.drivetrainPosition.leftEncoder().toString();
+
+ this.rightDrivetrainEncoder.innerHTML =
+ this.drivetrainPosition.rightEncoder().toString();
+ }
+
+ if (this.drivetrainCANPosition) {
+ this.falconRightFrontPosition.innerHTML =
+ this.drivetrainCANPosition.talonfxs(0).position().toString();
+
+ this.falconRightBackPosition.innerHTML =
+ this.drivetrainCANPosition.talonfxs(1).position().toString();
+
+ this.falconLeftFrontPosition.innerHTML =
+ this.drivetrainCANPosition.talonfxs(2).position().toString();
+
+ this.falconLeftBackPosition.innerHTML =
+ this.drivetrainCANPosition.talonfxs(3).position().toString();
+ }
+
+ if (this.drivetrainStatus && this.drivetrainStatus.trajectoryLogging()) {
+ this.drawRobot(
+ this.drivetrainStatus.trajectoryLogging().x(),
+ this.drivetrainStatus.trajectoryLogging().y(),
+ this.drivetrainStatus.trajectoryLogging().theta(), '#000000FF',
+ false);
+ }
+
+ if (this.localizerOutput) {
+ if (!this.localizerOutput.zeroed()) {
+ this.setZeroing(this.x);
+ this.setZeroing(this.y);
+ this.setZeroing(this.theta);
+ } else {
+ this.setValue(this.x, this.localizerOutput.x());
+ this.setValue(this.y, this.localizerOutput.y());
+ this.setValue(this.theta, this.localizerOutput.theta());
+ }
+
+ this.drawRobot(
+ this.localizerOutput.x(), this.localizerOutput.y(),
+ this.localizerOutput.theta());
+ }
window.requestAnimationFrame(() => this.draw());
}
diff --git a/y2024/y2024_imu.json b/y2024/y2024_imu.json
index 862a1d6..0c4e738 100644
--- a/y2024/y2024_imu.json
+++ b/y2024/y2024_imu.json
@@ -150,6 +150,36 @@
}
]
},
+ {
+ "name": "/localizer",
+ "type": "frc971.controls.LocalizerOutput",
+ "source_node": "imu",
+ "frequency": 52,
+ "logger": "LOCAL_AND_REMOTE_LOGGER",
+ "logger_nodes": [
+ "roborio"
+ ],
+ "destination_nodes": [
+ {
+ "name": "roborio",
+ "priority": 5,
+ "time_to_live": 5000000,
+ "timestamp_logger": "LOCAL_AND_REMOTE_LOGGER",
+ "timestamp_logger_nodes": [
+ "imu"
+ ]
+ }
+ ]
+ },
+ {
+ "name": "/imu/aos/remote_timestamps/roborio/localizer/frc971-controls-LocalizerOutput",
+ "type": "aos.message_bridge.RemoteMessage",
+ "source_node": "imu",
+ "logger": "NOT_LOGGED",
+ "frequency": 52,
+ "num_senders": 2,
+ "max_size": 200
+ },
{
"name": "/roborio/aos/remote_timestamps/imu/roborio/aos/aos-starter-StarterRpc",
"type": "aos.message_bridge.RemoteMessage",
diff --git a/y2024/y2024_roborio.json b/y2024/y2024_roborio.json
index 6af86f0..b78daef 100644
--- a/y2024/y2024_roborio.json
+++ b/y2024/y2024_roborio.json
@@ -19,6 +19,13 @@
},
{
"name": "/roborio/aos",
+ "type": "frc971.PDPValues",
+ "source_node": "roborio",
+ "frequency": 55,
+ "max_size": 368
+ },
+ {
+ "name": "/roborio/aos",
"type": "aos.RobotState",
"source_node": "roborio",
"frequency": 250
@@ -144,7 +151,7 @@
"source_node": "roborio",
"frequency": 220,
"num_senders": 2,
- "max_size": 400
+ "max_size": 608
},
{
"name": "/superstructure/rio",
@@ -152,7 +159,7 @@
"source_node": "roborio",
"frequency": 220,
"num_senders": 2,
- "max_size": 400
+ "max_size": 608
},
{
"name": "/can",
@@ -168,7 +175,7 @@
"source_node": "roborio",
"frequency": 220,
"num_senders": 2,
- "max_size": 400
+ "max_size": 424
},
{
"name": "/drivetrain",
@@ -213,7 +220,7 @@
"type": "frc971.control_loops.drivetrain.Position",
"source_node": "roborio",
"frequency": 400,
- "max_size": 112,
+ "max_size": 128,
"num_senders": 2
},
{