Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -41,5 +41,8 @@ public static class ControlConstants {
public static final double MAX_ROBOT_SPEED = 1;
public static final double MIN_ROBOT_SPEED = -1;
public static final double MAX_TURN_SPEED = 0.7;



}
}
31 changes: 24 additions & 7 deletions src/main/java/frc/robot/subsystems/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,10 @@


import com.revrobotics.RelativeEncoder;
import edu.wpi.first.wpilibj2.command.PIDCommand;
import edu.wpi.first.math.controller.PIDController;


public class Drivetrain extends SubsystemBase {
private CANSparkMax frontLeft;
private CANSparkMax frontRight;
Expand All @@ -39,6 +43,11 @@ public class Drivetrain extends SubsystemBase {
private RelativeEncoder backRighte;
private RelativeEncoder frontLefte;
private boolean finetuned;

private PIDController pidFR;
private PIDController pidBR;
private PIDController pidFL;
private PIDController pidBL;


public Drivetrain() {
Expand All @@ -52,11 +61,19 @@ public Drivetrain() {
backLefte = backLeft.getEncoder();
backRighte = backRight.getEncoder();

double kP = 0.2;
double kI = 0.05;
double kD = 0.0;

}
pidFR = new PIDController(kP,kI,kD);
pidBR = new PIDController(kP,kI,kD);
pidFL = new PIDController(kP,kI,kD);
pidBL = new PIDController(kP,kI,kD);



}

@Override
public void periodic() {

Expand All @@ -75,6 +92,8 @@ public void periodic() {
SmartDashboard.putNumber("CountsPerRevolution", CPR);
SmartDashboard.putNumber("Revolutions", revolutions);



}

// 2020 mecanum drive code
Expand Down Expand Up @@ -109,8 +128,6 @@ public void mecanumDrive(double joystickX, double joystickY, double rotation) {





//finetuned driving system

if (finetuned == true) {
Expand All @@ -127,10 +144,10 @@ public void mecanumDrive(double joystickX, double joystickY, double rotation) {


// Power the motors
frontLeft.set(frontLeftPower);
frontRight.set(frontRightPower);
backLeft.set(backLeftPower);
backRight.set(backRightPower);
frontLeft.set(pidFL.calculate(frontLefte.getVelocity(), frontLeftPower));
frontRight.set(pidFR.calculate(frontRighte.getVelocity(), frontRightPower));
backLeft.set(pidBL.calculate(backLefte.getVelocity(), frontLeftPower));
backRight.set(pidBR.calculate(backRighte.getVelocity(), frontLeftPower));

}
public double getBackRightPosition() {
Expand Down