Skip to content

Commit

Permalink
IO for FEEDER
Browse files Browse the repository at this point in the history
  • Loading branch information
michaelx0281 committed Jan 17, 2024
1 parent fc5005e commit e801fbf
Show file tree
Hide file tree
Showing 4 changed files with 41 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -22,6 +22,9 @@ public static class FF {

public static class Feeder {
public static final double GEARING = -1;

public static final double kV = 1;
public static final double kA = 1;
}

public static class Pivot {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,6 @@
public interface FeederIO {

public void setFeederVoltage(double voltage);
// public double getFeederVoltage();

public double getFeederSpeed();
}
Original file line number Diff line number Diff line change
@@ -1,18 +1,26 @@
package org.sciborgs1155.robot.shooter.feeder;

import static org.sciborgs1155.robot.Ports.Shooter.Feeder.*;

import com.revrobotics.CANSparkBase.IdleMode;
import com.revrobotics.CANSparkFlex;
import com.revrobotics.CANSparkLowLevel.MotorType;

public class RealFeeder implements FeederIO{
CANSparkFlex motor = new CANSparkFlex(0, MotorType.kBrushless)
public class RealFeeder implements FeederIO {

@Override
public double getFeederSpeed(){
private final CANSparkFlex motor = new CANSparkFlex(FEEDER_SPARK, MotorType.kBrushless);

}
public RealFeeder() {
motor.setIdleMode(IdleMode.kBrake);
}

@Override
public void setFeederVoltage(double speed){
// @Override
// public double getFeederVoltage() {
// return motor.getBusVoltage();
// }

}
@Override
public void setFeederVoltage(double speed) {
motor.setVoltage(speed);
}
}
Original file line number Diff line number Diff line change
@@ -1,3 +1,23 @@
package org.sciborgs1155.robot.shooter.feeder;

public class SimFeeder {}
import static org.sciborgs1155.robot.shooter.ShooterConstants.Feeder.*;

import edu.wpi.first.math.system.plant.DCMotor;
import edu.wpi.first.math.system.plant.LinearSystemId;
import edu.wpi.first.wpilibj.simulation.DCMotorSim;

public class SimFeeder implements FeederIO {
DCMotor motor = DCMotor.getNEO(1);

private final DCMotorSim simMotor =
new DCMotorSim(LinearSystemId.createDCMotorSystem(kV, kA), motor, GEARING);

// @Override public double getFeederVoltage(){
// motor.getVoltage()
// }

@Override
public void setFeederVoltage(double voltage) {
simMotor.setInputVoltage(voltage);
}
}

0 comments on commit e801fbf

Please sign in to comment.