Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Miniberty #6

Open
wants to merge 22 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from 12 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,91 @@
package frc.trigon.robot.subsystems.sideshooter;


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.math.util.Units;
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;
import frc.trigon.robot.utilities.Conversions;

public class SideShooter extends SubsystemBase {
private final static SideShooter INSTANCE = new SideShooter();

private final TalonFX shootingMotor = SideShooterConstants.SHOOTING_MOTOR;
private final CANSparkMax angleMotor = SideShooterConstants.ANGLE_MOTOR;
private final CANcoder angleEncoder = SideShooterConstants.ANGLE_ENCODER;

private TrapezoidProfile angleMotorProfile = null;
private double lastAngleMotorProfileGenerationTime;

private SideShooter() {
}

public static SideShooter getInstance() {
return INSTANCE;
}

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

private void generateAngleMotorProfile(Rotation2d targetAngle) {
angleMotorProfile = new TrapezoidProfile(
SideShooterConstants.ANGLE_CONSTRAINTS,
new TrapezoidProfile.State(targetAngle.getDegrees(), 0),
new TrapezoidProfile.State(getAnglePosition().getDegrees(), getAngleVelocityDegreesPerSecond())
);
lastAngleMotorProfileGenerationTime = Timer.getFPGATimestamp();
}

private void setTargetAngleFromProfile() {
if (angleMotorProfile == null) {
stopAngleMotor();
}

TrapezoidProfile.State targetState = angleMotorProfile.calculate(getAngleMotorProfileTime());
angleMotor.setVoltage(calculateAngleMotorOutput());
}

private Rotation2d getAnglePosition() {
return Rotation2d.fromRotations(SideShooterConstants.ANGLE_ENCODER_POSITION_SIGNAL.refresh().getValue());
}

private double getAngleVelocityDegreesPerSecond() {
return Conversions.revolutionsToDegrees(SideShooterConstants.ANGLE_ENCODER_VELOCITY_SIGNAL.refresh().getValue());
}

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

private double calculateAngleMotorOutput() {
TrapezoidProfile.State targetState = angleMotorProfile.calculate(getAngleMotorProfileTime());
double pidOutput = SideShooterConstants.ANGLE_PID_CONTROLLER.calculate(
getAnglePosition().getDegrees(),
targetState.position
);
double feedforward = SideShooterConstants.ANGLE_MOTOR_FEEDFORWARD.calculate(
Units.degreesToRadians(targetState.position),
Units.degreesToRadians(targetState.velocity)
);
return pidOutput + feedforward;
}

private void stopAngleMotor() {
angleMotor.stopMotor();
}
}

Original file line number Diff line number Diff line change
@@ -0,0 +1,110 @@
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.ArmFeedforward;
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 double VOLTAGE_COMPENSATION_SATURATION = 12;
private static final int
SHOOTING_MOTOR_ID = 0,
ANGLE_MOTOR_ID = 1,
ANGLE_ENCODER_ID = 2;
private static final double ANGLE_ENCODER_OFFSET = 0;
private static final AbsoluteSensorRangeValue ANGLE_ENCODER_RANGE = AbsoluteSensorRangeValue.Signed_PlusMinusHalf;
private static final InvertedValue SHOOTING_MOTOR_INVERTED_VALUE = InvertedValue.CounterClockwise_Positive;
private static final boolean ANGLE_MOTOR_INVERTED = false;

private static final SensorDirectionValue ANGLE_ENCODER_DIRECTION = SensorDirectionValue.Clockwise_Positive;
private static final NeutralModeValue SHOOTING_NEUTRAL_MODE_VALUE = NeutralModeValue.Coast;
private static final CANSparkMax.IdleMode ANGLE_MOTOR_IDLE_MODE = CANSparkMax.IdleMode.kBrake;

static final CANSparkMax ANGLE_MOTOR = new CANSparkMax(ANGLE_MOTOR_ID, CANSparkMaxLowLevel.MotorType.kBrushless);
static final CANcoder ANGLE_ENCODER = new CANcoder(ANGLE_ENCODER_ID);
static final TalonFX SHOOTING_MOTOR = new TalonFX(SHOOTING_MOTOR_ID);

private static final double
MAX_ANGLE_VELOCITY = 600,
MAX_ANGLE_ACCELERATION = 500;
static final TrapezoidProfile.Constraints ANGLE_CONSTRAINTS = new TrapezoidProfile.Constraints(MAX_ANGLE_VELOCITY, MAX_ANGLE_ACCELERATION);

private static final double
ANGLE_MOTOR_P = 1,
ANGLE_MOTOR_I = 0,
ANGLE_MOTOR_D = 0;
static final PIDController ANGLE_PID_CONTROLLER = new PIDController(ANGLE_MOTOR_P, ANGLE_MOTOR_I, ANGLE_MOTOR_D);

private static final double
ANGLE_MOTOR_KS = 0.5990,
ANGLE_MOTOR_KV = 0.5990,
ANGLE_MOTOR_KA = 0.5990,
ANGLE_MOTOR_KG = 0.5990;
static final ArmFeedforward ANGLE_MOTOR_FEEDFORWARD = new ArmFeedforward(
ANGLE_MOTOR_KS,ANGLE_MOTOR_KG,ANGLE_MOTOR_KV,ANGLE_MOTOR_KA
);

static final StatusSignal<Double> ANGLE_ENCODER_POSITION_SIGNAL = ANGLE_ENCODER.getPosition();
static final StatusSignal<Double> ANGLE_ENCODER_VELOCITY_SIGNAL = ANGLE_ENCODER.getVelocity();

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

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

SHOOTING_MOTOR.optimizeBusUtilization();
}

private static void configureAngleMotor() {
ANGLE_MOTOR.restoreFactoryDefaults();
ANGLE_MOTOR.setIdleMode(ANGLE_MOTOR_IDLE_MODE);
ANGLE_MOTOR.setInverted(ANGLE_MOTOR_INVERTED);
ANGLE_MOTOR.enableVoltageCompensation(VOLTAGE_COMPENSATION_SATURATION);
}

private static void configureAngleEncoder() {
CANcoderConfiguration config = new CANcoderConfiguration();
config.MagnetSensor.AbsoluteSensorRange = ANGLE_ENCODER_RANGE;
config.MagnetSensor.MagnetOffset = ANGLE_ENCODER_OFFSET;
config.MagnetSensor.SensorDirection = ANGLE_ENCODER_DIRECTION;
ANGLE_ENCODER.getConfigurator().apply(config);

ANGLE_ENCODER_POSITION_SIGNAL.setUpdateFrequency(100);
ANGLE_ENCODER.optimizeBusUtilization();
}

public enum SideShooterState {
COLLECTION(Rotation2d.fromDegrees(-15), -5),
MIDDLE(Rotation2d.fromDegrees(30), 5),
HIGH(Rotation2d.fromDegrees(60), 10);

final Rotation2d angle;
final double voltage;

SideShooterState(Rotation2d angle, double voltage) {
this.angle = angle;
this.voltage = voltage;
}
}
}