Hang Successful
This commit is contained in:
@ -1,5 +1,6 @@
|
|||||||
package org.firstinspires.ftc.teamcode.cometbots;
|
package org.firstinspires.ftc.teamcode.cometbots;
|
||||||
|
|
||||||
|
import static org.firstinspires.ftc.teamcode.PedroConstants.FRONT_LEFT_MOTOR;
|
||||||
import static org.firstinspires.ftc.teamcode.PedroConstants.MAX_POWER;
|
import static org.firstinspires.ftc.teamcode.PedroConstants.MAX_POWER;
|
||||||
|
|
||||||
import com.qualcomm.robotcore.hardware.Gamepad;
|
import com.qualcomm.robotcore.hardware.Gamepad;
|
||||||
@ -105,18 +106,14 @@ public class CometBotTeleOpDevelopment {
|
|||||||
private void armAndWristToFloor() {
|
private void armAndWristToFloor() {
|
||||||
if (currentGamepad2.a && !previousGamepad2.a) {
|
if (currentGamepad2.a && !previousGamepad2.a) {
|
||||||
arm.toFloorPositionTeleOp();
|
arm.toFloorPositionTeleOp();
|
||||||
if (wrist.getState() != WristSubsystem.WristState.FLOOR) {
|
if (arm.getState() == ArmSubsystem.ArmState.FLOOR) {
|
||||||
wrist.toFloorPositionTeleop();
|
wrist.switchState();
|
||||||
} else {
|
} else if (arm.getState() != ArmSubsystem.ArmState.FLOOR) {
|
||||||
wrist.toPickupPosition();
|
wrist.toPickupPosition();
|
||||||
|
} else {
|
||||||
|
wrist.toFloorPosition();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (currentGamepad2.a && !previousGamepad2.a) {
|
|
||||||
wrist.switchState();
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
private void armToBucketPosition() {
|
private void armToBucketPosition() {
|
||||||
@ -130,7 +127,7 @@ public class CometBotTeleOpDevelopment {
|
|||||||
private void armToParkPosition() {
|
private void armToParkPosition() {
|
||||||
if (currentGamepad2.x && !previousGamepad2.x) {
|
if (currentGamepad2.x && !previousGamepad2.x) {
|
||||||
arm.toParkPosition();
|
arm.toParkPosition();
|
||||||
wrist.toFloorPositionTeleop();
|
wrist.toFloorPosition();
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -19,7 +19,7 @@ public class DualMotorSliderTest extends LinearOpMode {
|
|||||||
|
|
||||||
private DcMotorEx liftSlideLeft;
|
private DcMotorEx liftSlideLeft;
|
||||||
private DcMotorEx liftSlideRight;
|
private DcMotorEx liftSlideRight;
|
||||||
public static double kp = 0.0015, ki = 0, kd = 0;
|
public static double kp = 0.002, ki = 0, kd = 0;
|
||||||
private double lastError = 0;
|
private double lastError = 0;
|
||||||
private double integralSum = 0;
|
private double integralSum = 0;
|
||||||
public static int targetPosition = 0;
|
public static int targetPosition = 0;
|
||||||
|
@ -27,7 +27,7 @@ public class RobotConstants {
|
|||||||
public final static double armSpecimen = 0.155;
|
public final static double armSpecimen = 0.155;
|
||||||
public final static double armInit = 0.13;
|
public final static double armInit = 0.13;
|
||||||
public final static double wristInit = 0.125;
|
public final static double wristInit = 0.125;
|
||||||
public final static double wristPickup = 0.475;
|
public final static double wristPickup = 0.425;
|
||||||
public final static double wristBucket = 0.56;
|
public final static double wristBucket = 0.56;
|
||||||
public final static double wristSpecimenPrep = 0.63;
|
public final static double wristSpecimenPrep = 0.63;
|
||||||
public final static double wristSpecimenHang = 0.53;
|
public final static double wristSpecimenHang = 0.53;
|
||||||
|
@ -56,7 +56,7 @@ public class DualMotorSliderSubsystem {
|
|||||||
It's the only value we set because the variable ki and kd deal with how to handle when we're off the path.
|
It's the only value we set because the variable ki and kd deal with how to handle when we're off the path.
|
||||||
Since we're going straight, we don't need to worry about.
|
Since we're going straight, we don't need to worry about.
|
||||||
*/
|
*/
|
||||||
public final static double kp = 0.0015, ki = 0, kd = 0;
|
public final static double kp = 0.002, ki = 0, kd = 0;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
lastError/integralSum/timer - These 3 variables are placeholders in determining how much
|
lastError/integralSum/timer - These 3 variables are placeholders in determining how much
|
||||||
|
Reference in New Issue
Block a user