Skip to content
Open
Show file tree
Hide file tree
Changes from all 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
30 changes: 30 additions & 0 deletions assets/Robot_Potato/config.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,30 @@
{
"name": "Potato",
"rotations": [
{
"axis": "x",
"degrees": 90
}
],
"position": [
0,
0,
0
],
"cameras": [],
"components": [
{
"zeroedRotations": [
{
"axis": "x",
"degrees": 90
}
],
"zeroedPositions": [
0,
0,
0
]
}
]
}
Binary file added assets/Robot_Potato/model.glb
Binary file not shown.
Binary file added assets/Robot_Potato/model_0.glb
Binary file not shown.
20 changes: 20 additions & 0 deletions src/main/java/com/team973/frc2025/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
package com.team973.frc2025;

import com.team973.frc2025.subsystems.DriveController;
import com.team973.frc2025.subsystems.turret.TurretIO;
import com.team973.lib.devices.GreyPigeonIO;
import com.team973.lib.util.AllianceCache;
import com.team973.lib.util.Joystick;
Expand All @@ -21,25 +22,32 @@ public class Robot extends TimedRobot {

private final GreyPigeonIO m_pigeon = m_subsystemManager.getPigeon();
private final DriveController m_driveController = m_subsystemManager.getDriveController();
private final TurretIO m_turret = m_subsystemManager.getTurret();

private final Joystick m_driverStick =
new Joystick(0, Joystick.Type.XboxController, m_logger.subLogger("driverStick"));
private final Joystick m_coDriverStick =
new Joystick(1, Joystick.Type.XboxController, m_logger.subLogger("coDriverStick"));

private void syncSensors() {
m_driveController.syncSensors();
m_turret.syncSensors();
}

private void updateSubsystems() {
m_driveController.update();
m_turret.update();
}

private void resetSubsystems() {
m_driveController.reset();
m_turret.reset();
}

private void log() {
m_subsystemManager.log();
m_driveController.log();
m_turret.log();
}

private void updateJoysticks() {
Expand Down Expand Up @@ -95,6 +103,18 @@ public void teleopPeriodic() {
allianceScalar * m_driverStick.getLeftXAxis() * 0.7,
m_driverStick.getRightXAxis() * 0.8);

if (m_coDriverStick.getAButtonPressed()) {
m_turret.setTargetPreset(TurretIO.Preset.One);
} else if (m_coDriverStick.getBButtonPressed()) {
m_turret.setTargetPreset(TurretIO.Preset.Two);
} else if (m_coDriverStick.getXButtonPressed()) {
m_turret.setTargetPreset(TurretIO.Preset.Three);
} else if (m_coDriverStick.getYButtonPressed()) {
m_turret.setState(TurretIO.State.Manual);
}

m_turret.setManualInput(m_coDriverStick.getLeftYAxis());

updateSubsystems();
}

Expand Down
33 changes: 33 additions & 0 deletions src/main/java/com/team973/frc2025/shared/RobotInfo.java
Original file line number Diff line number Diff line change
Expand Up @@ -18,6 +18,39 @@ public class RobotInfo {

public static final DriveInfo DRIVE_INFO = new DriveInfo();

public static final TurretInfo TURRET_INFO = new TurretInfo();

public static class TurretInfo {
public final int MOTOR_ID = 20;

public final double MOTOR_GEAR_RATIO = ((5.0 / 1.0) * (128.0 / 10.0));

public final double TURRET_KS = 0.0;
public final double TURRET_KV = 0.0;
public final double TURRET_KA = 0.0;
public final double TURRET_KP = 2.0;
public final double TURRET_KI = 0.0;
public final double TURRET_KD = 0.0;

public final double TURRET_MOTION_MAGIC_CRUISE_VELOCITY = 10.0;
public final double TURRET_MOTION_MAGIC_ACCELERATION = 10.0;
public final double TURRET_MOTION_MAGIC_JERK = 0.0;

public final double TURRET_VOLTAGE_CLOSED_LOOP_RAMP_PERIOD = 0.0;

public final double STATOR_CURRENT_LIMIT = 60.0;
public final double SUPPLY_CURRENT_LIMIT = 40.0;

public final double PEAK_FORWARD_VOLTAGE = 12.0;
public final double PEAK_REVERSE_VOLTAGE = -12.0;

public final double MANUAL_INPUT_TO_VOLTS = 12.0;

public final double PRESET_ONE = 0.0;
public final double PRESET_TWO = 90.0;
public final double PRESET_THREE = -150.0;
}

public static class DriveInfo {
public final int STATUS_SIGNAL_FREQUENCY = 200;

Expand Down
125 changes: 125 additions & 0 deletions src/main/java/com/team973/frc2025/subsystems/turret/Turret.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,125 @@
package com.team973.frc2025.subsystems.turret;

import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import com.team973.frc2025.shared.RobotInfo;
import com.team973.lib.devices.GreyTalonFX;
import com.team973.lib.util.Logger;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Translation3d;

public class Turret extends TurretIO {
protected static final RobotInfo.TurretInfo m_turretInfo = RobotInfo.TURRET_INFO;

private final Logger m_logger;

protected final GreyTalonFX m_motor;

private double m_targetPostionDeg;
private double m_manualInput;

public Turret(Logger logger) {
m_logger = logger;
m_motor =
new GreyTalonFX(
m_turretInfo.MOTOR_ID, RobotInfo.CANIVORE_CANBUS, m_logger.subLogger("motorRight"));

TalonFXConfiguration motorConfig = new TalonFXConfiguration();

motorConfig.MotorOutput.Inverted = InvertedValue.CounterClockwise_Positive;

motorConfig.Slot0.kS = m_turretInfo.TURRET_KS;
motorConfig.Slot0.kV = m_turretInfo.TURRET_KV;
motorConfig.Slot0.kA = m_turretInfo.TURRET_KA;
motorConfig.Slot0.kP = m_turretInfo.TURRET_KP;
motorConfig.Slot0.kI = m_turretInfo.TURRET_KI;
motorConfig.Slot0.kD = m_turretInfo.TURRET_KD;

motorConfig.MotionMagic.MotionMagicCruiseVelocity =
m_turretInfo.TURRET_MOTION_MAGIC_CRUISE_VELOCITY;
motorConfig.MotionMagic.MotionMagicAcceleration = m_turretInfo.TURRET_MOTION_MAGIC_ACCELERATION;
motorConfig.MotionMagic.MotionMagicJerk = m_turretInfo.TURRET_MOTION_MAGIC_JERK;

motorConfig.ClosedLoopRamps.VoltageClosedLoopRampPeriod =
m_turretInfo.TURRET_VOLTAGE_CLOSED_LOOP_RAMP_PERIOD;

motorConfig.MotorOutput.NeutralMode = NeutralModeValue.Brake;

motorConfig.CurrentLimits.StatorCurrentLimit = m_turretInfo.STATOR_CURRENT_LIMIT;
motorConfig.CurrentLimits.StatorCurrentLimitEnable = true;
motorConfig.CurrentLimits.SupplyCurrentLimit = m_turretInfo.SUPPLY_CURRENT_LIMIT;
motorConfig.CurrentLimits.SupplyCurrentLimitEnable = true;

motorConfig.Voltage.PeakForwardVoltage = m_turretInfo.PEAK_FORWARD_VOLTAGE;
motorConfig.Voltage.PeakReverseVoltage = m_turretInfo.PEAK_REVERSE_VOLTAGE;

m_motor.setConfig(motorConfig);
m_motor.setPosition(0.0);

m_targetPostionDeg = Preset.One.getPositionDeg();
m_manualInput = 0.0;
}

@Override
public Pose3d getPose() {
return new Pose3d(
new Translation3d(),
new Rotation3d(
0, 0, Math.toRadians(motorRotationsToDeg(m_motor.getPosition().getValueAsDouble()))));
}

@Override
public GreyTalonFX getMotor() {
return m_motor;
}

public double degToMotorRotations(double deg) {
return (deg / 360.0) * m_turretInfo.MOTOR_GEAR_RATIO;
}

private double motorRotationsToDeg(double motorPostion) {
return (motorPostion / m_turretInfo.MOTOR_GEAR_RATIO) * 360.0;
}

@Override
public void setTargetPreset(Preset preset) {
m_targetPostionDeg = preset.getPositionDeg();
setState(State.ClosedLoop);
}

@Override
public void setManualInput(double input) {
m_manualInput = input;
}

@Override
public double getTargetPositionMotorRot() {
return degToMotorRotations(m_targetPostionDeg);
}

@Override
public double getManualInput() {
return m_manualInput;
}

@Override
public void syncSensors() {}

@Override
public void log() {
double motorRot = m_motor.getPosition().getValueAsDouble();

m_motor.log();

m_logger.log("currentPostionDeg", motorRotationsToDeg(motorRot));
m_logger.log("targetPostionDeg", m_targetPostionDeg);
m_logger.log("manualInput", m_manualInput);

m_logger.log("state", getState().toString());
}

@Override
public void reset() {}
}
63 changes: 63 additions & 0 deletions src/main/java/com/team973/frc2025/subsystems/turret/TurretIO.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,63 @@
package com.team973.frc2025.subsystems.turret;

import com.team973.frc2025.shared.RobotInfo;
import com.team973.lib.devices.GreyTalonFX;
import com.team973.lib.util.StateMap;
import com.team973.lib.util.Subsystem;
import edu.wpi.first.math.geometry.Pose3d;

public abstract class TurretIO extends Subsystem<TurretIO.State> {
private final StateMap<State> m_stateMap;

protected static final RobotInfo.TurretInfo m_turretInfo = RobotInfo.TURRET_INFO;

public enum State {
ClosedLoop,
Manual,
Off
}

public enum Preset {
One(m_turretInfo.PRESET_ONE),
Two(m_turretInfo.PRESET_TWO),
Three(m_turretInfo.PRESET_THREE);

private final double m_positionDeg;

private Preset(double positionDeg) {
m_positionDeg = positionDeg;
}

public double getPositionDeg() {
return m_positionDeg;
}
}

@SuppressWarnings("unchecked")
public TurretIO() {
super(State.Off);

m_stateMap =
new StateMap<>(
State.class,
new StateMap.Entry<>(State.ClosedLoop, new TurretStates.ClosedLoop(this)),
new StateMap.Entry<>(State.Manual, new TurretStates.Manual(this)),
new StateMap.Entry<>(State.Off, new TurretStates.Off(this)));
}

public StateMap<State> getStateMap() {
return m_stateMap;
}

public abstract Pose3d getPose();

public abstract GreyTalonFX getMotor();

public abstract void setTargetPreset(Preset preset);

public abstract void setManualInput(double volts);

public abstract double getTargetPositionMotorRot();

public abstract double getManualInput();
}
62 changes: 62 additions & 0 deletions src/main/java/com/team973/frc2025/subsystems/turret/TurretSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,62 @@
package com.team973.frc2025.subsystems.turret;

import com.ctre.phoenix6.sim.TalonFXSimState;
import com.team973.lib.util.Logger;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.simulation.SingleJointedArmSim;

public class TurretSim extends Turret {
private final SingleJointedArmSim m_sim;
private final TalonFXSimState m_motorSimState;

private double m_lastPoseRad;

public TurretSim(Logger logger) {
super(logger);

m_sim =
new SingleJointedArmSim(
DCMotor.getKrakenX60(1),
m_turretInfo.MOTOR_GEAR_RATIO,
0.02,
0.0,
Math.toRadians(-165.0),
Math.toRadians(165.0),
false,
Math.toRadians(0.0));

m_motorSimState = m_motor.getSimState();
m_lastPoseRad = m_sim.getAngleRads();
}

@Override
public Pose3d getPose() {
return new Pose3d(new Translation3d(), new Rotation3d(0, 0, m_sim.getAngleRads()));
}

@Override
public void syncSensors() {
m_motorSimState.addRotorPosition(
(((m_sim.getAngleRads() - m_lastPoseRad) / (2 * Math.PI)) * m_turretInfo.MOTOR_GEAR_RATIO));
m_lastPoseRad = m_sim.getAngleRads();

m_motorSimState.setRotorVelocity(m_sim.getVelocityRadPerSec());

m_motorSimState.setSupplyVoltage(RobotController.getBatteryVoltage());

super.syncSensors();
}

@Override
public void update() {
super.update();

m_sim.setInputVoltage(m_motorSimState.getMotorVoltage());

m_sim.update(0.02);
}
}
Loading