Skip to content

Commit

Permalink
update motor ids, tune stage two, make it stop when you release bumper
Browse files Browse the repository at this point in the history
  • Loading branch information
IsaacThoman committed Sep 21, 2023
1 parent 0191a19 commit 3f20862
Show file tree
Hide file tree
Showing 4 changed files with 17 additions and 17 deletions.
24 changes: 12 additions & 12 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -63,14 +63,14 @@ public static final class ModuleConstants {

public static class ArmConstants {
public static final int stageOneLeftId = 11;
public static final int stageOneRightId = 12;
public static final int stageOneRightId = 13;

public static final double continuousCurrentLimit = 20;
public static final double peakCurrentLimit = 40;
public static final double peakCurrentTime = 250;

public static final int stageTwoLeftId = 1;
public static final int stageTwoRightId = 2;
public static final int stageTwoLeftId = 49;
public static final int stageTwoRightId = 48;

public static final int stageTwoSmartCurrentLimit = 40;
public static final double stageTwoSecondaryCurrentLimit = 60;
Expand Down Expand Up @@ -134,16 +134,16 @@ public static final class DriveConstants {
);

//TBD
public static final int FRONT_LEFT_DRIVE_MOTOR_PORT = 3;
public static final int FRONT_RIGHT_DRIVE_MOTOR_PORT = 5;
public static final int BACK_LEFT_DRIVE_MOTOR_PORT = 7;
public static final int BACK_RIGHT_DRIVE_MOTOR_PORT = 9;
public static final int FRONT_LEFT_DRIVE_MOTOR_PORT = 1;
public static final int FRONT_RIGHT_DRIVE_MOTOR_PORT = 6;
public static final int BACK_LEFT_DRIVE_MOTOR_PORT = 8;
public static final int BACK_RIGHT_DRIVE_MOTOR_PORT = 3;

//TBD
public static final int FRONT_LEFT_TURNING_MOTOR_PORT = 4;
public static final int FRONT_RIGHT_TURNING_MOTOR_PORT = 6;
public static final int BACK_LEFT_TURNING_MOTOR_PORT = 8;
public static final int BACK_RIGHT_TURNING_MOTOR_PORT = 10;
public static final int FRONT_RIGHT_TURNING_MOTOR_PORT = 5;
public static final int BACK_LEFT_TURNING_MOTOR_PORT = 2;
public static final int BACK_RIGHT_TURNING_MOTOR_PORT = 7;

public static final boolean FRONT_LEFT_DRIVE_ENCODER_REVERSED = false;
public static final boolean FRONT_RIGHT_DRIVE_ENCODER_REVERSED = true;
Expand All @@ -162,8 +162,8 @@ public static final class DriveConstants {
public static final int BACK_RIGHT_DRIVE_ABSOLUTE_ENCODER_PORT = 3;

//sort of calculated
public static final double FRONT_LEFT_DRIVE_ABSOLUTE_ENCODER_OFFSET_RAD = -2.260 +Math.PI; //-2.29+Math.PI
public static final double FRONT_RIGHT_DRIVE_ABSOLUTE_ENCODER_OFFSET_RAD = -6.087+Math.PI; //-6.06+Math.PI
public static final double FRONT_LEFT_DRIVE_ABSOLUTE_ENCODER_OFFSET_RAD = -2.260 -0.140 +Math.PI; //-2.29+Math.PI
public static final double FRONT_RIGHT_DRIVE_ABSOLUTE_ENCODER_OFFSET_RAD = -5.30+Math.PI; //-6.06+Math.PI
public static final double BACK_LEFT_DRIVE_ABSOLUTE_ENCODER_OFFSET_RAD = -5.420+Math.PI; //-2.25
public static final double BACK_RIGHT_DRIVE_ABSOLUTE_ENCODER_OFFSET_RAD = -3.925+Math.PI; //-0.75

Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ public RobotContainer() {

grabberSub.setDefaultCommand(new RunCommand(()-> grabberSub.joystickDrive(xboxController.getLeftY(),xboxController.getRightY()), grabberSub));
efSub.setDefaultCommand(new RunCommand(()->efSub.driveThing(xboxController.getLeftTriggerAxis() - xboxController.getRightTriggerAxis()),efSub));

swerveSubsystem.setDefaultCommand(new RunCommand(()->swerveSubsystem.joystickDrive(0,0,0),swerveSubsystem));
}


Expand All @@ -63,7 +63,7 @@ private void configureBindings() {
new JoystickButton(xboxController,XboxController.Button.kB.value).whileTrue(new InstantCommand(()->grabberSub.goHome()));

new JoystickButton(xboxController,XboxController.Button.kLeftBumper.value).whileTrue(new RunCommand(()->swerveSubsystem.joystickDrive(xboxController.getLeftY()*-1, xboxController.getLeftX()*-1, xboxController.getRightX()*-1),swerveSubsystem));
new JoystickButton(xboxController,XboxController.Button.kLeftBumper.value).whileTrue(new RunCommand(()->grabberSub.goHome(),grabberSub));
// new JoystickButton(xboxController,XboxController.Button.kLeftBumper.value).whileTrue(new RunCommand(()->grabberSub.goHome(),grabberSub));

}

Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/EFSub.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,8 @@ public class EFSub extends SubsystemBase {

/** Creates a new EndEffectorSubsystem. */
public EFSub() {
efMotorTop = new TalonSRX(14);
efMotorBottom = new TalonSRX(13);
efMotorTop = new TalonSRX(12);
efMotorBottom = new TalonSRX(14);

// setting motors to brake mode so they immediately stop moving when voltage stops being sent
efMotorTop.setNeutralMode(NeutralMode.Coast);
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/subsystems/StageTwoSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ public class StageTwoSubsystem extends SubsystemBase {
private CANSparkMax armMotorPrimary;
private CANSparkMax armMotorSecondary;
private AbsoluteEncoder encoder;
private PIDController pidController = new PIDController(1, 0,0);
private PIDController pidController = new PIDController(0.5, 0,0);


public StageTwoSubsystem(){
Expand Down

0 comments on commit 3f20862

Please sign in to comment.