Skip to content

Commit

Permalink
renaming and reformating intake, adding ids
Browse files Browse the repository at this point in the history
  • Loading branch information
penguin212 committed Jan 31, 2024
1 parent 44660a3 commit a354be7
Show file tree
Hide file tree
Showing 10 changed files with 70 additions and 72 deletions.
3 changes: 2 additions & 1 deletion .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -25,5 +25,6 @@
}
},
],
"java.test.defaultConfig": "WPIlibUnitTests"
"java.test.defaultConfig": "WPIlibUnitTests",
"java.jdt.ls.vmargs": "-XX:+UseParallelGC -XX:GCTimeRatio=4 -XX:AdaptiveSizePolicyWeight=90 -Dsun.zip.disableMemoryMapping=true -Xmx4G -Xms100m -Xlog:disable"
}
10 changes: 5 additions & 5 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -66,11 +66,11 @@ public static class SwerveConstants {
public static final Translation2d BR_POS = new Translation2d(MODULE_DIST, -MODULE_DIST);
}

public static class RollerandPivotConstants {
public static final int lastmotorID = 0;
public static final int topmotorID = 2;
public static final int bottommotorID = 3;
public static final int motor1ID = 1;
public static class IntakeConstants {
public static final int INTEGRATION_MOTOR_ID = 19;
public static final int FRONT_MOTOR_ID = 17;
public static final int BACK_MOTOR_ID = 18;
public static final int PIVOT_MOTOR_ID = 16;

public static final int sensorID = 0;
public static final int extendedlimitswitchID = 1;
Expand Down
67 changes: 32 additions & 35 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -37,13 +37,14 @@

public class RobotContainer {
// The robot's subsystems and commands are defined here...
private final IntakeRollersSubsystem intakeSubsystem = new IntakeRollersSubsystem();
private final BaseDriveController driveController = new DualJoystickDriveController();
private final BaseSwerveSubsystem baseSwerveSubsystem;

private final IntakePivotSubsystem intakePivotSubsystem;
private final ShooterFlywheelSubsystem shooterSubsystem;
private final ShooterFeederSubsystem feederSubsystem;
private final IntakeRollersSubsystem intakeRollerSubsystem = new IntakeRollersSubsystem();

private final ShooterFlywheelSubsystem shooterFlywheelSubsystem;
private final ShooterFeederSubsystem shooterFeederSubsystem;
private final ShooterPivotSubsystem shooterPivotSubsystem;

private final ClimbSubsystem climbSubsystem;
Expand All @@ -56,6 +57,7 @@ public class RobotContainer {
private final JoystickButton rightBumper = new JoystickButton(mechController, XboxController.Button.kRightBumper.value);
private final JoystickButton xButton = new JoystickButton(mechController, XboxController.Button.kX.value);
private final JoystickButton yButton = new JoystickButton(mechController, XboxController.Button.kY.value);

//private final JoystickButton xButton = new JoystickButton(mechController, XboxController.Button.kX.value);

ChoreoTrajectory traj;
Expand All @@ -68,10 +70,10 @@ public RobotContainer() {
// baseSwerveSubsystem = new TestSingleModuleSwerveSubsystem(module);
baseSwerveSubsystem = new SwerveSubsystem();
intakePivotSubsystem = new IntakePivotSubsystem();
feederSubsystem = new ShooterFeederSubsystem();
shooterFeederSubsystem = new ShooterFeederSubsystem();

shooterPivotSubsystem = new ShooterPivotSubsystem(false);
shooterSubsystem = new ShooterFlywheelSubsystem();
shooterFlywheelSubsystem = new ShooterFlywheelSubsystem();

climbSubsystem = new ClimbSubsystem();

Expand All @@ -84,54 +86,49 @@ public RobotContainer() {

private void configureBindings() {

/**
* Right trigger - run pivot forward at speed pulled
* Left trigger - run pivot backward at speed pulled
* A button - run flywheels while button held
* B button - run feed wheels while button held
*/

// aButton.onTrue(new LoadNoteCommand(feederSubsystem));

// bButton.onTrue(new ShootNoteCommand(feederSubsystem));

// leftBumper.onTrue(new AutoAimCommand(pivotSubsystem));

// rightBumper.onTrue(new VerticalCommand(pivotSubsystem));

// xButton.onTrue(new ReadyShooterCommand(shooterSubsystem));

// yButton.onTrue(new StopShooterCommands(shooterSubsystem));

intakePivotSubsystem.setDefaultCommand(new InstantCommand(() -> {
intakePivotSubsystem.setPivotSpeed(-mechController.getLeftTriggerAxis());
}));

shooterSubsystem.setDefaultCommand(new InstantCommand(() -> {
intakePivotSubsystem.setPivotSpeed(mechController.getRightTriggerAxis());
}));

bButton.onTrue(new InstantCommand(() -> {
feederSubsystem.setFeederMotorSpeed(.7);
shooterFeederSubsystem.setFeederMotorSpeed(.7);
}));

bButton.onFalse(new InstantCommand(() -> {
feederSubsystem.setFeederMotorSpeed(0);
shooterFeederSubsystem.setFeederMotorSpeed(0);
}));

xButton.onTrue(new InstantCommand(() -> {
feederSubsystem.setFeederMotorSpeed(-.7);
shooterFeederSubsystem.setFeederMotorSpeed(-.7);
}));

xButton.onFalse(new InstantCommand(() -> {
feederSubsystem.setFeederMotorSpeed(0);
shooterFeederSubsystem.setFeederMotorSpeed(0);
}));

shooterPivotSubsystem.setDefaultCommand(new InstantCommand(() -> {
shooterPivotSubsystem.setPivotMotorSpeed((.2 * mechController.getRightTriggerAxis() - mechController.getLeftTriggerAxis()));
// pivotSubsystem.printCurrentAngle();
}, shooterPivotSubsystem));

aButton.onTrue(new InstantCommand(() -> {
shooterFlywheelSubsystem.setShooterMotorSpeed(shooterFlywheelSubsystem.SHOOTER_MOTOR_SPEED);
}));

aButton.onFalse(new InstantCommand(() -> {
shooterFlywheelSubsystem.setShooterMotorSpeed(0);
}));

intakeRollerSubsystem.setDefaultCommand(new InstantCommand(() -> {
if(mechController.getPOV() == 90){
intakeRollerSubsystem.setAllRollSpeed(.3, .3);
} else if (mechController.getPOV() == 270){
intakeRollerSubsystem.setAllRollSpeed(-.3, -.3);
} else {
intakeRollerSubsystem.setAllRollSpeed(0, 0);
}
}));




if(baseSwerveSubsystem instanceof SwerveSubsystem){
final SwerveSubsystem swerveSubsystem = (SwerveSubsystem) baseSwerveSubsystem;

Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
package frc.robot.commands.intake.pivot;

import static frc.robot.Constants.RollerandPivotConstants.pivotcounterclockwise;
import static frc.robot.Constants.IntakeConstants.pivotcounterclockwise;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.intake.IntakePivotSubsystem;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@
package frc.robot.commands.intake.pivot;


import static frc.robot.Constants.RollerandPivotConstants.pivotclockwise;
import static frc.robot.Constants.IntakeConstants.pivotclockwise;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.intake.IntakePivotSubsystem;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
package frc.robot.commands.intake.roller;

import static frc.robot.Constants.RollerandPivotConstants.pastsensortime;
import static frc.robot.Constants.RollerandPivotConstants.rollersclockwise;
import static frc.robot.Constants.RollerandPivotConstants.rollerscounterclockwise;
import static frc.robot.Constants.IntakeConstants.pastsensortime;
import static frc.robot.Constants.IntakeConstants.rollersclockwise;
import static frc.robot.Constants.IntakeConstants.rollerscounterclockwise;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.intake.IntakeRollersSubsystem;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
package frc.robot.commands.intake.roller;


import static frc.robot.Constants.RollerandPivotConstants.rollersclockwise;
import static frc.robot.Constants.RollerandPivotConstants.rollerscounterclockwise;
import static frc.robot.Constants.IntakeConstants.rollersclockwise;
import static frc.robot.Constants.IntakeConstants.rollerscounterclockwise;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.intake.IntakeRollersSubsystem;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
package frc.robot.commands.intake.roller;


import static frc.robot.Constants.RollerandPivotConstants.pastsensortime;
import static frc.robot.Constants.RollerandPivotConstants.rollersclockwise;
import static frc.robot.Constants.RollerandPivotConstants.rollerscounterclockwise;
import static frc.robot.Constants.IntakeConstants.pastsensortime;
import static frc.robot.Constants.IntakeConstants.rollersclockwise;
import static frc.robot.Constants.IntakeConstants.rollerscounterclockwise;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.intake.IntakeRollersSubsystem;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
package frc.robot.subsystems.intake;

import static frc.robot.Constants.RollerandPivotConstants.*;
import static frc.robot.Constants.IntakeConstants.*;
//import edu.wpi.first.wpilibj.Encoder;
import com.ctre.phoenix.motorcontrol.TalonSRXControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
Expand All @@ -9,13 +9,13 @@


public class IntakePivotSubsystem extends SubsystemBase{
private final com.ctre.phoenix.motorcontrol.can.TalonSRX motor1;
private final com.ctre.phoenix.motorcontrol.can.TalonSRX pivotMotor;
// private final Encoder intakeencoder;
private final DigitalInput extendedlimitswitch;
private final DigitalInput retractedlimitswitch;

public IntakePivotSubsystem(){
motor1 = new TalonSRX(motor1ID);
pivotMotor = new TalonSRX(PIVOT_MOTOR_ID);
//intakeencoder = new Encoder(1,2);
extendedlimitswitch = new DigitalInput(extendedlimitswitchID);
retractedlimitswitch = new DigitalInput(retractedlimitswitchID);
Expand All @@ -30,7 +30,7 @@ public IntakePivotSubsystem(){
// }

public void movePivot(double speed){
motor1.set(TalonSRXControlMode.PercentOutput, speed);
pivotMotor.set(TalonSRXControlMode.PercentOutput, speed);
}

public boolean pivotisextended(){
Expand All @@ -52,7 +52,7 @@ public boolean pivotisretracted(){
}

public void setPivotSpeed(double right){
motor1.set(TalonSRXControlMode.PercentOutput, right);
pivotMotor.set(TalonSRXControlMode.PercentOutput, right);
}


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,25 +6,25 @@

package frc.robot.subsystems.intake;

import static frc.robot.Constants.RollerandPivotConstants.*;
import static frc.robot.Constants.IntakeConstants.*;

import com.ctre.phoenix.motorcontrol.TalonSRXControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
import edu.wpi.first.wpilibj.AnalogPotentiometer;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class IntakeRollersSubsystem extends SubsystemBase {
private final TalonSRX topmotor;
private final TalonSRX bottommotor;
private final TalonSRX lastmotor;
private final TalonSRX frontMotor;
private final TalonSRX backMotor;
private final TalonSRX integrationMotor;
private final AnalogPotentiometer sensor;


/** Creates a new ExampleSubsystem. */
public IntakeRollersSubsystem() {
lastmotor = new TalonSRX(lastmotorID);
topmotor = new TalonSRX(topmotorID);
bottommotor = new TalonSRX(bottommotorID);
integrationMotor = new TalonSRX(INTEGRATION_MOTOR_ID);
frontMotor = new TalonSRX(FRONT_MOTOR_ID);
backMotor = new TalonSRX(BACK_MOTOR_ID);
sensor = new AnalogPotentiometer(sensorID);
}

Expand All @@ -38,26 +38,26 @@ public boolean sensorNow(){
}

public void setRollSpeed(double top, double bottom){
topmotor.set(TalonSRXControlMode.PercentOutput, top);
bottommotor.set(TalonSRXControlMode.PercentOutput, bottom);
frontMotor.set(TalonSRXControlMode.PercentOutput, top);
backMotor.set(TalonSRXControlMode.PercentOutput, bottom);
}

public void setAllRollSpeed(double topone, double bottomone){
topmotor.set(TalonSRXControlMode.PercentOutput, topone);
lastmotor.set(TalonSRXControlMode.PercentOutput, topone);
bottommotor.set(TalonSRXControlMode.PercentOutput, bottomone);
frontMotor.set(TalonSRXControlMode.PercentOutput, topone);
integrationMotor.set(TalonSRXControlMode.PercentOutput, topone);
backMotor.set(TalonSRXControlMode.PercentOutput, bottomone);
}

public void setRollersOutwards(Boolean pressedA){
if(pressedA==true)
topmotor.set(TalonSRXControlMode.PercentOutput, rollersclockwise);
bottommotor.set(TalonSRXControlMode.PercentOutput, rollerscounterclockwise);
frontMotor.set(TalonSRXControlMode.PercentOutput, rollersclockwise);
backMotor.set(TalonSRXControlMode.PercentOutput, rollerscounterclockwise);
}

public void setRollersInwards(Boolean pressedB){
if(pressedB==true)
topmotor.set(TalonSRXControlMode.PercentOutput, rollersclockwise);
bottommotor.set(TalonSRXControlMode.PercentOutput, rollerscounterclockwise);
frontMotor.set(TalonSRXControlMode.PercentOutput, rollersclockwise);
backMotor.set(TalonSRXControlMode.PercentOutput, rollerscounterclockwise);
}


Expand Down

0 comments on commit a354be7

Please sign in to comment.