Fixes
This commit is contained in:
parent
79d5fd24eb
commit
d489794dc7
|
@ -1,7 +1,7 @@
|
|||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<project version="4">
|
||||
<component name="ExternalStorageConfigurationManager" enabled="true" />
|
||||
<component name="ProjectRootManager" version="2" languageLevel="JDK_17_PREVIEW" project-jdk-name="Embedded JDK" project-jdk-type="JavaSDK">
|
||||
<component name="ProjectRootManager" version="2" languageLevel="JDK_17" project-jdk-name="Embedded JDK" project-jdk-type="JavaSDK">
|
||||
<output url="file://$PROJECT_DIR$/build/classes" />
|
||||
</component>
|
||||
<component name="ProjectType">
|
||||
|
|
|
@ -11,7 +11,7 @@ import com.qualcomm.robotcore.hardware.ColorSensor;
|
|||
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
|
||||
|
||||
@Autonomous
|
||||
public class AutoBlueColorSensorBottom extends LinearOpMode {
|
||||
public class AutoBlueColorSensor extends LinearOpMode {
|
||||
SampleMecanumDrive mecanumDrive;
|
||||
|
||||
@Override
|
||||
|
|
|
@ -10,7 +10,7 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|||
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
|
||||
|
||||
@Autonomous
|
||||
public class AutoBlueSubstationParkingBehaviorBottom extends LinearOpMode {
|
||||
public class AutoBlueSubstationParkingBehavior extends LinearOpMode {
|
||||
SampleMecanumDrive mecanumDrive;
|
||||
|
||||
@Override
|
||||
|
@ -20,22 +20,9 @@ public class AutoBlueSubstationParkingBehaviorBottom extends LinearOpMode {
|
|||
|
||||
waitForStart();
|
||||
|
||||
Trajectory firstMove = makeTrajectories(
|
||||
new Pose2d(new Vector2d(-34, 60), 0),
|
||||
new int[]{-34},
|
||||
new int[]{40}
|
||||
);
|
||||
|
||||
mecanumDrive.followTrajectory(firstMove);
|
||||
|
||||
double time = getRuntime() + 5;
|
||||
/* wait for 5 seconds to allow color sensor to settle */
|
||||
while (true) {
|
||||
if (!(getRuntime() < time)) break; // needed to stop android studio from yelling
|
||||
}
|
||||
|
||||
// init move to default terminal
|
||||
Trajectory endpos = makeTrajectories(firstMove.end(),
|
||||
Trajectory endpos = makeTrajectories(
|
||||
new Pose2d(new Vector2d(-34, 60), 0),
|
||||
new int[]{-34, 1},
|
||||
new int[]{60, 60}
|
||||
);
|
||||
|
|
|
@ -10,7 +10,7 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|||
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
|
||||
|
||||
@Autonomous
|
||||
public class AutoBlueTerminalParkingBehaviorBottom extends LinearOpMode {
|
||||
public class AutoBlueTerminalParkingBehavior extends LinearOpMode {
|
||||
SampleMecanumDrive mecanumDrive;
|
||||
|
||||
@Override
|
||||
|
@ -20,22 +20,9 @@ public class AutoBlueTerminalParkingBehaviorBottom extends LinearOpMode {
|
|||
|
||||
waitForStart();
|
||||
|
||||
Trajectory firstMove = makeTrajectories(
|
||||
new Pose2d(new Vector2d(-34, 60), 0),
|
||||
new int[]{-34},
|
||||
new int[]{40}
|
||||
);
|
||||
|
||||
mecanumDrive.followTrajectory(firstMove);
|
||||
|
||||
double time = getRuntime() + 5;
|
||||
/* wait for 5 seconds to allow color sensor to settle */
|
||||
while (true) {
|
||||
if (!(getRuntime() < time)) break; // needed to stop android studio from yelling
|
||||
}
|
||||
|
||||
// init move to default terminal
|
||||
Trajectory endpos = makeTrajectories(firstMove.end(),
|
||||
Trajectory endpos = makeTrajectories(
|
||||
new Pose2d(new Vector2d(-34, 60), 0),
|
||||
new int[]{-34, -70},
|
||||
new int[]{60, 60}
|
||||
);
|
||||
|
|
|
@ -11,7 +11,7 @@ import com.qualcomm.robotcore.hardware.ColorSensor;
|
|||
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
|
||||
|
||||
@Autonomous
|
||||
public class AutoRedColorSensorBottom extends LinearOpMode {
|
||||
public class AutoRedColorSensor extends LinearOpMode {
|
||||
SampleMecanumDrive mecanumDrive;
|
||||
|
||||
@Override
|
||||
|
|
|
@ -10,7 +10,7 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|||
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
|
||||
|
||||
@Autonomous
|
||||
public class AutoRedSubstationParkingBehaviorBottom extends LinearOpMode {
|
||||
public class AutoRedSubstationParkingBehavior extends LinearOpMode {
|
||||
SampleMecanumDrive mecanumDrive;
|
||||
|
||||
@Override
|
||||
|
@ -20,22 +20,9 @@ public class AutoRedSubstationParkingBehaviorBottom extends LinearOpMode {
|
|||
|
||||
waitForStart();
|
||||
|
||||
Trajectory firstMove = makeTrajectories(
|
||||
new Pose2d(new Vector2d(-34, -60), 0),
|
||||
new int[]{-34},
|
||||
new int[]{-40}
|
||||
);
|
||||
|
||||
mecanumDrive.followTrajectory(firstMove);
|
||||
|
||||
double time = getRuntime() + 5;
|
||||
/* wait for 5 seconds to allow color sensor to settle */
|
||||
while (true) {
|
||||
if (!(getRuntime() < time)) break; // needed to stop android studio from yelling
|
||||
}
|
||||
|
||||
// init move to default terminal
|
||||
Trajectory endpos = makeTrajectories(firstMove.end(),
|
||||
Trajectory endpos = makeTrajectories(
|
||||
new Pose2d(new Vector2d(-34, -60), 0),
|
||||
new int[]{-34, 1},
|
||||
new int[]{-60, -60}
|
||||
);
|
||||
|
|
|
@ -10,7 +10,7 @@ import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
|||
import org.firstinspires.ftc.teamcode.drive.SampleMecanumDrive;
|
||||
|
||||
@Autonomous
|
||||
public class AutoRedTerminalParkingBehaviorBottom extends LinearOpMode {
|
||||
public class AutoRedTerminalParkingBehavior extends LinearOpMode {
|
||||
SampleMecanumDrive mecanumDrive;
|
||||
|
||||
@Override
|
||||
|
@ -20,22 +20,9 @@ public class AutoRedTerminalParkingBehaviorBottom extends LinearOpMode {
|
|||
|
||||
waitForStart();
|
||||
|
||||
Trajectory firstMove = makeTrajectories(
|
||||
new Pose2d(new Vector2d(-34, -60), 0),
|
||||
new int[]{-34},
|
||||
new int[]{-40}
|
||||
);
|
||||
|
||||
mecanumDrive.followTrajectory(firstMove);
|
||||
|
||||
double time = getRuntime() + 5;
|
||||
/* wait for 5 seconds to allow color sensor to settle */
|
||||
while (true) {
|
||||
if (!(getRuntime() < time)) break; // needed to stop android studio from yelling
|
||||
}
|
||||
|
||||
// init move to default terminal
|
||||
Trajectory endpos = makeTrajectories(firstMove.end(),
|
||||
Trajectory endpos = makeTrajectories(
|
||||
new Pose2d(new Vector2d(-34, -60), 0),
|
||||
new int[]{-34, -70},
|
||||
new int[]{-60, -60}
|
||||
);
|
||||
|
|
Loading…
Reference in a new issue