Adding a few subsystems, not sure I like the use of periodic for the shooter and intake pivot subsystems
This commit is contained in:
82
src/main/java/frc/robot/subsystems/IntakePivot.java
Normal file
82
src/main/java/frc/robot/subsystems/IntakePivot.java
Normal file
@@ -0,0 +1,82 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import java.util.Optional;
|
||||
|
||||
import org.littletonrobotics.junction.Logger;
|
||||
|
||||
import com.revrobotics.AbsoluteEncoder;
|
||||
import com.revrobotics.PersistMode;
|
||||
import com.revrobotics.ResetMode;
|
||||
import com.revrobotics.spark.SparkClosedLoopController;
|
||||
import com.revrobotics.spark.SparkMax;
|
||||
import com.revrobotics.spark.SparkBase.ControlType;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.constants.IntakePivotConstants;
|
||||
import frc.robot.constants.IntakePivotConstants.IntakePivotPosition;
|
||||
|
||||
public class IntakePivot extends SubsystemBase {
|
||||
private SparkMax leftMotor;
|
||||
private SparkMax rightMotor;
|
||||
|
||||
private AbsoluteEncoder encoder;
|
||||
|
||||
private SparkClosedLoopController controller;
|
||||
|
||||
private IntakePivotPosition currentTargetPosition;
|
||||
|
||||
public IntakePivot() {
|
||||
leftMotor = new SparkMax(IntakePivotConstants.kLeftMotorCANID, MotorType.kBrushless);
|
||||
rightMotor = new SparkMax(IntakePivotConstants.kRightMotorCANID, MotorType.kBrushless);
|
||||
|
||||
leftMotor.configure(
|
||||
IntakePivotConstants.leftMotorConfig,
|
||||
ResetMode.kResetSafeParameters,
|
||||
PersistMode.kPersistParameters
|
||||
);
|
||||
|
||||
rightMotor.configure(
|
||||
IntakePivotConstants.rightMotorConfig,
|
||||
ResetMode.kResetSafeParameters,
|
||||
PersistMode.kPersistParameters
|
||||
);
|
||||
|
||||
controller = leftMotor.getClosedLoopController();
|
||||
|
||||
encoder = leftMotor.getAbsoluteEncoder();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void periodic() {
|
||||
if(currentTargetPosition == null) {
|
||||
leftMotor.disable();
|
||||
rightMotor.disable();
|
||||
} else {
|
||||
controller.setSetpoint(currentTargetPosition.getPositionRadians(), ControlType.kPosition);
|
||||
}
|
||||
|
||||
Logger.recordOutput(
|
||||
"IntakePivot/TargetPosition",
|
||||
currentTargetPosition == null ? -1 : currentTargetPosition.getPositionRadians());
|
||||
Logger.recordOutput("IntakePivot/CurrentPosition", encoder.getPosition());
|
||||
Logger.recordOutput("IntakePivot/AtSetpoint", controller.isAtSetpoint());
|
||||
}
|
||||
|
||||
public Command setTargetPosition(IntakePivotPosition position) {
|
||||
return runOnce(() -> {
|
||||
currentTargetPosition = position;
|
||||
});
|
||||
}
|
||||
|
||||
public Command stop() {
|
||||
return runOnce(() -> {
|
||||
currentTargetPosition = null;
|
||||
});
|
||||
}
|
||||
|
||||
public Optional<IntakePivotPosition> getCurrentTargetPosition() {
|
||||
return Optional.of(currentTargetPosition);
|
||||
}
|
||||
}
|
||||
51
src/main/java/frc/robot/subsystems/IntakeRoller.java
Normal file
51
src/main/java/frc/robot/subsystems/IntakeRoller.java
Normal file
@@ -0,0 +1,51 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import com.revrobotics.PersistMode;
|
||||
import com.revrobotics.ResetMode;
|
||||
import com.revrobotics.spark.SparkMax;
|
||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.constants.IntakeRollerConstants;
|
||||
|
||||
public class IntakeRoller extends SubsystemBase {
|
||||
private SparkMax leftMotor;
|
||||
private SparkMax rightMotor;
|
||||
|
||||
public IntakeRoller() {
|
||||
leftMotor = new SparkMax(IntakeRollerConstants.kLeftMotorCANID, MotorType.kBrushless);
|
||||
rightMotor = new SparkMax(IntakeRollerConstants.kRightMotorCANID, MotorType.kBrushless);
|
||||
|
||||
leftMotor.configure(
|
||||
IntakeRollerConstants.leftMotorConfig,
|
||||
ResetMode.kResetSafeParameters,
|
||||
PersistMode.kPersistParameters
|
||||
);
|
||||
|
||||
rightMotor.configure(
|
||||
IntakeRollerConstants.rightMotorConfig,
|
||||
ResetMode.kResetSafeParameters,
|
||||
PersistMode.kPersistParameters
|
||||
);
|
||||
}
|
||||
|
||||
public Command runIn() {
|
||||
return run(() -> {
|
||||
leftMotor.set(1);
|
||||
});
|
||||
}
|
||||
|
||||
public Command runOut() {
|
||||
return run(() -> {
|
||||
leftMotor.set(-1);
|
||||
});
|
||||
}
|
||||
|
||||
public Command stop() {
|
||||
return run(() -> {
|
||||
leftMotor.set(0);
|
||||
});
|
||||
}
|
||||
|
||||
}
|
||||
42
src/main/java/frc/robot/subsystems/Spindexer.java
Normal file
42
src/main/java/frc/robot/subsystems/Spindexer.java
Normal file
@@ -0,0 +1,42 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import com.ctre.phoenix6.controls.DutyCycleOut;
|
||||
import com.ctre.phoenix6.hardware.TalonFX;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.constants.SpindexerConstants;
|
||||
|
||||
public class Spindexer extends SubsystemBase {
|
||||
private TalonFX motor;
|
||||
|
||||
private DutyCycleOut motorOutput;
|
||||
|
||||
public Spindexer() {
|
||||
motor = new TalonFX(SpindexerConstants.kMotorCANID);
|
||||
|
||||
motor.getConfigurator().apply(SpindexerConstants.kCurrentLimitConfig);
|
||||
motor.getConfigurator().apply(SpindexerConstants.kMotorConfig);
|
||||
|
||||
motorOutput = new DutyCycleOut(0);
|
||||
}
|
||||
|
||||
public Command spinToShooter() {
|
||||
return run(() -> {
|
||||
motor.setControl(motorOutput.withOutput(1));
|
||||
});
|
||||
}
|
||||
|
||||
public Command spinToIntake() {
|
||||
return run(() -> {
|
||||
motor.setControl(motorOutput.withOutput(-1));
|
||||
});
|
||||
}
|
||||
|
||||
public Command stop() {
|
||||
return run(() -> {
|
||||
motor.setControl(motorOutput.withOutput(0));
|
||||
});
|
||||
}
|
||||
|
||||
}
|
||||
Reference in New Issue
Block a user