Skip to content

Commit

Permalink
Merge pull request #15 from Team612/comp1edits
Browse files Browse the repository at this point in the history
final draft changes
  • Loading branch information
Abhinav-Vadlamani authored Feb 24, 2024
2 parents 22c4a62 + c6a0aac commit 4930fd0
Show file tree
Hide file tree
Showing 5 changed files with 16 additions and 7 deletions.
9 changes: 5 additions & 4 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ public static final class Mod0 {
public static final int driveMotorID = 2;
public static final int angleMotorID = 3;
public static final int canCoderID = 0;
public static final Rotation2d desiredAngle = Rotation2d.fromDegrees(223); //43
public static final Rotation2d desiredAngle = Rotation2d.fromDegrees(0); //43
public static final SwerveModuleConstants constants =
new SwerveModuleConstants(driveMotorID, angleMotorID, canCoderID, desiredAngle);
}
Expand All @@ -130,7 +130,7 @@ public static final class Mod1 {
public static final int driveMotorID = 8;
public static final int angleMotorID = 1;
public static final int canCoderID = 1;
public static final Rotation2d desiredAngle = Rotation2d.fromDegrees(344); //344
public static final Rotation2d desiredAngle = Rotation2d.fromDegrees(0); //344
public static final SwerveModuleConstants constants =
new SwerveModuleConstants(driveMotorID, angleMotorID, canCoderID, desiredAngle);
}
Expand All @@ -140,7 +140,7 @@ public static final class Mod2 {
public static final int driveMotorID = 4;
public static final int angleMotorID = 5;
public static final int canCoderID = 2;
public static final Rotation2d desiredAngle = Rotation2d.fromDegrees(87);
public static final Rotation2d desiredAngle = Rotation2d.fromDegrees(0);
public static final SwerveModuleConstants constants =
new SwerveModuleConstants(driveMotorID, angleMotorID, canCoderID, desiredAngle);
}
Expand All @@ -150,7 +150,7 @@ public static final class Mod3 {
public static final int driveMotorID = 6;
public static final int angleMotorID = 7;
public static final int canCoderID = 3;
public static final Rotation2d desiredAngle = Rotation2d.fromDegrees(73.5);
public static final Rotation2d desiredAngle = Rotation2d.fromDegrees(0);
public static final SwerveModuleConstants constants =
new SwerveModuleConstants(driveMotorID, angleMotorID, canCoderID, desiredAngle);
}
Expand Down Expand Up @@ -199,6 +199,7 @@ public static class IntakeConstants{
public static final double intakeUpSpeed = 0.1;
public static final double intakeDownSpeed = -0.1;
public static final double rollerSpeed = 0.1;
public static final int IRport = 1;
}

// Shooter constants
Expand Down
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,8 @@ private void configureButtonBindings() {
ControlMap.m_gunnerController.x().whileTrue(m_moveRollers);
ControlMap.m_gunnerController.y().whileTrue(m_shootSpeaker);
ControlMap.m_gunnerController.leftTrigger().whileTrue(m_shootAmp);

// FOR TESTING, REMOVE FOR COMP
ControlMap.m_gunnerController.leftBumper().whileTrue(m_shootLeftMotor);
ControlMap.m_gunnerController.rightBumper().whileTrue(m_shootRightMotor);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,6 @@ public void end(boolean interrupted) {
// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
return m_Intake.getIRSensor();
}
}
6 changes: 6 additions & 0 deletions src/main/java/frc/robot/subsystems/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

package frc.robot.subsystems;

import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import com.ctre.phoenix.motorcontrol.TalonSRXControlMode;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
Expand All @@ -18,6 +19,7 @@ public class Intake extends SubsystemBase {
private static final double DEADZONE = 0.05;
private CANSparkMax m_IntakePivotMotor;
private TalonSRX m_IntakeRollerMotor;
private DigitalInput IRSensor = new DigitalInput(Constants.IntakeConstants.IRport);
static Intake instance = null;
/** Creates a new Intake. */
public Intake() {
Expand Down Expand Up @@ -51,6 +53,10 @@ public void moveRollers(double rotate){
m_IntakeRollerMotor.set(TalonSRXControlMode.PercentOutput, rotate);
}

public boolean getIRSensor(){
return IRSensor.get();
}

@Override
public void periodic() {
// This method will be called once per scheduler run
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,8 @@ public static Shooter getInstance(){
public void shoot(double rotateLeft, double rotateRight){
if(rotateLeft < DEADZONE) rotateLeft = 0;
if(rotateRight < DEADZONE) rotateRight = 0;
m_ShooterMotorLeft.set(TalonSRXControlMode.PercentOutput, rotateLeft);
m_ShooterMotorRight.set(TalonSRXControlMode.PercentOutput, rotateRight);
moveLeftMotor(rotateLeft);
moveRightMotor(rotateRight);
}

// move left motor
Expand Down

0 comments on commit 4930fd0

Please sign in to comment.