Skip to content
Open
Show file tree
Hide file tree
Changes from 10 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
133 changes: 133 additions & 0 deletions src/main/java/frc/trigon/robot/subsystems/arm/ArmConstants.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,133 @@
package frc.trigon.robot.subsystems.arm;

import com.ctre.phoenix.motorcontrol.FeedbackDevice;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.signals.AbsoluteSensorRangeValue;
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;
import frc.trigon.robot.utilities.Conversions;

public class ArmConstants {
private static final int
MASTER_ELEVATOR_MOTOR_ID = 0,
FOLLOWER_ELEVATOR_MOTOR_ID = 0,
MASTER_ANGLE_MOTOR_ID = 0,
FOLLOWER_ANGLE_MOTOR_ID = 0,
ANGLE_ENCODER_ID = 0,
ELEVATOR_ENCODER_ID = 0;
private static final CANSparkMax.IdleMode
MASTER_ANGLE_IDLE_MODE = CANSparkMax.IdleMode.kBrake,
FOLLOWER_ANGLE_IDLE_MODE = CANSparkMax.IdleMode.kBrake,
MASTER_ELEVATOR_IDLE_MODE = CANSparkMax.IdleMode.kBrake,
FOLLOWER_ELEVATOR_IDLE_MODE = CANSparkMax.IdleMode.kBrake;
private static final boolean
MASTER_ANGLE_INVERTED = false,
FOLLOWER_ANGLE_INVERTED = false,
MASTER_ELEVATOR_INVERTED = false,
FOLLOWER_ELEVATOR_INVERTED = false,
ELEVATOR_ENCODER_PHASE = false;
private static final double VOLTAGE_COMPENSATION_SATURATION = 12;
private static final SensorDirectionValue ANGLE_ENCODER_SENSOR_DIRECTION_VALUE = SensorDirectionValue.CounterClockwise_Positive;
private static final double
ANGLE_ENCODER_OFFSET = 0,
ELEVATOR_ENCODER_OFFSET = 0;
private static final AbsoluteSensorRangeValue ANGLE_ENCODER_RANGE_VALUE = AbsoluteSensorRangeValue.Signed_PlusMinusHalf;
static final CANSparkMax
MASTER_ELEVATOR_MOTOR = new CANSparkMax(MASTER_ELEVATOR_MOTOR_ID, CANSparkMaxLowLevel.MotorType.kBrushless),
FOLLOWER_ELEVATOR_MOTOR = new CANSparkMax(FOLLOWER_ANGLE_MOTOR_ID, CANSparkMaxLowLevel.MotorType.kBrushless),
MASTER_ANGLE_MOTOR = new CANSparkMax(MASTER_ANGLE_MOTOR_ID, CANSparkMaxLowLevel.MotorType.kBrushless),
FOLLOWER_ANGLE_MOTOR = new CANSparkMax(FOLLOWER_ELEVATOR_MOTOR_ID, CANSparkMaxLowLevel.MotorType.kBrushless);
static final CANcoder ANGLE_ENCODER = new CANcoder(ANGLE_ENCODER_ID);
static final WPI_TalonSRX ELEVATOR_ENCODER = new WPI_TalonSRX(ELEVATOR_ENCODER_ID);

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 {
configureAngleMotors();
configureElevatorMotors();
configureAngleEncoder();
configureElevatorEncoder();
}

private static void configureAngleMotors() {
MASTER_ANGLE_MOTOR.restoreFactoryDefaults();
FOLLOWER_ANGLE_MOTOR.restoreFactoryDefaults();
MASTER_ANGLE_MOTOR.setIdleMode(MASTER_ANGLE_IDLE_MODE);
FOLLOWER_ANGLE_MOTOR.setIdleMode(FOLLOWER_ANGLE_IDLE_MODE);
MASTER_ANGLE_MOTOR.setInverted(MASTER_ANGLE_INVERTED);
FOLLOWER_ANGLE_MOTOR.setInverted(FOLLOWER_ANGLE_INVERTED);
MASTER_ANGLE_MOTOR.enableVoltageCompensation(VOLTAGE_COMPENSATION_SATURATION);
FOLLOWER_ANGLE_MOTOR.enableVoltageCompensation(VOLTAGE_COMPENSATION_SATURATION);
}

private static void configureElevatorMotors() {
MASTER_ELEVATOR_MOTOR.restoreFactoryDefaults();
FOLLOWER_ELEVATOR_MOTOR.restoreFactoryDefaults();
MASTER_ELEVATOR_MOTOR.setIdleMode(MASTER_ELEVATOR_IDLE_MODE);
FOLLOWER_ELEVATOR_MOTOR.setIdleMode(FOLLOWER_ELEVATOR_IDLE_MODE);
MASTER_ELEVATOR_MOTOR.setInverted(MASTER_ELEVATOR_INVERTED);
FOLLOWER_ELEVATOR_MOTOR.setInverted(FOLLOWER_ELEVATOR_INVERTED);
MASTER_ELEVATOR_MOTOR.enableVoltageCompensation(VOLTAGE_COMPENSATION_SATURATION);
FOLLOWER_ELEVATOR_MOTOR.enableVoltageCompensation(VOLTAGE_COMPENSATION_SATURATION);
}

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

private static void configureElevatorEncoder() {
ELEVATOR_ENCODER.configFactoryDefault();
ELEVATOR_ENCODER.configSelectedFeedbackSensor(FeedbackDevice.CTRE_MagEncoder_Absolute);
ELEVATOR_ENCODER.setSensorPhase(ELEVATOR_ENCODER_PHASE);
ELEVATOR_ENCODER.setSelectedSensorPosition(Conversions.offsetRead(ELEVATOR_ENCODER.getSelectedSensorPosition(), ELEVATOR_ENCODER_OFFSET));
}

public enum ArmState {
CONE_COLLECTION(Rotation2d.fromDegrees(0), 0),
CONE_HIGH_STATE(Rotation2d.fromDegrees(0), 0),
CONE_MID_STATE(Rotation2d.fromDegrees(0), 0),
CONE_LOW_STATE(Rotation2d.fromDegrees(0), 0);

final Rotation2d angle;
final double elevatorPosition;

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

import com.ctre.phoenix6.controls.VoltageOut;
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 VoltageOut shootingVoltageRequest = new VoltageOut(0, SideShooterConstants.FOC_ENABLED, false);
private TrapezoidProfile angleMotorProfile = null;
private double lastAngleMotorProfileGeneration;
private double angleTolerance = 1;

public static SideShooter getInstance() {
return INSTANCE;
}

private SideShooter() {
}

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

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();
}

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

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

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

boolean atAngle(Rotation2d angle){
return Math.abs(angle.getDegrees() - getAnglePosition().getDegrees()) < angleTolerance;
}

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 getAngleProfileTime() {
return Timer.getFPGATimestamp() - lastAngleMotorProfileGeneration;
}
}
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.Command;
import edu.wpi.first.wpilibj2.command.ParallelCommandGroup;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
import edu.wpi.first.wpilibj2.command.FunctionalCommand;
import edu.wpi.first.wpilibj2.command.StartEndCommand;
import frc.trigon.robot.utilities.Commands;

public class SideShooterCommands {
private static final SideShooter SIDE_SHOOTER = SideShooter.getInstance();

public static Command getSetTargetStateCommand(boolean byOrder, SideShooterConstants.SideShooterState targetState) {
if (!byOrder) {
return new ParallelCommandGroup(
Commands.removeRequirements(getSetTargetAngleCommand(targetState.angle)),
getSetTargetShootingVoltageCommand(targetState.voltage)
);
}
return new SequentialCommandGroup(
Commands.removeRequirements(getSetTargetAngleCommand(targetState.angle).until(() -> SIDE_SHOOTER.atAngle(targetState.angle))),
getSetTargetShootingVoltageCommand(targetState.voltage)
);
}

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

public static Command getSetTargetShootingVoltageCommand(double targetVoltage) {
return new StartEndCommand(
() -> SIDE_SHOOTER.setTargetShootingVoltage(targetVoltage),
SIDE_SHOOTER::stopShooting,
SIDE_SHOOTER
);
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,107 @@
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;
}
}
}
4 changes: 2 additions & 2 deletions src/main/java/frc/trigon/robot/utilities/Commands.java
Original file line number Diff line number Diff line change
@@ -1,10 +1,10 @@
package frc.trigon.robot.utilities;

import edu.wpi.first.wpilibj2.command.CommandBase;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.FunctionalCommand;

public class Commands {
public static Command removeRequirements(CommandBase command) {
public static Command removeRequirements(Command command) {
return new FunctionalCommand(
command::initialize,
command::execute,
Expand Down