From db980f3cd64a1f873ae162de72686e9cdebc8f92 Mon Sep 17 00:00:00 2001 From: Blue-Flag-666 <64064866+Blue-Flag-666@users.noreply.github.com> Date: Mon, 4 Nov 2024 17:47:29 +0800 Subject: [PATCH] Fix swerve --- src/main/java/frc/libzodiac | 2 +- src/main/java/frc/robot/RobotContainer.java | 1 + src/main/java/frc/robot/subsystems/Chassis.java | 12 ++++++------ 3 files changed, 8 insertions(+), 7 deletions(-) diff --git a/src/main/java/frc/libzodiac b/src/main/java/frc/libzodiac index bf9f4ac..04c8f3d 160000 --- a/src/main/java/frc/libzodiac +++ b/src/main/java/frc/libzodiac @@ -1 +1 @@ -Subproject commit bf9f4ac42e6e3d6586cf1428989f0c34e698eaa2 +Subproject commit 04c8f3d571733270557ea7b5fadadb8f5ac419a6 diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 36acfd0..d3d68a6 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -5,6 +5,7 @@ package frc.robot; import edu.wpi.first.wpilibj2.command.Command; +import frc.libzodiac.ZDashboard; import frc.libzodiac.Zambda; import frc.libzodiac.Zamera; import frc.libzodiac.ui.Axis; diff --git a/src/main/java/frc/robot/subsystems/Chassis.java b/src/main/java/frc/robot/subsystems/Chassis.java index 8b901b0..a7682e1 100644 --- a/src/main/java/frc/robot/subsystems/Chassis.java +++ b/src/main/java/frc/robot/subsystems/Chassis.java @@ -6,19 +6,19 @@ import frc.libzodiac.hardware.Pigeon; import frc.libzodiac.hardware.TalonFXMotor; import frc.libzodiac.hardware.group.TalonFXSwerve; -import frc.libzodiac.util.Vec2D; +import frc.libzodiac.util.Vec2; public class Chassis extends Zwerve { // TODO: Swerve zero position - private static final TalonFXSwerve front_left = new TalonFXSwerve(5, 1, 9, 3581).invert(false, true); - private static final TalonFXSwerve front_right = new TalonFXSwerve(8, 4, 12, 1921).invert(false, false); - private static final TalonFXSwerve rear_left = new TalonFXSwerve(6, 2, 10, 408).invert(true, true); - private static final TalonFXSwerve rear_right = new TalonFXSwerve(7, 3, 11, 149).invert(true, true); + private static final TalonFXSwerve front_left = new TalonFXSwerve(5, 1, 9, 3354).invert(false, true); + private static final TalonFXSwerve front_right = new TalonFXSwerve(8, 4, 12, 1921).invert(false, true); + private static final TalonFXSwerve rear_left = new TalonFXSwerve(6, 2, 10, 792).invert(false, true); + private static final TalonFXSwerve rear_right = new TalonFXSwerve(7, 3, 11, 147).invert(false, true); private static final Pigeon gyro = new Pigeon(0); private static final Pose2d initialPose = new Pose2d(0, 0, Rotation2d.fromRadians(0)); // TODO: Initial pose - private static final Vec2D size = new Vec2D(114, 114); // TODO: Robot size + private static final Vec2 size = new Vec2(114, 114); // TODO: Robot size /** * Creates a new Chassis.