Skip to content

Commit

Permalink
added increment in a couple places, refactored names to match
Browse files Browse the repository at this point in the history
  • Loading branch information
braelynandthefrogs authored and jachninja committed Oct 26, 2024
1 parent d360331 commit ba48226
Show file tree
Hide file tree
Showing 2 changed files with 22 additions and 16 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -24,9 +24,9 @@ public class HorizontalSlidesSubsystem implements Subsystem, Loggable {
public static double LinkServoRetract = 0;
public static double ClawServoClose = 0.55;
public static double ClawServoOpen = 0;
public static double ClawWristServoTransfer = 0.545;
public static double ClawWristServoPickup = 0.05;
public static double ClawWristServoIncrement = 0.555;
public static double WristServoTransfer = 0.545;
public static double WristServoPickup = 0.05;
public static double WristServoIncrement = 0.555;

@Log(name = "wristTarget")
public double wristTargetPos;
Expand All @@ -38,7 +38,7 @@ public class HorizontalSlidesSubsystem implements Subsystem, Loggable {
private boolean isHardware;

public HorizontalSlidesSubsystem(Hardware hw) {
clawwristServo = hw.wristservo;
wristServo = hw.wristservo;
clawServo = hw.clawservo;
linkServo = hw.linkservo;

Expand All @@ -51,7 +51,7 @@ public HorizontalSlidesSubsystem(Hardware hw) {
public HorizontalSlidesSubsystem() {
isHardware = false;
linkServo = null;
clawwristServo = null;
wristServo = null;
clawServo = null;
}

Expand All @@ -74,12 +74,12 @@ public void ClawServoBigOpen() {
}

public void ClawWristServoPickup() {
clawwristServo.setPosition(ClawWristServoPickup); //lowers claw to intake
wristServo.setPosition(WristServoPickup); //lowers claw to intake
}

public void ClawWristServoTransfer() {
// positions for the arm of the bot for transfer
clawwristServo.setPosition(ClawWristServoTransfer);
wristServo.setPosition(WristServoTransfer);
}

public void ClawWristServoIncrement() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ public class VerticalSlidesSubsystem implements Subsystem, Loggable {
public static double LOW_BUCKET = -950;
public static double HIGH_BUCKET = -1350;
// public static double HIGH_POS = 1000;
public static double WRIST_POS = 0;
public static double SLIDE_POS = 0;
public static double ARM_POS = 0;
public static double MIN_MOTOR_SPEED = -0.7;
public static double MAX_MOTOR_SPEED = 1;
Expand All @@ -48,11 +48,11 @@ public class VerticalSlidesSubsystem implements Subsystem, Loggable {
@Log(name = "slideTarget")
public int slideTargetPos;

@Log(name = "wristPos")
public double wristPos;

@Log(name = "wristTarget")
public double wristTargetPos;
@Log(name = "armTarget")
public double armTargetPos;
@Log(name = "bucketTarget")
public double bucketTargetPos;

public static PIDCoefficients PID = new PIDCoefficients(0.0, 0.0, 0.0);
public Servo armServo;
Expand Down Expand Up @@ -98,10 +98,10 @@ private void setSlidePos(int e) {
slideTargetPos = e;
}

private void setWristPos(double w) {
private void setArmPos(double w) {
if (armServo != null) {
armServo.setPosition(w);
wristTargetPos = w;
armTargetPos = w;
}
}

Expand Down Expand Up @@ -160,7 +160,7 @@ public void SlideChamberHigh() {

public void LiftHeightIntake() {
//brings the arm all the way down
slidePidController.setTargetPosition(WRIST_POS);
slidePidController.setTargetPosition(SLIDE_POS);
// armServo.setPosition(0);
// scoreServo.setPosition(0);
}
Expand All @@ -171,7 +171,7 @@ private void setSlideMotorPower(double speed) {
}
}

public void BucketWristServoIncrement() {
public void BucketServoIncrement() {
// the arm's position to score
armServo.setPosition(WristServoIncrement);
}
Expand Down Expand Up @@ -203,4 +203,10 @@ public void ArmServoHighBucket() {
// positions for the arm of the bot
armServo.setPosition(ArmServoInput);
}
private void setBucketPos(double w) {
if (bucketServo != null) {
bucketServo.setPosition(w);
bucketTargetPos = w;
}
}
}

0 comments on commit ba48226

Please sign in to comment.