Skip to content

Commit

Permalink
Merge pull request #16 from 2491-NoMythic/hall-effects
Browse files Browse the repository at this point in the history
autoclimbing code and hall effects sensors
  • Loading branch information
rflood07 authored Jan 24, 2024
2 parents 33313d9 + 36cd021 commit 9406542
Show file tree
Hide file tree
Showing 2 changed files with 13 additions and 2 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -37,6 +37,6 @@ public void end(boolean interrupted) {
// Returns true when the command should end.
@Override
public boolean isFinished() {
return m_climber.getRightRPM() < ClimberConstants.CLIMBER_RPM && m_climber.getLeftRPM() < ClimberConstants.CLIMBER_RPM;
return m_climber.isClimberIn();
}
}
13 changes: 12 additions & 1 deletion src/main/java/frc/robot/subsystems/Climber.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,14 @@

package frc.robot.subsystems;

import com.revrobotics.CANSparkBase;
import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;
import com.revrobotics.SparkLimitSwitch;
import com.revrobotics.SparkPIDController;
import com.revrobotics.SparkRelativeEncoder;
import com.revrobotics.CANSparkBase.ControlType;
import com.revrobotics.CANDigitalInput.LimitSwitchPolarity;
import com.revrobotics.CANSparkBase.ControlType;
import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkLowLevel.MotorType;

Expand All @@ -22,12 +25,16 @@ public class Climber extends SubsystemBase {
RelativeEncoder climbEncoderL;
double speed;
double voltage;
SparkLimitSwitch limitSwitchR;
SparkLimitSwitch limitSwitchL;
/** Creates a new Climber. */
public Climber() {
climbMotorR = new CANSparkMax(ClimberConstants.CLIMBER_MOTOR_RIGHT, MotorType.kBrushless);
climbMotorL = new CANSparkMax(ClimberConstants.CLIMBER_MOTOR_LEFT, MotorType.kBrushless);
climbEncoderR = climbMotorR.getEncoder(SparkRelativeEncoder.Type.kQuadrature, 4098);
climbEncoderL = climbMotorL.getEncoder(SparkRelativeEncoder.Type.kQuadrature, 4098);
limitSwitchR = climbMotorR.getForwardLimitSwitch(SparkLimitSwitch.Type.kNormallyClosed);
limitSwitchL = climbMotorL.getForwardLimitSwitch(SparkLimitSwitch.Type.kNormallyClosed);
climbMotorL.setIdleMode(IdleMode.kBrake);
climbMotorR.setIdleMode(IdleMode.kBrake);
}
Expand All @@ -54,4 +61,8 @@ public double getLeftRPM(){
return climbEncoderL.getVelocity();
}

public boolean isClimberIn(){
return limitSwitchR.isPressed() && limitSwitchL.isPressed();
}

}

0 comments on commit 9406542

Please sign in to comment.