Skip to content

Commit

Permalink
swerve testing changes
Browse files Browse the repository at this point in the history
  • Loading branch information
CrolineCrois authored and penguin212 committed Feb 7, 2024
1 parent 874ed5c commit 2cc0d28
Show file tree
Hide file tree
Showing 3 changed files with 8 additions and 10 deletions.
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -66,7 +66,7 @@ public static class SwerveConstants {

public static final int BR_DRIVE = 6;
public static final int BR_STEER = 7;
public static final double BR_OFFSET = 2.66 + Math.PI * 3.0 / 4.0;
public static final double BR_OFFSET = 2.43 - Math.PI * 1 / 4;

private static double MODULE_DIST = Units.inchesToMeters(27.25 / 2.0);
public static final Translation2d FL_POS = new Translation2d(-MODULE_DIST, MODULE_DIST);
Expand Down
8 changes: 7 additions & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -32,6 +32,7 @@
import frc.robot.subsystems.elevator.ElevatorSubsystem;
import frc.robot.subsystems.swerve.BaseSwerveSubsystem;
import frc.robot.subsystems.swerve.SingleModuleSwerveSubsystem;
import frc.robot.subsystems.swerve.SwerveModule;
import frc.robot.subsystems.swerve.SwerveSubsystem;
import frc.robot.subsystems.swerve.TestSingleModuleSwerveSubsystem;
import frc.robot.util.ConditionalWaitCommand;
Expand Down Expand Up @@ -89,6 +90,7 @@ public class RobotContainer {
//private final JoystickButton xButton = new JoystickButton(mechController, XboxController.Button.kX.value);

ChoreoTrajectory traj;

// private final SwerveModule module;

/** The container for the robot. Contains subsystems, OI devices, and commands. */
Expand All @@ -111,14 +113,18 @@ public RobotContainer() {

// Configure the trigger bindings
configureBindings();
// private final SwerveModule module;
//construct Test
// module = new SwerveModule(6, 7, 0);
// baseSwerveSubsystem = new TestSingleModuleSwerveSubsystem(module);

camera1 = new UsbCamera("camera1", 0);
camera1.setFPS(60);
camera1.setBrightness(45);
camera1.setResolution(176, 144);
mjpgserver1 = new MjpegServer("m1", 1181);
mjpgserver1.setSource(camera1);
}
}


private void configureBindings() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -120,14 +120,6 @@ public SwerveSubsystem() {
}

public void periodic() {

// System.out.println(frontLeftModule.getDriveSetpoint());

// if (crimer.advanceIfElapsed(.1)){
// //System.out.println("BR : " + backRightModule.getRawAngle());
// System.out.println("BL : " + backLeftModule.getRawAngle());
// }

FLsteer.setValue(frontLeftModule.getSteerAmpDraws());
FLdrive.setValue(frontLeftModule.getDriveAmpDraws());

Expand Down

0 comments on commit 2cc0d28

Please sign in to comment.