Skip to content

Commit

Permalink
added burnFlash() method to motor configurations and also set more ID…
Browse files Browse the repository at this point in the history
…s and added brushes perference
  • Loading branch information
rflood07 committed Feb 14, 2024
1 parent 289baef commit ff6f3c1
Show file tree
Hide file tree
Showing 4 changed files with 36 additions and 23 deletions.
1 change: 1 addition & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -123,6 +123,7 @@ public class RobotContainer {
/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
//preferences are initialized IF they don't already exist on the Rio
Preferences.initBoolean("Brushes", false);
Preferences.initBoolean("Intake", false);
Preferences.initBoolean("Climber", false);
Preferences.initBoolean("Shooter", false);
Expand Down
14 changes: 7 additions & 7 deletions src/main/java/frc/robot/settings/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -254,9 +254,9 @@ private DriveConstants() {
public static final double k_PICKUP_NOTE_tx_D = 0;
}
public static final class ShooterConstants{
public static final int SHOOTER_R_MOTORID = 2491;
public static final int SHOOTER_L_MOTORID = 2491;
public static final int PITCH_MOTOR_ID = 2491;
public static final int SHOOTER_R_MOTORID = 10;
public static final int SHOOTER_L_MOTORID = 9;
public static final int PITCH_MOTOR_ID = 22;
public static final double SHOOTER_MOTOR_POWER = 1;
public static final double SHOOTING_SPEED_MPS = 10;
public static final double RUNNING_VELOCITY_RPS = 2491;
Expand Down Expand Up @@ -310,15 +310,15 @@ public static final class ClimberConstants{
public static final double CLIMBER_RPM = 0.1;
}
public static final class IndexerConstants{
public static final int INDEXER_MOTOR = 2491;
public static final int INDEXER_MOTOR = 23;
public static final double INDEXER_SPEED = 2491;
}
public static final class IntakeConstants{
public static final int INTAKE_1_MOTOR = 20;
public static final int INTAKE_2_MOTOR = 21;
public static final int BRUSH_1_MOTOR = 22;
public static final int BRUSH_2_MOTOR = 23;
public static final int BRUSH_3_MOTOR = 24;
public static final int BRUSH_1_MOTOR = 2491;
public static final int BRUSH_2_MOTOR = 2491;
public static final int BRUSH_3_MOTOR = 2491;
public static final double INTAKE_SPEED = 0.75;
}
public static final class CTREConfigs {
Expand Down
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/subsystems/IndexerSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,8 @@ public class IndexerSubsystem extends SubsystemBase {

public IndexerSubsystem() {
m_IndexerMotor = new CANSparkMax(IndexerConstants.INDEXER_MOTOR, MotorType.kBrushless);
m_IndexerMotor.setInverted(false);
m_IndexerMotor.burnFlash();
m_DistanceSensor = m_IndexerMotor.getAnalog(Mode.kAbsolute);
}

Expand Down
42 changes: 26 additions & 16 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;

import edu.wpi.first.wpilibj.Preferences;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.settings.Constants.IntakeConstants;
Expand All @@ -27,36 +28,45 @@ public class IntakeSubsystem extends SubsystemBase {
public IntakeSubsystem() {
intake1 = new CANSparkMax(IntakeConstants.INTAKE_1_MOTOR, MotorType.kBrushless);
intake2 = new CANSparkMax(IntakeConstants.INTAKE_2_MOTOR, MotorType.kBrushless);
brush1 = new CANSparkMax(IntakeConstants.BRUSH_1_MOTOR, MotorType.kBrushless);
brush2 = new CANSparkMax(IntakeConstants.BRUSH_2_MOTOR, MotorType.kBrushless);
brush3 = new CANSparkMax(IntakeConstants.BRUSH_3_MOTOR, MotorType.kBrushless);

if(Preferences.getBoolean("Brushes", false)) {
brush1 = new CANSparkMax(IntakeConstants.BRUSH_1_MOTOR, MotorType.kBrushless);
brush2 = new CANSparkMax(IntakeConstants.BRUSH_2_MOTOR, MotorType.kBrushless);
brush3 = new CANSparkMax(IntakeConstants.BRUSH_3_MOTOR, MotorType.kBrushless);
brush1.setIdleMode(IdleMode.kCoast);
brush2.setIdleMode(IdleMode.kCoast);
brush3.setIdleMode(IdleMode.kCoast);
}
intake2.follow(intake1);
intake2.setInverted(true);
intake1.setIdleMode(IdleMode.kCoast);
intake2.setIdleMode(IdleMode.kCoast);
brush1.setIdleMode(IdleMode.kCoast);
brush2.setIdleMode(IdleMode.kCoast);
brush3.setIdleMode(IdleMode.kCoast);
intake1.burnFlash();
intake2.burnFlash();
}

public void intakeYes(double intakeRunSpeed) {
intake1.set(intakeRunSpeed);
brush1.set(intakeRunSpeed);
brush2.set(intakeRunSpeed);
brush3.set(intakeRunSpeed);
if(Preferences.getBoolean("Brushes", false)) {
brush1.set(intakeRunSpeed);
brush2.set(intakeRunSpeed);
brush3.set(intakeRunSpeed);
}

}
public void intakeNo(double intakeRunSpeed) {
intake1.set(-intakeRunSpeed);
brush1.set(-intakeRunSpeed);
brush2.set(-intakeRunSpeed);
brush3.set(-intakeRunSpeed);
if(Preferences.getBoolean("Brushes", false)) {
brush1.set(-intakeRunSpeed);
brush2.set(-intakeRunSpeed);
brush3.set(-intakeRunSpeed);
}
}
public void intakeOff() {
intake1.set(0);
brush2.set(0);
brush1.set(0);
brush3.set(0);
if(Preferences.getBoolean("Brushes", false)) {
brush2.set(0);
brush1.set(0);
brush3.set(0);
}
}
}

0 comments on commit ff6f3c1

Please sign in to comment.