Skip to content
Open
Show file tree
Hide file tree
Changes from 6 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,70 @@
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.SubsystemBase;

public class SideShooter extends SubsystemBase {
private final static SideShooter INSTANCE = new SideShooter();
private final TalonFX shootingMotor = SideShooterConstants.SHOOTING_MOTOR;
private final CANSparkMax angelMotor = SideShooterConstants.ANGEL_MOTOR;
private final CANcoder angleEncoder = SideShooterConstants.ANGLE_ENCODER;
private final VoltageOut shootingVoltageRequest = new VoltageOut(0, SideShooterConstants.FOC_ENABLED, false);
private TrapezoidProfile angleMotorProfile = null;
private double lastAngleMotorProfileGeneration;
public static SideShooter getInstance() {
return INSTANCE;
}

private SideShooter() {
}

void setTargetShootingVoltage(double voltage) {
shootingMotor.setControl(shootingVoltageRequest.withOutput(voltage));
}

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

TrapezoidProfile.State targetState = angleMotorProfile.calculate(getAngleMotorProfileTime());
double output = SideShooterConstants.ANGLE_PID_CONTROLLER.calculate(getAnglePosition().getDegrees(), targetState.position);
angelMotor.setVoltage(output);
}

void stopShooting(){
shootingMotor.stopMotor();
}

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

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

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

void generateAngleMotorProfile(Rotation2d targetAngle){
angleMotorProfile = new TrapezoidProfile(
SideShooterConstants.ANGLE_CONSTRAINTS,
new TrapezoidProfile.State(targetAngle.getDegrees(), 0),
new TrapezoidProfile.State(getAnglePosition().getDegrees(), getAngleVelocity())
);

lastAngleMotorProfileGeneration = Timer.getFPGATimestamp();
}
}

Original file line number Diff line number Diff line change
@@ -0,0 +1,45 @@
package frc.trigon.robot.subsystems.sideshooter;

import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj2.command.*;

public class SideShooterCommands {
private static final SideShooter SIDE_SHOOTER = SideShooter.getInstance();
public static Command getSetTargetAngleCommand(Rotation2d targetAngle){
return new FunctionalCommand(
()-> SideShooter.getInstance().generateAngleMotorProfile(targetAngle),
SIDE_SHOOTER::setTargetAngleFromProfile,
(interrupted) -> {
},
()-> false,
SIDE_SHOOTER
);
}

public static Command getSetVoltageShootingCommand(double Voltage){
return new StartEndCommand(
()-> SideShooter.getInstance().setTargetShootingVoltage(Voltage),
()-> SideShooter.getInstance().stopShooting(),
SIDE_SHOOTER
);
}

public static Command getSetTargetStateCommand(boolean byOrder, SideShooterConstants.SideShooterState state){
if (byOrder){
return new ParallelCommandGroup(
getSetTargetAngleCommand(state.angle),
getSetVoltageShootingCommand(state.voltage)
);
}else {
return new SequentialCommandGroup(
getSetTargetAngleCommand(state.angle),
getSetVoltageShootingCommand(state.voltage)
);
}
}
}





Original file line number Diff line number Diff line change
@@ -0,0 +1,104 @@
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.ctre.phoenix6.signals.SensorDirectionValue;
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 SensorDirectionValue ANGLE_ENCODER_SENSOR_DIRECTION_VALUE = SensorDirectionValue.CounterClockwise_Positive;
private static final double ENCODER_OFFSET = 0;
private static final AbsoluteSensorRangeValue ENCODER_RANGE_VALUE = AbsoluteSensorRangeValue.Signed_PlusMinusHalf;
private static final double VOLTAGE_COMPENSATION_SATURATION = 12;
static final boolean FOC_ENABLED = true;
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);
private static final double
MAX_ANGLE_VELOCITY = 0,
MAX_ANGLE_ACCELERATION = 0;
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(),
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_SATURATION);
}

private static void configureAngleEncoder() {
CANcoderConfiguration config = new CANcoderConfiguration();
config.MagnetSensor.MagnetOffset = ENCODER_OFFSET;
config.MagnetSensor.AbsoluteSensorRange = ENCODER_RANGE_VALUE;
config.MagnetSensor.SensorDirection = ANGLE_ENCODER_SENSOR_DIRECTION_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;
}
}
}