Skip to content

Commit

Permalink
intake -> neo
Browse files Browse the repository at this point in the history
  • Loading branch information
rgodha24 committed Feb 23, 2024
1 parent 17f59be commit 59b19f4
Show file tree
Hide file tree
Showing 6 changed files with 37 additions and 31 deletions.
22 changes: 12 additions & 10 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,16 +23,10 @@
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.commands.DriveCommands;
import frc.robot.commands.FeedForwardCharacterization;
import frc.robot.subsystems.drive.Drive;
import frc.robot.subsystems.drive.GyroIO;
import frc.robot.subsystems.drive.GyroIOPigeon2;
import frc.robot.subsystems.drive.ModuleIO;
import frc.robot.subsystems.drive.ModuleIOSim;
import frc.robot.subsystems.drive.ModuleIOTalonFX;
import frc.robot.subsystems.intake.Intake;
import frc.robot.subsystems.intake.IntakeIO;
import frc.robot.subsystems.intake.IntakeIOReal;
import frc.robot.subsystems.intake.IntakeIOSim;
import frc.robot.subsystems.drive.*;
import frc.robot.subsystems.intake.*;
import frc.robot.subsystems.pivot.*;
import frc.robot.subsystems.shooter.*;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;

/**
Expand All @@ -45,6 +39,8 @@ public class RobotContainer {
// Subsystems
private final Drive drive;
private final Intake intake;
private final Pivot pivot;
private final Shooter shooter;

// Controller
private final CommandXboxController driver = new CommandXboxController(0);
Expand All @@ -66,6 +62,8 @@ public RobotContainer() {
new ModuleIOTalonFX(3));

intake = new Intake(new IntakeIOReal());
pivot = new Pivot(new PivotIOReal());
shooter = new Shooter(new ShooterIOReal());

break;

Expand All @@ -80,6 +78,8 @@ public RobotContainer() {
new ModuleIOSim());

intake = new Intake(new IntakeIOSim());
pivot = new Pivot(new PivotIOSim());
shooter = new Shooter(new ShooterIOSim());

break;

Expand All @@ -94,6 +94,8 @@ public RobotContainer() {
new ModuleIO() {});

intake = new Intake(new IntakeIO() {});
pivot = new Pivot(new PivotIO() {});
shooter = new Shooter(new ShooterIO() {});

break;
}
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/frc/robot/subsystems/drive/Drive.java
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,8 @@

public class Drive extends SubsystemBase {
private static final double MAX_LINEAR_SPEED = Units.feetToMeters(14.5);
private static final double TRACK_WIDTH_X = Units.inchesToMeters(25.0);
private static final double TRACK_WIDTH_Y = Units.inchesToMeters(25.0);
private static final double TRACK_WIDTH_X = Units.inchesToMeters(22.75);
private static final double TRACK_WIDTH_Y = Units.inchesToMeters(18.75);
private static final double DRIVE_BASE_RADIUS =
Math.hypot(TRACK_WIDTH_X / 2.0, TRACK_WIDTH_Y / 2.0);
private static final double MAX_ANGULAR_SPEED = MAX_LINEAR_SPEED / DRIVE_BASE_RADIUS;
Expand Down
14 changes: 7 additions & 7 deletions src/main/java/frc/robot/subsystems/drive/GyroIOPigeon2.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,18 +24,18 @@

/** IO implementation for Pigeon2 */
public class GyroIOPigeon2 implements GyroIO {
private final Pigeon2 pigeo = new Pigeon2(20);
private final StatusSignal<Double> yaw = pigeo.getYaw();
private final Pigeon2 pigeon = new Pigeon2(20);
private final StatusSignal<Double> yaw = pigeon.getYaw();
private final Queue<Double> yawPositionQueue;
private final StatusSignal<Double> yawVelocity = pigeo.getAngularVelocityZWorld();
private final StatusSignal<Double> yawVelocity = pigeon.getAngularVelocityZWorld();

public GyroIOPigeon2(boolean phoenixDrive) {
pigeo.getConfigurator().apply(new Pigeon2Configuration());
pigeo.getConfigurator().setYaw(0.0);
pigeon.getConfigurator().apply(new Pigeon2Configuration());
pigeon.getConfigurator().setYaw(0.0);
yaw.setUpdateFrequency(Module.ODOMETRY_FREQUENCY);
yawVelocity.setUpdateFrequency(100.0);
pigeo.optimizeBusUtilization();
yawPositionQueue = PhoenixOdometryThread.getInstance().registerSignal(pigeo, pigeo.getYaw());
pigeon.optimizeBusUtilization();
yawPositionQueue = PhoenixOdometryThread.getInstance().registerSignal(pigeon, pigeon.getYaw());
}

@Override
Expand Down
18 changes: 6 additions & 12 deletions src/main/java/frc/robot/subsystems/intake/IntakeIOReal.java
Original file line number Diff line number Diff line change
@@ -1,26 +1,20 @@
package frc.robot.subsystems.intake;

import com.ctre.phoenix6.BaseStatusSignal;
import com.ctre.phoenix6.StatusSignal;
import com.ctre.phoenix6.hardware.TalonFX;
import com.revrobotics.CANSparkMax;
import com.revrobotics.CANSparkLowLevel.MotorType;

import frc.robot.Constants.IntakeConstants;

public class IntakeIOReal implements IntakeIO {
private final TalonFX motor;
private final StatusSignal<Double> current;
private final CANSparkMax motor;

public IntakeIOReal() {
motor = new TalonFX(IntakeConstants.intakeCANId);
current = motor.getStatorCurrent();

BaseStatusSignal.setUpdateFrequencyForAll(20.0, current);
motor.optimizeBusUtilization();
motor = new CANSparkMax(IntakeConstants.intakeCANId, MotorType.kBrushless);
}

@Override
public void updateInputs(IntakeIO.IntakeIOInputs inputs) {
BaseStatusSignal.refreshAll(current);
inputs.current = current.getValue();
inputs.current = motor.getOutputCurrent();
}

@Override
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/subsystems/pivot/PivotIOSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
package frc.robot.subsystems.pivot;

public class PivotIOSim implements PivotIO {
// todo
}
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/subsystems/shooter/ShooterIOSim.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
package frc.robot.subsystems.shooter;

public class ShooterIOSim implements ShooterIO {
//todo
}

0 comments on commit 59b19f4

Please sign in to comment.