2+4 auto (187->180)
This commit is contained in:
parent
0590708cd0
commit
3e623df8aa
|
@ -114,7 +114,7 @@ public class Robot {
|
|||
}
|
||||
|
||||
public String getTelemetry() {
|
||||
return String.format("Arm:\n------------\n%s\nSlides:\n------------\n%s", arm.getTelemetry(), slides.getTelemetry());
|
||||
return String.format("Arm:\n------------\n%s\nSlides:\n------------\n%s\nIMU:\n------------\n%s" , arm.getTelemetry(), slides.getTelemetry(), drive.getExternalHeadingVelocity());
|
||||
}
|
||||
|
||||
public TrajectorySequenceBuilder getTrajectorySequenceBuilder() {
|
||||
|
|
|
@ -25,7 +25,7 @@ public class Slides {
|
|||
public static int targetMax = 830;
|
||||
|
||||
public static int down = 0;
|
||||
public static int mini_tier1 = 190;
|
||||
public static int mini_tier1 = 205;
|
||||
public static int tier1 = 350;
|
||||
public static int tier2 = 500;
|
||||
public static int tier3 = 720;
|
||||
|
|
|
@ -9,8 +9,8 @@ public class endGame_Mechs {
|
|||
private Servo servo;
|
||||
private Servo hang1;
|
||||
private Servo hang2;
|
||||
public static double initPos = 0.4;
|
||||
public static double launchPos = 0.8;
|
||||
public static double initPos = 0.8;
|
||||
public static double launchPos = 0.4;
|
||||
public static double hold = 0.8;
|
||||
public static double release = 0.5;
|
||||
public static double hold2 = 0.8;
|
||||
|
|
|
@ -18,14 +18,14 @@ import org.firstinspires.ftc.teamcode.util.CenterStageCommon;
|
|||
@Autonomous(name = "Blue Backstage Auto(2+4)", group = "Competition", preselectTeleOp = "Main TeleOp")
|
||||
public class BlueBackStageAuto extends AutoBase {
|
||||
public static final Pose2d DROP_3 = new Pose2d(16, 32, Math.toRadians(-180));
|
||||
public static final Pose2d DROP_2 = new Pose2d(13.7, 35, Math.toRadians(-90));
|
||||
public static final Pose2d DROP_2 = new Pose2d(14, 35, Math.toRadians(-90));
|
||||
|
||||
public static final Pose2d ALINE = new Pose2d(51,35, Math.toRadians(-180));
|
||||
|
||||
public static final Pose2d DROP_1 = new Pose2d(25, 41.6, Math.toRadians(-90));
|
||||
public static final Pose2d DROP_1 = new Pose2d(25, 43, Math.toRadians(-90));
|
||||
public static final Pose2d DEPOSIT_PRELOAD_3 = new Pose2d(54.8, 27.5, Math.toRadians(-180));
|
||||
public static final Pose2d DEPOSIT_PRELOAD_2 = new Pose2d(54, 32.5, Math.toRadians(-180));
|
||||
public static final Pose2d DEPOSIT_PRELOAD_1 = new Pose2d(53.3, 39.5, Math.toRadians(-180));
|
||||
public static final Pose2d DEPOSIT_PRELOAD_2 = new Pose2d(52, 32.5, Math.toRadians(-180));
|
||||
public static final Pose2d DEPOSIT_PRELOAD_1 = new Pose2d(52.2, 39.3, Math.toRadians(-180));
|
||||
|
||||
public static final Pose2d DEPOSIT_WHITE_STACKS_3 = new Pose2d(53.4, 35.6, Math.toRadians(-187));
|
||||
|
||||
|
@ -35,9 +35,9 @@ public class BlueBackStageAuto extends AutoBase {
|
|||
|
||||
|
||||
//public static final Vector2d POST_SCORING_SPLINE_END = new Vector2d(24, -8.5);//-36
|
||||
public static final Pose2d POST_SCORING_SPLINE_END = new Pose2d(24, 11.6, Math.toRadians(-180));//-36
|
||||
public static final Pose2d POST_SCORING_SPLINE_END = new Pose2d(26, 11.8, Math.toRadians(-180));//-36
|
||||
|
||||
public static final Pose2d STACK_LOCATION = new Pose2d(-55.5, 11.6, Math.toRadians(-180));
|
||||
public static final Pose2d STACK_LOCATION = new Pose2d(-54.7, 11.8, Math.toRadians(-180));
|
||||
|
||||
@Override
|
||||
public void createTrajectories() {
|
||||
|
|
|
@ -22,22 +22,22 @@ public class RedBackStageAuto extends AutoBase {
|
|||
|
||||
public static final Pose2d ALINE = new Pose2d(51,-32.5, Math.toRadians(180));
|
||||
|
||||
public static final Pose2d DROP_3 = new Pose2d(25, -41.3, Math.toRadians(90));
|
||||
public static final Pose2d DROP_3 = new Pose2d(25, -45.5, Math.toRadians(90));
|
||||
public static final Pose2d DEPOSIT_PRELOAD_1 = new Pose2d(52, -27.5, Math.toRadians(180));
|
||||
public static final Pose2d DEPOSIT_PRELOAD_2 = new Pose2d(52, -32.5, Math.toRadians(180));
|
||||
public static final Pose2d DEPOSIT_PRELOAD_2 = new Pose2d(53.5, -32.5, Math.toRadians(180));
|
||||
public static final Pose2d DEPOSIT_PRELOAD_3 = new Pose2d(51.3, -39.5, Math.toRadians(180));
|
||||
|
||||
public static final Pose2d DEPOSIT_WHITE_STACKS_1 = new Pose2d(50.3, -35.3, Math.toRadians(187));
|
||||
public static final Pose2d DEPOSIT_WHITE_STACKS_1 = new Pose2d(50.3, -35.3, Math.toRadians(180));//187
|
||||
|
||||
public static final Pose2d DEPOSIT_WHITE_STACKS_2 = new Pose2d(52, -29, Math.toRadians(187));
|
||||
public static final Pose2d DEPOSIT_WHITE_STACKS_2 = new Pose2d(52, -29, Math.toRadians(180));//187
|
||||
|
||||
public static final Pose2d DEPOSIT_WHITE_STACKS_3 = new Pose2d(50.6, -32, Math.toRadians(187));
|
||||
public static final Pose2d DEPOSIT_WHITE_STACKS_3 = new Pose2d(50.6, -32, Math.toRadians(180));//817
|
||||
|
||||
|
||||
//public static final Vector2d POST_SCORING_SPLINE_END = new Vector2d(24, -8.5);//-36
|
||||
public static final Pose2d POST_SCORING_SPLINE_END = new Pose2d(24, -10.6, Math.toRadians(180));//-36
|
||||
public static final Pose2d POST_SCORING_SPLINE_END = new Pose2d(24, -12.5, Math.toRadians(180));//-36
|
||||
|
||||
public static final Pose2d STACK_LOCATION = new Pose2d(-57.4, -10.6, Math.toRadians(180));
|
||||
public static final Pose2d STACK_LOCATION = new Pose2d(-56.8, -12.5, Math.toRadians(180));
|
||||
|
||||
@Override
|
||||
public void createTrajectories() {
|
||||
|
|
|
@ -17,9 +17,9 @@ import org.firstinspires.ftc.teamcode.hardware.Slides;
|
|||
@TeleOp(name = "Main TeleOp", group = "OpModes")
|
||||
public class MainTeleOp extends OpMode {
|
||||
|
||||
public static double normal = 0.5;
|
||||
public static double normal = 0.7;
|
||||
public static double turbo = 1;
|
||||
public static double slow_mode = 0.15;
|
||||
public static double slow_mode = 0.35;
|
||||
public static double intakeMax = 0.5;
|
||||
public static double intakeMax2 = -0.65;
|
||||
|
||||
|
@ -102,14 +102,14 @@ public class MainTeleOp extends OpMode {
|
|||
// macros
|
||||
switch (robot.runningMacro) {
|
||||
case (0): // manual mode
|
||||
if (controller2.getLeftBumper().isPressed()){
|
||||
robot.arm.setDoor(Arm.DoorPosition.OPEN);
|
||||
}
|
||||
|
||||
robot.slides.increaseTarget(controller2.getLeftStick().getY());
|
||||
if (robot.intake.getPower() >= 0.01) {
|
||||
robot.arm.setDoor(OPEN);
|
||||
} else if (robot.intake.getPower() <= -0.01) {
|
||||
robot.arm.setDoor(OPEN);
|
||||
} else if (controller2.getLeftBumper().isPressed()) {
|
||||
robot.arm.setDoor(Arm.DoorPosition.OPEN);
|
||||
} else {
|
||||
robot.arm.setDoor(CLOSE);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue