Skip to content

Commit

Permalink
save
Browse files Browse the repository at this point in the history
  • Loading branch information
Thierry-Lachance committed Jan 26, 2024
1 parent 1e446d1 commit e912d3f
Show file tree
Hide file tree
Showing 6 changed files with 57 additions and 20 deletions.
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -39,5 +39,7 @@ public static class OperatorConstants {
public static class PCM {
public final int PISTON_FORWARD = 0;
public final int PISTON_REVERSE = 1;
public final int PISTON_CLIMBER_FORWARD = 2;
public final int PISTON_CLIMBER_REVERSE = 3;
}
}
9 changes: 8 additions & 1 deletion src/main/java/frc/robot/commands/ClimberInABoxCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,14 @@ public void initialize() {}
// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
climberInAnBox.climb(xboxController.getRightTriggerAxis());
if(xboxController.getRightTriggerAxis() != 0){
climberInAnBox.activateRatchet();
climberInAnBox.climb(xboxController.getRightTriggerAxis());
}
if(xboxController.getLeftTriggerAxis() != 0){
climberInAnBox.climb(-xboxController.getLeftTriggerAxis());
}

}

// Called once the command ends or is interrupted.
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/commands/SetShooterAngleCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,9 @@ public SetShooterAngleCommand(AngleShooter angleShooter, Limelight limelight) {
// The controller that the command will use
new PIDController(0, 0, 0),
// This should return the measurement
() -> angleShooter.getEncoder(),
() -> angleShooter.getEncoderValue(),
// This should return the setpoint (can also be a constant)
() -> (angleShooter.encoderZero()+((limelight.calculateShooterAngle()*8.57))),//TODO adjust 8.57 based on gearbox and encoder
() -> ((limelight.calculateShooterAngle()*8.57)),//TODO adjust 8.57 based on gearbox and encoder
// This uses the output
output -> {
angleShooter.setPower(output);
Expand Down
19 changes: 10 additions & 9 deletions src/main/java/frc/robot/subsystems/AngleShooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,19 +5,21 @@
package frc.robot.subsystems;

import com.revrobotics.CANSparkLowLevel.MotorType;
import com.revrobotics.AbsoluteEncoder;
import com.revrobotics.CANSparkMax;
import com.revrobotics.RelativeEncoder;


import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.wpilibj.DutyCycleEncoder;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.OperatorConstants;

public class AngleShooter extends SubsystemBase {
private CANSparkMax shooterAngle;
private RelativeEncoder shooterAngleEncoder;
private DutyCycleEncoder shooterAngleEncoder = new DutyCycleEncoder(0);
private PIDController pidControllerShooterAngle = new PIDController(0.1, 0.1, 0);

private double shooterAngleEncoderZero = 0.0;

private double encoderOffset = 0.0;


Expand All @@ -30,15 +32,14 @@ public AngleShooter() {

shooterAngle.setInverted(false);

shooterAngleEncoder = shooterAngle.getAlternateEncoder(42);


}
public double getEncoder(){
return shooterAngleEncoder.getPosition() + encoderOffset;
}
public double encoderZero(){
return shooterAngleEncoderZero;
public double getEncoderValue(){

return shooterAngleEncoder.getAbsolutePosition()-encoderOffset;
}

public void setPower(double power){
shooterAngle.set(power);
}
Expand Down
28 changes: 21 additions & 7 deletions src/main/java/frc/robot/subsystems/ClimberInAnBox.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,30 +4,44 @@

package frc.robot.subsystems;

import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkLowLevel.MotorType;
import edu.wpi.first.wpilibj.DoubleSolenoid;
import edu.wpi.first.wpilibj.PneumaticsModuleType;
import edu.wpi.first.wpilibj.motorcontrol.Talon;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.OperatorConstants;
import frc.robot.Constants.PCM;

public class ClimberInAnBox extends SubsystemBase {
private CANSparkMax climberDroit;
private CANSparkMax climberGauche;
private Talon climberDroit;
private Talon climberGauche;
private DoubleSolenoid piston;

/** Creates a new ClimberInAnBox. */
public ClimberInAnBox() {
OperatorConstants deviceNumber = new OperatorConstants();
climberDroit = new CANSparkMax(deviceNumber.DeviceNumberClimberDroit, MotorType.kBrushless);
climberGauche = new CANSparkMax(deviceNumber.DeviceNumberClimberGauche, MotorType.kBrushless);
PCM pcm = new PCM();
climberDroit = new Talon(deviceNumber.DeviceNumberClimberDroit);
climberGauche = new Talon(deviceNumber.DeviceNumberClimberGauche);

climberDroit.setInverted(false);
climberGauche.setInverted(false);
piston =
new DoubleSolenoid(1, PneumaticsModuleType.CTREPCM, pcm.PISTON_CLIMBER_FORWARD, pcm.PISTON_CLIMBER_REVERSE);
piston.set(DoubleSolenoid.Value.kReverse);
}

public void climb(double activated) {
climberDroit.set(activated);
climberGauche.set(activated);
}

public void activateRatchet(){

piston.set(DoubleSolenoid.Value.kForward);




}
@Override
public void periodic() {
// This method will be called once per scheduler run
Expand Down
15 changes: 14 additions & 1 deletion src/main/java/frc/robot/subsystems/Intake.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,7 @@
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkLowLevel.MotorType;

import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.OperatorConstants;

Expand All @@ -15,6 +16,9 @@ public class Intake extends SubsystemBase {
private CANSparkMax intakeDroit;
private CANSparkMax intakeGauche;
private CANSparkMax intakePivot;

DigitalInput outlimitSwitch = new DigitalInput(0);
DigitalInput inlimitSwitch = new DigitalInput(1);
public Intake() {
OperatorConstants deviceNumber = new OperatorConstants();
intakeDroit = new CANSparkMax(deviceNumber.DeviceNumberIntakeDroit, MotorType.kBrushless);
Expand All @@ -30,7 +34,16 @@ public void spinWheel(double power){
intakeGauche.set(power);
}
public void moveIntake(double power){
intakePivot.set(power);
if(inlimitSwitch.get() && power < 0){
intakePivot.set(0);
}
else if(outlimitSwitch.get() && power > 0){
intakePivot.set(0);
}
else{
intakePivot.set(power);
}

}
@Override
public void periodic() {
Expand Down

0 comments on commit e912d3f

Please sign in to comment.