Skip to content

Commit

Permalink
fixed fixmes in elevator subsystem/commands
Browse files Browse the repository at this point in the history
  • Loading branch information
miyac22 committed Sep 19, 2023
1 parent 67cef0a commit d88b586
Show file tree
Hide file tree
Showing 3 changed files with 14 additions and 24 deletions.
1 change: 0 additions & 1 deletion src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,6 @@
import java.nio.file.Path;
import java.util.List;
import java.util.Map;
import java.util.NodeSelectorUtility.ScoreTypeIdentifier;
import java.util.Set;

@SuppressWarnings("java:S1118")
Expand Down
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/commands/ElevatorPositionCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -10,16 +10,16 @@
public class ElevatorPositionCommand extends CommandBase {
private final ElevatorSubsystem ElevatorSubsystem;
private final double targetHeight;
private final double desiredAngle; // FIXME rename to "targetAngle"
private final double targetAngle; // FIXME rename to "targetAngle"

/** Creates a new ArmPositionCommand. */
public ElevatorPositionCommand(
ElevatorSubsystem elevatorSubsystem, double targetHeight, double desiredAngle) {
ElevatorSubsystem elevatorSubsystem, double targetHeight, double targetAngle) {
// FIXME make a second constructor that requires an ElevatorState instead of two doubles for
// height and angle
this.ElevatorSubsystem = elevatorSubsystem;
this.targetHeight = targetHeight;
this.desiredAngle = desiredAngle;
this.targetAngle = targetAngle;
// Use addRequirements() here to declare subsystem dependencies.
addRequirements(elevatorSubsystem);
}
Expand All @@ -28,7 +28,7 @@ public ElevatorPositionCommand(
@Override
public void initialize() {
ElevatorSubsystem.setTargetHeight(targetHeight);
ElevatorSubsystem.setDesiredAngle(desiredAngle);
ElevatorSubsystem.setTargetAngle(targetAngle);
}

// Called every time the scheduler runs while the command is scheduled.
Expand Down
29 changes: 10 additions & 19 deletions src/main/java/frc/robot/subsystems/ElevatorSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -26,9 +26,8 @@ public class ElevatorSubsystem extends SubsystemBase {
private TalonFX wristMotor;
private double currentHeight;
private double targetHeight;
private double desiredAngle;
// FIXME change "desiredAngle" to "targetAngle" - keep naming consistent!
// FIXME also add a currentAngle variable
private double currentAngle;
private double targetAngle;

private PIDController heightController;
private PIDController wristController;
Expand Down Expand Up @@ -58,7 +57,8 @@ public ElevatorSubsystem() {

currentHeight = 0.0;
targetHeight = 0.0;
desiredAngle = 0.0;
currentAngle = 0.0;
targetAngle = 0.0;

right_motor.configFactoryDefault();
left_motor.configFactoryDefault();
Expand Down Expand Up @@ -91,31 +91,21 @@ public static double ticksToHeight(double ticks) {

// FIXME getCurrentTicks is for the elevator, not the wrist
private double getCurrentTicks() {
return wristMotor.getSelectedSensorPosition();
return rightMotor.getSelectedSensorPosition();
}

// FIXME you can just use the cancoder for this, that's what it's for
public double getCurrentAngleDegrees() {
return getCurrentRotation() * Elevator.WRIST_DEGREES;
}

// FIXME unnecessary once you fix getCurrentAngle method
public double getCurrentRotation() {
return (getCurrentTicks() / Elevator.WRIST_TICKS) * Elevator.WRIST_GEAR_RATIO;
}

// FIXME unnecessary once you fix getCurrentAngle method
public static double ticksToAngleDegree(double ticks) {
return (ticks / Elevator.WRIST_TICKS) * Elevator.WRIST_GEAR_RATIO * Elevator.WRIST_DEGREES;
return canCoder.getAbsolutePosition();
}

public void setTargetHeight(double targetHeight) {
this.targetHeight = targetHeight;
}

// FIXME rename with consistent naming
public void setDesiredAngle(double desiredAngle) {
this.desiredAngle = desiredAngle;
public void setTargetAngle(double targetAngle) {
this.targetAngle = targetAngle;
}

public double getTargetHeight() {
Expand All @@ -131,13 +121,14 @@ public double getHeight() {
@Override
public void periodic() {
currentHeight = getHeight();
currentAngle = getCurrentAngleDegrees();
// FIXME update the current angle using the cancoder
double motorPower = heightController.calculate(currentHeight, targetHeight);
right_motor.set(TalonFXControlMode.PercentOutput, motorPower);
wristMotor.set(
TalonFXControlMode.PercentOutput,
MathUtil.clamp(
wristController.calculate(canCoder.getAbsolutePosition(), desiredAngle), -0.25, 0.25));
wristController.calculate(currentAngle, targetAngle), -0.25, 0.25));
// FIXME replace all uses of "canCOder.getAbsolutePosition()" with currentAngle (variable)
}
}

0 comments on commit d88b586

Please sign in to comment.