Skip to content

Commit

Permalink
Merge pull request #57 from 2491-NoMythic/Distance-Sensor
Browse files Browse the repository at this point in the history
  • Loading branch information
veggie2u authored Feb 10, 2024
2 parents eb9c1d4 + 85764a5 commit ec409b8
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 8 deletions.
7 changes: 6 additions & 1 deletion src/main/java/frc/robot/subsystems/IndexerSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.SparkAnalogSensor.Mode;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.settings.Constants.IndexerConstants;

Expand All @@ -18,7 +19,7 @@ public IndexerSubsystem() {
}

public boolean isNoteIn() {
return m_DistanceSensor.getVoltage()>1;
return m_DistanceSensor.getVoltage()>2;
}

public void on() {
Expand All @@ -32,4 +33,8 @@ public void off() {
public void reverse() {
m_IndexerMotor.set(-IndexerConstants.INDEXER_SPEED);
}
@Override
public void periodic() {
SmartDashboard.putNumber("voltage sensor output", m_DistanceSensor.getVoltage());
}
}
14 changes: 7 additions & 7 deletions src/main/java/frc/robot/subsystems/IntakeSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,12 @@

import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.SparkPIDController;
import com.revrobotics.SparkPIDController;
import com.revrobotics.SparkRelativeEncoder;
import com.revrobotics.CANSparkBase.ControlType;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.settings.Constants.IntakeConstants;
public class IntakeSubsystem extends SubsystemBase {
/** Creates a new Intake. */
Expand All @@ -23,11 +23,11 @@ public class IntakeSubsystem extends SubsystemBase {

double intakeRunSpeed;
public IntakeSubsystem() {
CANSparkMax intake1 = new CANSparkMax(IntakeConstants.INTAKE_1_MOTOR, MotorType.kBrushless);
CANSparkMax intake2 = new CANSparkMax(IntakeConstants.INTAKE_1_MOTOR, MotorType.kBrushless);
CANSparkMax brush1 = new CANSparkMax(IntakeConstants.BRUSH_1_MOTOR, MotorType.kBrushless);
CANSparkMax brush2 = new CANSparkMax(IntakeConstants.BRUSH_2_MOTOR, MotorType.kBrushless);
CANSparkMax brush3 = new CANSparkMax(IntakeConstants.BRUSH_3_MOTOR, MotorType.kBrushless);
intake1 = new CANSparkMax(IntakeConstants.INTAKE_1_MOTOR, MotorType.kBrushless);
intake2 = new CANSparkMax(IntakeConstants.INTAKE_1_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);

intake2.follow(intake1);
intake2.setInverted(true);
Expand Down

0 comments on commit ec409b8

Please sign in to comment.