Skip to content

Commit

Permalink
Yotam- make elbow which works for both simulation and real, robot typ…
Browse files Browse the repository at this point in the history
…e constant, ElbowFactory
  • Loading branch information
Yotam7 committed Aug 7, 2024
1 parent ead47f9 commit e12b953
Show file tree
Hide file tree
Showing 5 changed files with 58 additions and 18 deletions.
32 changes: 32 additions & 0 deletions src/main/java/subsystems/elbow/Elbow.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
package subsystems.elbow;

import edu.wpi.first.math.geometry.Rotation2d;

public class Elbow implements IElbow {

private IElbow iElbow;

public Elbow(){
iElbow =Factory.create();
}

@Override
public Rotation2d getAngle() {
return iElbow.getAngle();
}

@Override
public double getRPMVelocity() {
return iElbow.getRPMVelocity();
}

@Override
public void setPower(double power) {
iElbow.setPower(power);
}

@Override
public void goToPosition(Rotation2d position) {
iElbow.goToPosition(position);
}
}
16 changes: 16 additions & 0 deletions src/main/java/subsystems/elbow/Factory.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
package subsystems.elbow;

import subsystems.elbow.neoElbow.NeoElbow;
import subsystems.elbow.simulationElbow.SimulationElbow;
import training.Robot;

public class Factory {

public static IElbow create(){
return switch (Robot.ROBOT_TYPE){
case REAL -> new NeoElbow();
case SIMULATION -> new SimulationElbow();
};
}

}
10 changes: 1 addition & 9 deletions src/main/java/subsystems/elbow/neoElbow/NeoElbow.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,23 +9,15 @@

public class NeoElbow extends GBSubsystem implements IElbow {

private static NeoElbow instance;
private static CANSparkMax motor;

private NeoElbow() {
public NeoElbow() {
motor = new CANSparkMax(NeoElbowConstants.MOTOR_ID, RobotConstants.MOTOR_BRUSHLESS_TYPE);
motor.getPIDController().setP(ElbowConstants.KP);
motor.getPIDController().setI(ElbowConstants.KI);
motor.getPIDController().setD(ElbowConstants.KD);
}

public static NeoElbow getInstance() {
if (instance == null) {
instance = new NeoElbow();
}
return instance;
}

public Rotation2d getAngle() {
return Rotation2d.fromRotations(motor.getEncoder().getPosition() % 1);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,11 +10,10 @@

public class SimulationElbow implements IElbow {

private static SimulationElbow instance;
private final SingleJointedArmSim motor;
private final PIDController controller;

private SimulationElbow() {
public SimulationElbow() {
this.motor = new SingleJointedArmSim(
DCMotor.getFalcon500(SimulationElbowConstants.NUMBER_OF_MOTORS),
SimulationElbowConstants.GEAR_RATIO,
Expand All @@ -28,13 +27,6 @@ private SimulationElbow() {
this.controller = new PIDController(ElbowConstants.KP, ElbowConstants.KI, ElbowConstants.KD);
}

public SimulationElbow getInstance() {
if (instance == null) {
instance = new SimulationElbow();
}
return instance;
}

@Override
public Rotation2d getAngle() {
return Rotation2d.fromRadians(motor.getAngleRads());
Expand Down
8 changes: 8 additions & 0 deletions src/main/java/training/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,14 @@

public class Robot {

public enum RobotType{
SIMULATION,
REAL
}

public static final RobotType ROBOT_TYPE = RobotType.REAL;


// Enter your subsystems...
private final NeoElbow elbow;
private final Wrist wrist;
Expand Down

0 comments on commit e12b953

Please sign in to comment.