Skip to content

Commit

Permalink
feat: Arm subsystem done!
Browse files Browse the repository at this point in the history
  • Loading branch information
lunaggonzalez committed Feb 1, 2025
1 parent 0d0a5cf commit 1933afd
Show file tree
Hide file tree
Showing 8 changed files with 328 additions and 29 deletions.
2 changes: 1 addition & 1 deletion src/main/java/org/team1540/robot2025/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,5 +29,5 @@ public enum Mode {
REPLAY
}

public static final double LOOP_PERIODIC_SECS = 0.02; // TODO: is this value okay?
public static final double LOOP_PERIODIC_SECS = 0.02;
}
120 changes: 117 additions & 3 deletions src/main/java/org/team1540/robot2025/subsystems/arm/Arm.java
Original file line number Diff line number Diff line change
@@ -1,12 +1,126 @@
package org.team1540.robot2025.subsystems.arm;

import static org.team1540.robot2025.subsystems.arm.ArmConstants.*;
// import static org.team1540.robot2025.subsystems.arm.ArmConstants.KP;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.filter.LinearFilter;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotState;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.FunctionalCommand;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import java.util.function.Supplier;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;
import org.team1540.robot2025.Constants;
import org.team1540.robot2025.util.LoggedTunableNumber;
import org.team1540.robot2025.util.MechanismVisualizer;

public class Arm extends SubsystemBase {

// fields:
// private final ArmIO io;
private final ArmIOInputsAutoLogged armInputs = new ArmIOInputsAutoLogged();
private final ArmIO io;
private final ArmIOInputsAutoLogged inputs = new ArmIOInputsAutoLogged();
private final LinearFilter positionFilter = LinearFilter.movingAverage(5); // units: rots
private Rotation2d setpoint = new Rotation2d();
private double avgPositionRots = 0;

private final LoggedTunableNumber kP = new LoggedTunableNumber("Arm/kP", KP);
private final LoggedTunableNumber kI = new LoggedTunableNumber("Arm/kP", KI);
private final LoggedTunableNumber kD = new LoggedTunableNumber("Arm/kP", KD);
private final LoggedTunableNumber kG = new LoggedTunableNumber("Arm/kP", KG);

private static boolean hasInstance = false;

public Arm(ArmIO io) {
if (hasInstance) throw new IllegalStateException("Instance of arm already exists");
hasInstance = true;
this.io = io;
}

public static Arm createReal() {
if (Constants.currentMode != Constants.Mode.REAL) {
DriverStation.reportWarning("Using real shooter on simulated robot", false);
}
return new Arm(new ArmIOReal());
}

public static Arm createSim() {
if (Constants.currentMode == Constants.Mode.REAL) {
DriverStation.reportWarning("Using simulated arm on real robot", false);
}
return new Arm(new ArmIOSim());
}

public static Arm createDummy() {
if (Constants.currentMode == Constants.Mode.REAL) {
DriverStation.reportWarning("Using dummy arm on real robot", false);
}
return new Arm(new ArmIO() {});
}

public void periodic() {
// update + process inputs!
io.updateInputs(inputs);
Logger.processInputs("Arm", inputs);
MechanismVisualizer.setArmRotation(inputs.position);

if (RobotState.isDisabled()) {
io.setVoltage(MathUtil.clamp(0, -12, 12));
}

// update tunable numbers
if (Constants.isTuningMode()
&& (kP.hasChanged(hashCode())
|| kI.hasChanged(hashCode())
|| kD.hasChanged(hashCode())
|| kG.hasChanged(hashCode()))) {
io.configPID(kP.get(), kI.get(), kD.get(), kG.get());
}

avgPositionRots = positionFilter.calculate(inputs.position.getRotations());
}

public void holdPivotPosition() {
setPosition(inputs.position);
}

public void setPosition(Rotation2d position) {
setpoint = Rotation2d.fromRotations(
MathUtil.clamp(position.getRotations(), MIN_ANGLE.getRotations(), MAX_ANGLE.getRotations()));
positionFilter.reset();
io.setPosition(setpoint);
}

public Rotation2d getPosition() {
return inputs.position;
}

public void setPivotBrakeMode(boolean isBrakeMode) {
io.setBrakeMode(isBrakeMode);
}

public boolean isPivotAtSetpoint() {
return MathUtil.isNear(setpoint.getRotations(), avgPositionRots, ERROR_TOLERANCE.getRotations());
}

public Command setPositionCommand(Supplier<Rotation2d> setpoint) {
return new FunctionalCommand(
() -> {}, () -> setPosition(setpoint.get()), (ignored) -> {}, this::isPivotAtSetpoint, this);
}

@AutoLogOutput(key = "Arm/Setpoint")
public Rotation2d getSetpoint() {
return setpoint;
}

public void zero() {
io.setEncoderPosition(0);
}

public void Arm() {}
public void zeroArmToCancoder() {
io.setEncoderPosition(inputs.position.getRotations());
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,6 @@ public class ArmConstants {
public static final Rotation2d MIN_ANGLE = Rotation2d.fromDegrees(30);
public static final Rotation2d MAX_ANGLE = Rotation2d.fromDegrees(330);
public static final Rotation2d STARTING_ANGLE = MIN_ANGLE;
public static final double MEASUREMENT_STANDARD_DEVIATIONS = 0; // TODO:

// PID loop constants
// TODO: what numbers are reasonable?
Expand All @@ -33,6 +32,8 @@ public class ArmConstants {
public static final int MOTOR_ID = 0;
public static final double CANCODER_TO_PIVOT_RATIO = 1;
public static final double MOTOR_TO_CANCODER = 1;
public static final double CANCODER_OFFSET_ROTS = 20; // TODO: get offset
public static final double DISCONTINUITY_POINT = 1; // makes the range 0-1

public static final double CRUISE_VELOCITY_RPS = 1;
public static final double MAX_ACCEL_RPS = 2;
Expand All @@ -41,4 +42,6 @@ public class ArmConstants {
public static final double CURRENT_LIMIT = 10;
public static final double CURRENT_LOWER_LIMIT = 0.1;
public static final double TIME_LOWER_LIMIT = 15;

public static final Rotation2d ERROR_TOLERANCE = Rotation2d.fromDegrees(0.7);
}
17 changes: 10 additions & 7 deletions src/main/java/org/team1540/robot2025/subsystems/arm/ArmIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,26 +6,29 @@
public interface ArmIO {
@AutoLog
class ArmIOInputs {
// TODO: are these inputs okay? do I want any other ones?
public double velocityRPM = 0.0;
public double appliedVolts = 0.0;
public double currentAmps = 0.0;
public Rotation2d rotation2d = new Rotation2d();
public Rotation2d position = new Rotation2d();
public double tempCelsius = 0.0;
public boolean isAtForwardLimit = false;
public boolean isAtReverseLimit = false;
}

// runs open loop at given voltage
default void setVoltage(double voltage) {}

// updates the loggable inputs
default void updateInputs(ArmIOInputs inputs) {}

default void setPosition(Rotation2d setPoint) {}
;
// runs closed loop to given position
default void setPosition(Rotation2d position) {}

default void configPID(double kP, double kI, double kD) {}
;
// configures the PID controller
default void configPID(double kP, double kI, double kD, double kG) {}

// sets neutral output mode, either coast or brake mode
default void setBrakeMode(boolean setBrake) {}
;

default void setEncoderPosition(double rots) {}
}
86 changes: 74 additions & 12 deletions src/main/java/org/team1540/robot2025/subsystems/arm/ArmIOReal.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,34 +2,45 @@

import static org.team1540.robot2025.subsystems.arm.ArmConstants.*;

import com.ctre.phoenix6.BaseStatusSignal;
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.controls.MotionMagicVoltage;
import com.ctre.phoenix6.controls.VoltageOut;
import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.FeedbackSensorSourceValue;
import com.ctre.phoenix6.signals.GravityTypeValue;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import com.ctre.phoenix6.signals.*;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.units.measure.*;

public class ArmIOReal implements ArmIO {
private final TalonFX motor = new TalonFX(MOTOR_ID);
private final CANcoder cancoder = new CANcoder(CANCODER_ID);

// TODO: write status signals later after figuring out what methods I want
private final StatusSignal<Angle> position = motor.getPosition();
private final StatusSignal<AngularVelocity> velocity = motor.getVelocity();
private final StatusSignal<Voltage> appliedVoltage = motor.getMotorVoltage();
private final StatusSignal<Current> current = motor.getSupplyCurrent();
private final StatusSignal<Temperature> temp = motor.getDeviceTemp();
private final StatusSignal<ForwardLimitValue> forwardLimit = motor.getForwardLimit();
private final StatusSignal<ReverseLimitValue> reverseLimit = motor.getReverseLimit();

// private final StatusSignal<Double> position = motor.getPosition();
private final MotionMagicVoltage positionCtrlReq = new MotionMagicVoltage(0).withSlot(0);
private final VoltageOut voltageCtrlReq = new VoltageOut(0);

// constructor
public ArmIOReal() {
TalonFXConfiguration motorConfig = new TalonFXConfiguration();

// TODO: clockwise positive or counter clockwise positive?
motorConfig.MotorOutput.NeutralMode = NeutralModeValue.Coast;
motorConfig.MotorOutput.Inverted = InvertedValue.Clockwise_Positive;

motorConfig.Feedback.FeedbackSensorSource = FeedbackSensorSourceValue.FusedCANcoder;
motorConfig.Feedback.FeedbackRemoteSensorID = CANCODER_ID;
motorConfig.Feedback.SensorToMechanismRatio = CANCODER_TO_PIVOT_RATIO * MOTOR_TO_CANCODER;
motorConfig.Feedback.RotorToSensorRatio = 1; // TODO: is this even true?
motorConfig.Feedback.RotorToSensorRatio = 1;

motorConfig.SoftwareLimitSwitch.ForwardSoftLimitEnable = true;
motorConfig.SoftwareLimitSwitch.ForwardSoftLimitThreshold = MAX_ANGLE.getRotations();
Expand Down Expand Up @@ -61,12 +72,63 @@ public ArmIOReal() {
motorConfig.CurrentLimits.SupplyCurrentLowerTime = TIME_LOWER_LIMIT;

CANcoderConfiguration cancoderConfig = new CANcoderConfiguration();
cancoderConfig.MagnetSensor.SensorDirection = SensorDirectionValue.CounterClockwise_Positive;
cancoderConfig.MagnetSensor.MagnetOffset = CANCODER_OFFSET_ROTS;
cancoderConfig.MagnetSensor.AbsoluteSensorDiscontinuityPoint = DISCONTINUITY_POINT;

cancoder.getConfigurator().apply(cancoderConfig);
motor.getConfigurator().apply(motorConfig);
motor.setPosition(position.getValueAsDouble() * MOTOR_TO_CANCODER);
BaseStatusSignal.setUpdateFrequencyForAll(
50, position, velocity, appliedVoltage, current, temp, forwardLimit, reverseLimit);

motor.optimizeBusUtilization();
cancoder.optimizeBusUtilization();
motor.setPosition(
Rotation2d.fromRotations(position.getValueAsDouble() / CANCODER_TO_PIVOT_RATIO /* *CHAIN_FACTOR? */)
.plus(Rotation2d.fromRotations(CANCODER_OFFSET_ROTS))
.getRotations());
}

@Override
public void updateInputs(ArmIOInputs inputs) {
BaseStatusSignal.refreshAll(position, velocity, appliedVoltage, current, temp, forwardLimit, reverseLimit);
inputs.isAtForwardLimit = forwardLimit.getValue() == ForwardLimitValue.ClosedToGround;
inputs.isAtReverseLimit = reverseLimit.getValue() == ReverseLimitValue.ClosedToGround;
inputs.position = Rotation2d.fromRotations(position.getValueAsDouble());
inputs.velocityRPM = velocity.getValueAsDouble() * 60; // converting from rps to rpm
inputs.appliedVolts = appliedVoltage.getValueAsDouble();
inputs.currentAmps = current.getValueAsDouble();
inputs.tempCelsius = temp.getValueAsDouble();
}

@Override
public void updateInputs(ArmIOInputs inputs) {}
public void setPosition(Rotation2d position) {
motor.setControl(positionCtrlReq.withPosition(position.getRotations()));
}

@Override
public void setVoltage(double volts) {
motor.setControl(voltageCtrlReq.withOutput(volts));
}

// TODO:
// @Override
// public void setPosition
@Override
public void setBrakeMode(boolean isBrakeMode) {
motor.setNeutralMode(isBrakeMode ? NeutralModeValue.Brake : NeutralModeValue.Coast);
}

@Override
public void configPID(double kP, double kI, double kD, double kG) {
Slot0Configs pidConfigs = new Slot0Configs();
pidConfigs.kP = kP;
pidConfigs.kI = kI;
pidConfigs.kD = kD;
pidConfigs.kG = kG;
motor.getConfigurator().apply(pidConfigs);
}

@Override
public void setEncoderPosition(double rots) {
motor.setPosition(rots);
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -32,10 +32,11 @@ public class ArmIOSim implements ArmIO {
private TrapezoidProfile.State goalState;

// methods
// TODO: constructor

@Override
public void updateInputs(ArmIOInputs inputs) {
if (isClosedLoop) {
armAppliedVolts = controller.calculate(armSim.getAngleRads(), inputs.rotation2d.getRadians())
armAppliedVolts = controller.calculate(armSim.getAngleRads(), inputs.position.getRadians())
+ feedforward.calculate(
Units.rotationsToDegrees(controller.getSetpoint().position),
controller.getSetpoint().velocity);
Expand All @@ -44,13 +45,13 @@ public void updateInputs(ArmIOInputs inputs) {
armSim.setInputVoltage(armAppliedVolts);
armSim.update(LOOP_PERIODIC_SECS);

// TODO: should I rename rotation2d to call it position rotation 2d
inputs.rotation2d = Rotation2d.fromRadians(armSim.getAngleRads());
inputs.position = Rotation2d.fromRadians(armSim.getAngleRads());
inputs.appliedVolts = armAppliedVolts;
inputs.currentAmps = armSim.getCurrentDrawAmps();
inputs.velocityRPM = armSim.getVelocityRadPerSec() * 60 / (2 * Math.PI); // converting to rpm;
}

@Override
public void setPosition(Rotation2d position) {
controller.reset(
Units.radiansToRotations(armSim.getAngleRads()),
Expand All @@ -59,10 +60,12 @@ public void setPosition(Rotation2d position) {
goalState = new TrapezoidProfile.State(position.getRotations(), 0);
}

public void configPID(double kP, double kI, double kD) {
@Override
public void configPID(double kP, double kI, double kD, double kG) {
controller.setPID(kP, kI, kD);
}

@Override
public void setVoltage(double volts) {
isClosedLoop = false;
armAppliedVolts = volts;
Expand Down
Loading

0 comments on commit 1933afd

Please sign in to comment.