Skip to content
Open
Show file tree
Hide file tree
Changes from 4 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -0,0 +1,98 @@
package frc.trigon.robot.subsystems.sideshooter;

import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.AbsoluteSensorRangeValue;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkMaxLowLevel;
import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.trajectory.TrapezoidProfile;

public class SideShooterConstants {
private static final int
SHOOTING_MOTOR_ID = 0,
ANGLE_MOTOR_ID = 0,
ANGLE_ENCODER_ID = 0;
private static final NeutralModeValue SHOOTING_NEUTRAL_MODE_VALUE = NeutralModeValue.Coast;
private static final CANSparkMax.IdleMode ANGLE_IDLE_MODE = CANSparkMax.IdleMode.kBrake;
private static final InvertedValue SHOOTING_INVERTED_VALUE = InvertedValue.CounterClockwise_Positive;
private static final boolean ANGLE_INVERTED = false;
private static final double ENCODER_OFFSET = 0;
private static final AbsoluteSensorRangeValue ENCODER_RANGE_VALUE = AbsoluteSensorRangeValue.Signed_PlusMinusHalf;
private static final double VOLTAGE_COMPENSATION_VALUE = 0;
private static final double
MAX_ANGLE_VELOCITY = 0,
MAX_ANGLE_ACCELERATION = 0;
static final CANcoder ANGLE_ENCODER = new CANcoder(ANGLE_ENCODER_ID);
static final TalonFX SHOOTING_MOTOR = new TalonFX(SHOOTING_MOTOR_ID);
static final CANSparkMax ANGEL_MOTOR = new CANSparkMax(ANGLE_MOTOR_ID, CANSparkMaxLowLevel.MotorType.kBrushless);
static final boolean FOC_ENABLED = true;
static final TrapezoidProfile.Constraints ANGLE_CONSTRAINTS = new TrapezoidProfile.Constraints(
MAX_ANGLE_VELOCITY, MAX_ANGLE_ACCELERATION
);
static final StatusSignal<Double> ANGEL_ENCODER_POSITION_SIGNAL = ANGLE_ENCODER.getPosition();
static final StatusSignal<Double> ANGEL_ENCODER_VELOCITY_SIGNAL = ANGLE_ENCODER.getVelocity();
private static final double
ANGLE_P = 0,
ANGLE_I = 0,
ANGLE_D = 0;
static final PIDController ANGLE_PID_CONTROLLER = new PIDController(
ANGLE_P,
ANGLE_I,
ANGLE_D
);

static {
configureShootingMotor();
configureAngleMotor();
configureAngleEncoder();
}

private static void configureShootingMotor() {
TalonFXConfiguration config = new TalonFXConfiguration();
config.Audio.BeepOnBoot = false;
config.Audio.BeepOnConfig = false;
config.MotorOutput.NeutralMode = SHOOTING_NEUTRAL_MODE_VALUE;
config.MotorOutput.Inverted = SHOOTING_INVERTED_VALUE;
SHOOTING_MOTOR.getConfigurator().apply(config);
SHOOTING_MOTOR.optimizeBusUtilization();
}

private static void configureAngleMotor() {
ANGEL_MOTOR.restoreFactoryDefaults();
ANGEL_MOTOR.setIdleMode(ANGLE_IDLE_MODE);
ANGEL_MOTOR.setInverted(ANGLE_INVERTED);
ANGEL_MOTOR.enableVoltageCompensation(VOLTAGE_COMPENSATION_VALUE);
}

private static void configureAngleEncoder() {
CANcoderConfiguration config = new CANcoderConfiguration();
config.MagnetSensor.MagnetOffset = ENCODER_OFFSET;
config.MagnetSensor.AbsoluteSensorRange = ENCODER_RANGE_VALUE;
ANGLE_ENCODER.getConfigurator().apply(config);
ANGEL_ENCODER_POSITION_SIGNAL.setUpdateFrequency(100);
ANGEL_ENCODER_VELOCITY_SIGNAL.setUpdateFrequency(100);
ANGLE_ENCODER.optimizeBusUtilization();
}

public enum SideShooterState {
COLLECTION(Rotation2d.fromDegrees(0),0),
HIGH_STATE(Rotation2d.fromDegrees(0), 0),
MID_STATE(Rotation2d.fromDegrees(0), 0),
LOW_STATE(Rotation2d.fromDegrees(0), 0);

final Rotation2d angle;
final double voltage;

SideShooterState(Rotation2d angle, double voltage) {
this.angle = angle;
this.voltage = voltage;
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,78 @@
package frc.trigon.robot.subsystems.sideshooter;


import com.ctre.phoenix6.controls.VoltageOut;
import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.hardware.TalonFX;
import com.revrobotics.CANSparkMax;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.FunctionalCommand;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public class SideShooterSubsystem extends SubsystemBase {
private final static SideShooterSubsystem INSTANCE = new SideShooterSubsystem();
private final static TalonFX SHOOTER_MOTOR = SideShooterConstants.SHOOTING_MOTOR;
private final static CANSparkMax ANGLE_MOTOR = SideShooterConstants.ANGEL_MOTOR;
private final static CANcoder ANGLE_ENCODER = SideShooterConstants.ANGLE_ENCODER;
private final VoltageOut ShootingVoltageRequest = new VoltageOut(0, SideShooterConstants.FOC_ENABLED, false);
public static SideShooterSubsystem getInstance() {
return INSTANCE;
}
private TrapezoidProfile angleMotorProfile = null;
private double lastAngleMotorProfileGeneration;

private SideShooterSubsystem() {
}

private void setTargetShootingVoltage(double voltage) {
SHOOTER_MOTOR.setControl(ShootingVoltageRequest.withOutput(voltage));
}

private Rotation2d getAngleMotorPosition(){
double positionRevolutions = SideShooterConstants.ANGEL_ENCODER_POSITION_SIGNAL.refresh().getValue();
return Rotation2d.fromRotations(positionRevolutions);
}

private double getAngleMotorVelocity(){
return SideShooterConstants.ANGEL_ENCODER_VELOCITY_SIGNAL.refresh().getValue();
}

private double getAngleMotorProfileTime(){
return Timer.getFPGATimestamp() - lastAngleMotorProfileGeneration;
}

private void generateAngleMotorProfile(Rotation2d targetAngle){
angleMotorProfile = new TrapezoidProfile(
SideShooterConstants.ANGLE_CONSTRAINTS,
new TrapezoidProfile.State(targetAngle.getDegrees(), 0),
new TrapezoidProfile.State(getAngleMotorPosition().getDegrees(), getAngleMotorVelocity())
);

lastAngleMotorProfileGeneration = Timer.getFPGATimestamp();
}

private void setTargetAngleFromProfile(){
if (angleMotorProfile == null){
ANGLE_MOTOR.stopMotor();
return;
}

TrapezoidProfile.State targetState = angleMotorProfile.calculate(getAngleMotorProfileTime());
SideShooterConstants.ANGLE_PID_CONTROLLER.calculate(getAngleMotorPosition().getDegrees(), targetState.position);
}

public Command getSetTargetAngleCommand(Rotation2d targetAngle){
return new FunctionalCommand(
()-> generateAngleMotorProfile(targetAngle),
this::setTargetAngleFromProfile,
(interrupted) -> {
},
()-> false,
this
);
}
}