diff --git a/src/main/deploy/swerve/controllerproperties.json b/src/main/deploy/swerve/controllerproperties.json index ab93140..4abb93a 100644 --- a/src/main/deploy/swerve/controllerproperties.json +++ b/src/main/deploy/swerve/controllerproperties.json @@ -1,8 +1,8 @@ { - "angleJoystickRadiusDeadband": 0.25, + "angleJoystickRadiusDeadband": 0.05, "heading": { "p": 0.4, "i": 0, - "d": 0.01 + "d": 0 } } \ No newline at end of file diff --git a/src/main/deploy/swerve/modules/backleft.json b/src/main/deploy/swerve/modules/backleft.json index a22a195..187a1ca 100644 --- a/src/main/deploy/swerve/modules/backleft.json +++ b/src/main/deploy/swerve/modules/backleft.json @@ -1,7 +1,7 @@ { "location": { - "front": -13.5, - "left": 13.5 + "front": -11, + "left": 11 }, "absoluteEncoderOffset": 276.15234375, "drive": { diff --git a/src/main/deploy/swerve/modules/backright.json b/src/main/deploy/swerve/modules/backright.json index 65decfd..b93f795 100644 --- a/src/main/deploy/swerve/modules/backright.json +++ b/src/main/deploy/swerve/modules/backright.json @@ -1,7 +1,7 @@ { "location": { - "front": -13.5, - "left": -13.5 + "front": -11, + "left": -11 }, "absoluteEncoderOffset": 299.267578125, "drive": { diff --git a/src/main/deploy/swerve/modules/frontleft.json b/src/main/deploy/swerve/modules/frontleft.json index 123e6a1..b1b7e96 100644 --- a/src/main/deploy/swerve/modules/frontleft.json +++ b/src/main/deploy/swerve/modules/frontleft.json @@ -1,7 +1,7 @@ { "location": { - "front": 13.5, - "left": 13.5 + "front": 11, + "left": 11 }, "absoluteEncoderOffset": 357.978515625, "drive": { diff --git a/src/main/deploy/swerve/modules/frontright.json b/src/main/deploy/swerve/modules/frontright.json index 16efc78..1b99eab 100644 --- a/src/main/deploy/swerve/modules/frontright.json +++ b/src/main/deploy/swerve/modules/frontright.json @@ -1,7 +1,7 @@ { "location": { - "front": 13.5, - "left": -13.5 + "front": 11, + "left": -11 }, "absoluteEncoderOffset": 52.91015625, "drive": { diff --git a/src/main/deploy/swerve/modules/physicalproperties.json b/src/main/deploy/swerve/modules/physicalproperties.json index dfb4be5..b2d3972 100644 --- a/src/main/deploy/swerve/modules/physicalproperties.json +++ b/src/main/deploy/swerve/modules/physicalproperties.json @@ -11,6 +11,6 @@ }, "rampRate": { "drive": 0.25, - "angle": 0.25 + "angle": 0 } } \ No newline at end of file diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index efc0c2b..fbdb906 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -61,7 +61,7 @@ public RobotContainer() { // Configure the trigger bindings configureBindings(); - AbsoluteDriveAdv closedAbsoluteDriveAdv = + final AbsoluteDriveAdv closedAbsoluteDriveAdv = new AbsoluteDriveAdv( drivebase, () -> MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND), @@ -94,7 +94,7 @@ public RobotContainer() { drivebase.driveCommand( () -> MathUtil.applyDeadband(driverXbox.getLeftY(), OperatorConstants.LEFT_Y_DEADBAND), () -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND), - () -> driverXbox.getRawAxis(2)); + () -> driverXbox.getRightX() * 0.5); Command driveFieldOrientedDirectAngleSim = drivebase.simDriveCommand( @@ -102,7 +102,7 @@ public RobotContainer() { () -> MathUtil.applyDeadband(driverXbox.getLeftX(), OperatorConstants.LEFT_X_DEADBAND), () -> driverXbox.getRawAxis(2)); - drivebase.setDefaultCommand(closedAbsoluteDriveAdv); + drivebase.setDefaultCommand(driveFieldOrientedAnglularVelocity); } /**