Commit "working" code?
This commit is contained in:
@ -113,6 +113,14 @@ public class DevTeleop extends OpMode {
|
||||
wrist.bucketWrist();
|
||||
}
|
||||
}
|
||||
|
||||
public void theTravel(LiftSubsystem lift, ArmSubsystem arm, WristSubsystem wrist){
|
||||
if (currentGamepad2.dpad_down && !previousGamepad2.dpad_down){
|
||||
lift.toFloor();
|
||||
arm.bucketArm();
|
||||
wrist.floorWrist();
|
||||
}
|
||||
}
|
||||
@Override
|
||||
public void loop() {
|
||||
previousGamepad1.copy(currentGamepad1);
|
||||
@ -126,6 +134,7 @@ public class DevTeleop extends OpMode {
|
||||
theLift(arm, wrist);
|
||||
theLowBucketScore(lift, wrist, arm);
|
||||
theHighBucketScore(lift, wrist, arm);
|
||||
theTravel(lift, arm, wrist);
|
||||
|
||||
double max;
|
||||
|
||||
@ -164,6 +173,7 @@ public class DevTeleop extends OpMode {
|
||||
// Show the elapsed game time and wheel power.
|
||||
telemetry.addData("Front left/Right", "%4.2f, %4.2f", leftFrontPower, rightFrontPower);
|
||||
telemetry.addData("Back left/Right", "%4.2f, %4.2f", leftBackPower, rightBackPower);
|
||||
telemetry.addData("Current Lift Position", lift.getPosition());
|
||||
telemetry.update();
|
||||
|
||||
}
|
||||
|
@ -13,8 +13,8 @@ public class RobotConstants {
|
||||
|
||||
public static double wristFloor = 0.625;
|
||||
public static double wristBucket = 0.215;
|
||||
public static int liftToFloorPos = 0;
|
||||
public static int liftToPoolPos = 500;
|
||||
public static int liftToFloorPos = 20;
|
||||
public static int liftToFloatPos = 150;
|
||||
public static int liftToLowBucketPos = 2250;
|
||||
public static int liftToHighBucketPos = 3850;
|
||||
public static double liftPower = .45;
|
||||
|
@ -1,9 +1,10 @@
|
||||
package org.firstinspires.ftc.teamcode.subsystem;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftPower;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToFloatPos;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToFloorPos;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToHighBucketPos;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToLowBucketPos;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToPoolPos;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
@ -17,7 +18,7 @@ public class LiftSubsystem {
|
||||
public RunAction toFloor, toLowBucket, toHighBucket;
|
||||
|
||||
public enum LiftState {
|
||||
FLOOR, LOW_BUCKET, HIGH_BUCKET, POOL
|
||||
FLOOR, LOW_BUCKET, HIGH_BUCKET, FLOAT
|
||||
}
|
||||
|
||||
private LiftState liftState;
|
||||
@ -36,8 +37,8 @@ public class LiftSubsystem {
|
||||
|
||||
public void switchState() {
|
||||
if (this.liftState == LiftState.FLOOR) {
|
||||
this.toPool();
|
||||
} else if (this.liftState == LiftState.POOL) {
|
||||
this.toFloor();
|
||||
} else if (this.liftState == LiftState.FLOAT) {
|
||||
this.toLowBucket();
|
||||
} else if (this.liftState == LiftState.LOW_BUCKET) {
|
||||
this.toHighBucket();
|
||||
@ -47,13 +48,13 @@ public class LiftSubsystem {
|
||||
}
|
||||
|
||||
public void toFloor() {
|
||||
this.setTarget(liftToPoolPos);
|
||||
this.setTarget(liftToFloorPos);
|
||||
this.setState(LiftState.FLOOR);
|
||||
}
|
||||
|
||||
public void toPool() {
|
||||
this.setTarget(liftToPoolPos);
|
||||
this.setState(LiftState.POOL);
|
||||
public void toFloat() {
|
||||
this.setTarget(liftToFloatPos);
|
||||
this.setState(LiftState.FLOAT);
|
||||
}
|
||||
|
||||
public void toLowBucket() {
|
||||
|
Reference in New Issue
Block a user