-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
- Loading branch information
1 parent
86acd7f
commit 791b7d5
Showing
6 changed files
with
158 additions
and
54 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,38 @@ | ||
package frc.robot.climber; | ||
|
||
import edu.wpi.first.wpilibj2.command.Command; | ||
import edu.wpi.first.wpilibj2.command.SubsystemBase; | ||
import org.littletonrobotics.junction.Logger; | ||
|
||
public class Climber extends SubsystemBase { | ||
private final ClimberIO m_climberIO; | ||
private final ClimberIOInputsAutoLogged m_inputs = new ClimberIOInputsAutoLogged(); | ||
|
||
public Climber(ClimberIO climberIO) { | ||
m_climberIO = climberIO; | ||
|
||
setDefaultCommand(idle()); | ||
} | ||
|
||
@Override | ||
public void periodic() { | ||
m_climberIO.updateInputs(m_inputs); | ||
Logger.processInputs("ClimberInputs", m_inputs); | ||
} | ||
|
||
public Command idle() { | ||
return this.run( | ||
() -> { | ||
m_climberIO.setLeftDutyCycle(0.0); | ||
m_climberIO.setRightDutyCycle(0.0); | ||
}); | ||
} | ||
|
||
public Command winchDown() { | ||
return this.run( | ||
() -> { | ||
m_climberIO.setLeftDutyCycle(0.5); | ||
m_climberIO.setRightDutyCycle(0.5); | ||
}); | ||
} | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,24 @@ | ||
package frc.robot.climber; | ||
|
||
import org.littletonrobotics.junction.AutoLog; | ||
|
||
public interface ClimberIO { | ||
@AutoLog | ||
public class ClimberIOInputs { | ||
public double leftWinchPositionRad = 0.0; | ||
public double leftWinchVelocityRadPerSec = 0.0; | ||
public double leftWinchAppliedVolts = 0.0; | ||
public double leftWinchCurrentAmps = 0.0; | ||
|
||
public double rightWinchPositionRad = 0.0; | ||
public double rightWinchVelocityRadPerSec = 0.0; | ||
public double rightWinchAppliedVolts = 0.0; | ||
public double rightWinchCurrentAmps = 0.0; | ||
} | ||
|
||
public default void updateInputs(ClimberIOInputs inputs) {} | ||
|
||
public default void setLeftDutyCycle(double outputDutyCycle) {} | ||
|
||
public default void setRightDutyCycle(double outputDutyCycle) {} | ||
} |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,50 @@ | ||
package frc.robot.climber; | ||
|
||
import com.revrobotics.CANSparkMax; | ||
import com.revrobotics.RelativeEncoder; | ||
import edu.wpi.first.math.util.Units; | ||
|
||
public class ClimberIOSparkMAX implements ClimberIO { | ||
|
||
private final double kWinchReduction = 1.0; | ||
private final CANSparkMax m_leftWinchMotor, m_rightWinchMotor; | ||
private final RelativeEncoder m_leftWinchEncoder, m_rightWinchEncoder; | ||
|
||
public ClimberIOSparkMAX() { | ||
|
||
m_leftWinchMotor = new CANSparkMax(8, CANSparkMax.MotorType.kBrushless); | ||
m_rightWinchMotor = new CANSparkMax(9, CANSparkMax.MotorType.kBrushless); | ||
|
||
m_leftWinchEncoder = m_leftWinchMotor.getEncoder(); | ||
m_rightWinchEncoder = m_rightWinchMotor.getEncoder(); | ||
} | ||
|
||
@Override | ||
public void updateInputs(ClimberIOInputs inputs) { | ||
inputs.leftWinchPositionRad = | ||
Units.rotationsToRadians(m_leftWinchEncoder.getPosition() / kWinchReduction); | ||
inputs.leftWinchVelocityRadPerSec = | ||
Units.rotationsToRadians(m_leftWinchEncoder.getVelocity() / kWinchReduction); | ||
inputs.leftWinchAppliedVolts = | ||
m_leftWinchMotor.getAppliedOutput() * m_leftWinchMotor.getBusVoltage(); | ||
inputs.leftWinchCurrentAmps = m_leftWinchMotor.getOutputCurrent(); | ||
|
||
inputs.rightWinchPositionRad = | ||
Units.rotationsToRadians(m_rightWinchEncoder.getPosition() / kWinchReduction); | ||
inputs.rightWinchVelocityRadPerSec = | ||
Units.rotationsToRadians(m_rightWinchEncoder.getVelocity() / kWinchReduction); | ||
inputs.rightWinchAppliedVolts = | ||
m_rightWinchMotor.getAppliedOutput() * m_rightWinchMotor.getBusVoltage(); | ||
inputs.rightWinchCurrentAmps = m_rightWinchMotor.getOutputCurrent(); | ||
} | ||
|
||
@Override | ||
public void setLeftDutyCycle(double outputDutyCycle) { | ||
m_leftWinchMotor.set(outputDutyCycle); | ||
} | ||
|
||
@Override | ||
public void setRightDutyCycle(double outputDutyCycle) { | ||
m_rightWinchMotor.set(outputDutyCycle); | ||
} | ||
} |