diff --git a/src/main/deploy/pathplanner/paths/HP to 330 Right.path b/src/main/deploy/pathplanner/paths/HP to 330 Right.path index 66f17f4..d9f7713 100644 --- a/src/main/deploy/pathplanner/paths/HP to 330 Right.path +++ b/src/main/deploy/pathplanner/paths/HP to 330 Right.path @@ -46,7 +46,7 @@ ], "globalConstraints": { "maxVelocity": 3.5, - "maxAcceleration": 1.75, + "maxAcceleration": 1.25, "maxAngularVelocity": 540.0, "maxAngularAcceleration": 400.0, "nominalVoltage": 12.0, diff --git a/src/main/deploy/pathplanner/paths/HP to K.path b/src/main/deploy/pathplanner/paths/HP to K.path index addc2ff..d99e6fe 100644 --- a/src/main/deploy/pathplanner/paths/HP to K.path +++ b/src/main/deploy/pathplanner/paths/HP to K.path @@ -46,7 +46,7 @@ ], "globalConstraints": { "maxVelocity": 5.0, - "maxAcceleration": 1.75, + "maxAcceleration": 1.25, "maxAngularVelocity": 540.0, "maxAngularAcceleration": 400.0, "nominalVoltage": 12.0, diff --git a/src/main/deploy/pathplanner/paths/Start to 30 Right.path b/src/main/deploy/pathplanner/paths/Start to 30 Right.path index 4c58b63..f3d34aa 100644 --- a/src/main/deploy/pathplanner/paths/Start to 30 Right.path +++ b/src/main/deploy/pathplanner/paths/Start to 30 Right.path @@ -46,7 +46,7 @@ ], "globalConstraints": { "maxVelocity": 3.5, - "maxAcceleration": 1.75, + "maxAcceleration": 1.25, "maxAngularVelocity": 540.0, "maxAngularAcceleration": 400.0, "nominalVoltage": 12.0, diff --git a/src/main/java/frc/robot/subsystems/Drivetrain.java b/src/main/java/frc/robot/subsystems/Drivetrain.java index 7ebe7b4..cc4695c 100644 --- a/src/main/java/frc/robot/subsystems/Drivetrain.java +++ b/src/main/java/frc/robot/subsystems/Drivetrain.java @@ -111,7 +111,7 @@ public class Drivetrain extends SubsystemBase { m_rearRight.getPosition() }, new Pose2d(), - VecBuilder.fill(0.07, 0.7, Units.degreesToRadians(0.5)), + VecBuilder.fill(0.1, 0.1, Units.degreesToRadians(0.5)), VecBuilder.fill(1, 1, Units.degreesToRadians(4000)) );