Skip to content

Commit

Permalink
2024-11-23 autonomous herding
Browse files Browse the repository at this point in the history
  • Loading branch information
OviedoRobotics committed Nov 23, 2024
1 parent 813c3ba commit 5faec3c
Show file tree
Hide file tree
Showing 25 changed files with 63 additions and 6,321 deletions.

This file was deleted.

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -11,24 +11,15 @@
import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.util.ElapsedTime;
import com.qualcomm.robotcore.util.Range;
import com.qualcomm.robotcore.util.ReadWriteFile;

import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.ExposureControl;
import org.firstinspires.ftc.robotcore.external.hardware.camera.controls.GainControl;
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
import org.firstinspires.ftc.robotcore.external.navigation.Pose2D;
import org.firstinspires.ftc.robotcore.internal.system.AppUtil;
import org.firstinspires.ftc.vision.VisionPortal;
import org.firstinspires.ftc.vision.apriltag.AprilTagDetection;
import org.firstinspires.ftc.vision.apriltag.AprilTagProcessor;

import java.io.File;
import java.text.SimpleDateFormat;
import java.util.Date;
import java.util.List;
import java.util.Locale;
import java.util.concurrent.TimeUnit;

public abstract class AutonomousBase extends LinearOpMode {
/* Declare OpMode members. */
Expand Down Expand Up @@ -101,10 +92,11 @@ public abstract class AutonomousBase extends LinearOpMode {
int startDelaySec = 0; // 1: wait [seconds] at startup -- applies to both left/rigth starting positions
int parkDelaySec = 0; // 2: wait [seconds] before parking in observation zone -- applies to that parking zone

boolean audienceYellow = false; // 3: score yellow pixel on audience side (true=yes; false=just park?)
boolean yellowOnLeft = true; // 4: drop yellow pixel in backdrop on left? (true=LEFT; false=RIGHT)
boolean scorePreloadSpecimen = true; // 3: score preloaded specimen (true=yes; false=no)
boolean onlyPark = false; // 4: only park no scoring (true=yes; false=no)

int parkLocation = 0; // 5: park 0=NONE, 1=LEFT, 2=RIGHT
int spikeSamples = 3;
final int PARK_NONE = 0;
final int PARK_LEFT = 1;
final int PARK_RIGHT = 2;
Expand Down Expand Up @@ -234,14 +226,14 @@ else if( gamepad1_cross_now && !gamepad1_cross_last ) {
}
} // prev
break;
case 3 : // SCORE YELLOW PIXEL FROM AUDIENCE SIDE?
case 3 : // SCORE PRELOADED SPECIMEN?
if( nextValue || prevValue) {
audienceYellow = !audienceYellow;
scorePreloadSpecimen = !scorePreloadSpecimen;
} // next
break;
case 4 : // WHERE ON BACKDROP DO WE PLACE THE YELLOW PIXEL? (LEFT/RIGHT)
case 4 : // immediately park
if( nextValue || prevValue) {
yellowOnLeft = !yellowOnLeft;
onlyPark = !onlyPark;
} // next
break;

Expand All @@ -261,15 +253,15 @@ else if( gamepad1_cross_now && !gamepad1_cross_last ) {

case 6 : // HOW MANY PIXELS DO WE SCORE FROM 5-STACK?
if( nextValue ) {
// if (fiveStackCycles < 1) {
// fiveStackCycles++;
// }
if (spikeSamples < 3) {
spikeSamples++;
}
} // next

if( prevValue ) {
// if (fiveStackCycles > 0) {
// fiveStackCycles--;
// }
if (spikeSamples > 0) {
spikeSamples--;
}
} // prev
break;
default : // recover from bad state
Expand All @@ -280,10 +272,11 @@ else if( gamepad1_cross_now && !gamepad1_cross_last ) {
// Update our telemetry
telemetry.addData("Start Delay", "%d sec %s", startDelaySec, ((initMenuSelected==1)? "<-":" ") );
telemetry.addData("Park Delay", "%d sec %s", parkDelaySec, ((initMenuSelected==2)? "<-":" ") );
telemetry.addData("Specimen Preload", "%s %s",((scorePreloadSpecimen)? "yes":"no"), ((initMenuSelected==3)? "<-":" ") );
telemetry.addData("Only Park", "%s %s",((onlyPark)? "yes":"no"), ((initMenuSelected==4)? "<-":" ") );
telemetry.addData("Park Location","%s %s", parkLocationStr[parkLocation],
((initMenuSelected==5)? "<-":" "));

// telemetry.addData("5-stack cycles", "%d cycles %s",fiveStackCycles,((initMenuSelected==6)? "<-":" ") );
telemetry.addData("spike specimens", "%d %s",spikeSamples,((initMenuSelected==6)? "<-":" ") );
telemetry.addData(">","version 100" );
telemetry.update();
} // processAutonomousInitMenu
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -284,19 +284,20 @@ private void level1Ascent() {
// Back up from submersible
driveToPosition( 32.0, 6.0, 90.0, DRIVE_SPEED_50, TURN_SPEED_50, DRIVE_TO );
// Drive forward toward the wall
driveToPosition( 34.0, -27.0, 90.0, DRIVE_SPEED_50, TURN_SPEED_30, DRIVE_TO );
driveToPosition( 38.0, -27.0, 90.0, DRIVE_SPEED_50, TURN_SPEED_30, DRIVE_TO );
} // opModeIsActive

if( opModeIsActive() ) {
// Strafe towards submersible
driveToPosition( 64.0, -27.0, 90.0, DRIVE_SPEED_70, TURN_SPEED_50, DRIVE_TO );
// Drive backward
driveToPosition( 64.0, -12.0, 90.0, DRIVE_SPEED_20, TURN_SPEED_20, DRIVE_TO );
driveToPosition( 64.0, -15.0, 90.0, DRIVE_SPEED_20, TURN_SPEED_20, DRIVE_TO );
} // opModeIsActive

if( opModeIsActive() ) {
autoViperMotorMoveToTarget( robot.VIPER_EXTEND_GRAB);
autoTiltMotorMoveToTarget( robot.TILT_ANGLE_BASKET);
timeDriveStraight(-DRIVE_SPEED_20,3000);
do {
if( !opModeIsActive() ) break;
// wait for lift/tilt to finish...
Expand Down
Loading

0 comments on commit 5faec3c

Please sign in to comment.