4 Commits

Author SHA1 Message Date
f9b00bd558 Fine tuning to autonomous prior to switching to new robot 2025-01-20 09:00:55 -08:00
653c81ca7e 3 samples in high bucket
overtime
2025-01-16 16:12:15 -08:00
d41add449c 3 samples in high bucket
overtime
2025-01-16 16:11:19 -08:00
1c90a851e7 3 samples in high bucket
overtime
2025-01-16 15:59:16 -08:00
9 changed files with 173 additions and 32 deletions

View File

@ -1,5 +1,7 @@
package org.firstinspires.ftc.teamcode;
import static com.qualcomm.hardware.lynx.commands.core.LynxSetMotorPIDFControlLoopCoefficientsCommand.InternalMotorControlAlgorithm.Max;
import androidx.annotation.NonNull;
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
@ -18,6 +20,8 @@ import org.firstinspires.ftc.teamcode.subsystem.HighBasketAutoPath1;
import org.firstinspires.ftc.teamcode.subsystem.HighBasketAutoPath2;
import org.firstinspires.ftc.teamcode.subsystem.HighBasketAutoPath3;
import org.firstinspires.ftc.teamcode.subsystem.HighBasketAutoPath4;
import org.firstinspires.ftc.teamcode.subsystem.HighBasketAutoPath5;
import org.firstinspires.ftc.teamcode.subsystem.HighBasketAutoPath6;
import org.firstinspires.ftc.teamcode.subsystem.LiftActionsSubsystem;
import org.firstinspires.ftc.teamcode.subsystem.SkyHookSubsystem;
@ -32,6 +36,8 @@ public class ComeBotDriveDevV2 extends OpMode {
private HighBasketAutoPath3 path3;
private HighBasketAutoPath4 path4;
private HighBasketAutoPath5 path5;
private HighBasketAutoPath6 path6;
private AutoPark pathPark;
private SkyHookSubsystem hook;
@ -48,6 +54,10 @@ public class ComeBotDriveDevV2 extends OpMode {
path1 = new HighBasketAutoPath1();
path2 = new HighBasketAutoPath2();
path3 = new HighBasketAutoPath3();
path4 = new HighBasketAutoPath4();
path5 = new HighBasketAutoPath5();
path6 = new HighBasketAutoPath6();
pathPark = new AutoPark();
comp = new CometBotTeleopCompetition(hardwareMap, telemetry, gamepad1, gamepad2);
@ -83,19 +93,19 @@ public class ComeBotDriveDevV2 extends OpMode {
theArmThing();
break;
case 6:
//moveToPickupAgainPath4();
moveToPickupAgainPath4();
break;
case 7:
//doPickUpThingAgain();
doPickUpThingAgain();
break;
case 8:
//line five
moveToPickupAgainPath5();
break;
case 9:
//theArmThingAgain();
theArmThingAgain();
break;
case 10:
//line six
//moveToParkPath6();
break;
case 11:
@ -140,7 +150,7 @@ public class ComeBotDriveDevV2 extends OpMode {
}
private void doArmThing() {
comp.highBucketDrop();
comp.highBucketDropAuto();
state = 2;
}
@ -149,14 +159,15 @@ public class ComeBotDriveDevV2 extends OpMode {
telemetry.addData("end?", follower.atParametricEnd());
if (follower.atParametricEnd()){
follower.breakFollowing();
comp.highBucketDrop();
comp.highBucketDropAuto();
state = 6;
}
// follower.breakFollowing();
}
private void theArmThingAgain() {
comp.highBucketDrop();
follower.breakFollowing();
comp.highBucketDropAuto();
state = 10;
}
@ -181,13 +192,40 @@ public class ComeBotDriveDevV2 extends OpMode {
}
if (runtime != null) {
telemetry.addData("Runtime (seconds)", runtime.seconds());
if (follower.atParametricEnd() || runtime.seconds() > 12.0) {
if (follower.atParametricEnd() || runtime.seconds() > 27.0) {
state = 7;
followingPath = false;
}
}
}
private void moveToPickupAgainPath5() {
if (!followingPath) {
path5.moveToPickupAgainPath5(follower);
followingPath = true;
}
if (runtime != null) {
telemetry.addData("Runtime (seconds)", runtime.seconds());
if (follower.atParametricEnd() || runtime.seconds() > 36.0) {
state = 9;
followingPath = false;
}
}
}
private void moveToParkPath6() {
if (!followingPath) {
path6.moveToParkPath6(follower);
followingPath = true;
}
if (runtime != null) {
telemetry.addData("Runtime (seconds)", runtime.seconds());
if (follower.atParametricEnd() || runtime.seconds() > 48.0) {
state = 11;
followingPath = false;
}
}
}
private void moveToBasketPath3() {
if (!followingPath) {
path3.moveToBasketPath3(follower);
@ -195,37 +233,55 @@ public class ComeBotDriveDevV2 extends OpMode {
}
if (runtime != null) {
telemetry.addData("Runtime (seconds)", runtime.seconds());
if (follower.atParametricEnd() || runtime.seconds() > 12.0) {
if (follower.atParametricEnd() || runtime.seconds() > 10.0) {
state = 5;
followingPath = false;
}
}
}
private void thePickUp() {
private void thePickUpAuto() {
Actions.runBlocking(new SequentialAction(
new SleepAction(.25),
new SleepAction(.1),
comp.claw.openClaw(),
new SleepAction(.2),
comp.wrist.toPickupPosition(),
new SleepAction(.2),
comp.arm.toSubmarinePosition(),
new SleepAction(.5),
comp.wrist.toPickupPosition(),
new SleepAction(.75),
comp.claw.closeClaw(),
new SleepAction(.75),
new SleepAction(.3),
comp.wrist.toFloorPosition(),
new SleepAction(0.5),
new SleepAction(.2),
comp.arm.toParkPosition(),
new SleepAction(.25)
new SleepAction(.2)
));
}
private void thePickUp() {
Actions.runBlocking(new SequentialAction(
new SleepAction(.5),
comp.wrist.toPickupPosition(),
new SleepAction(.5),
comp.arm.toSubmarinePosition(),
new SleepAction(.7),
comp.claw.closeClaw(),
new SleepAction(.7),
comp.wrist.toFloorPosition(),
new SleepAction(.5),
comp.arm.toParkPosition(),
new SleepAction(.5)
));
}
private void doPickUpThing() {
follower.breakFollowing();
thePickUp();
thePickUpAuto();
state = 4;
}
private void doPickUpThingAgain() {
thePickUp();
follower.breakFollowing();
thePickUpAuto();
state = 8;
}

View File

@ -31,7 +31,7 @@ public class PedroConstants {
/*
Motor Max Power
*/
public static final double MAX_POWER = .675;
public static final double MAX_POWER = .8;
/*
IMU

View File

@ -212,20 +212,20 @@ public class CometBotTeleopCompetition {
}
public void highBucketDropAuto() {
Actions.runBlocking(new SequentialAction(
new SleepAction(.5),
new SleepAction(.1),
this.lift.toHighBucketPosition(),
new SleepAction(.5),
new SleepAction(.25),
this.arm.toBucketPosition(),
new SleepAction(.5),
new SleepAction(.25),
this.wrist.toBucketPosition(),
new SleepAction(.5),
new SleepAction(.25),
this.claw.openClaw(),
new SleepAction(.5),
new SleepAction(.25),
this.wrist.toFloorPosition(),
new SleepAction(.5),
new SleepAction(.25),
this.arm.toParkPosition(),
this.lift.toZeroPosition(),
new SleepAction(.5)
new SleepAction(.25)
));
}
/*

View File

@ -115,11 +115,13 @@ public class LiftWristArmTest extends LinearOpMode {
}
if (currentGamepad1.right_bumper && !previousGamepad1.right_bumper) {
lift.setPosition(lift.getPosition() + 175);
lift.setPosition(lift.getPosition() + 100);
}
if (currentGamepad1.left_bumper && !previousGamepad1.left_bumper) {
lift.setPosition(lift.getPosition() - 25);
if (lift.getPosition() > 1000) {
lift.setPosition(lift.getPosition()-1000);
}
}

View File

@ -24,7 +24,7 @@ public class HighBasketAutoPath2 {
// Line 1
new BezierLine(
new Point(18.000, 126.000, Point.CARTESIAN),
new Point(29.000, 120.000, Point.CARTESIAN)
new Point(25.500, 120.000, Point.CARTESIAN)
)
)
.setLinearHeadingInterpolation(Math.toRadians(135), Math.toRadians(0));

View File

@ -18,7 +18,6 @@ public class HighBasketAutoPath3 {
public void moveToBasketPath3(Follower robot) {
PathChain pathChain;
PathBuilder builder = new PathBuilder();
// robot.setStartingPose( new Pose(29, 120));
builder
.addPath(
// Line 1

View File

@ -22,7 +22,7 @@ public class HighBasketAutoPath4 {
// Line 1
new BezierLine(
new Point(18.000, 126.000, Point.CARTESIAN),
new Point(29.000, 131.400, Point.CARTESIAN)
new Point(25.000, 129.900, Point.CARTESIAN)
)
)
.setLinearHeadingInterpolation(Math.toRadians(135), Math.toRadians(0));

View File

@ -0,0 +1,34 @@
package org.firstinspires.ftc.teamcode.subsystem;
import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierLine;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathBuilder;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathChain;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point;
/*
AutoLine# - This file does something of a path......
*/
public class HighBasketAutoPath5 {
public void moveToPickupAgainPath5(Follower robot) {
PathChain pathChain;
PathBuilder builder = new PathBuilder();
builder
.addPath(
// Line 1
new BezierLine(
new Point(24.000, 131.000, Point.CARTESIAN),
new Point(18.000, 126.000, Point.CARTESIAN)
)
)
.setLinearHeadingInterpolation(Math.toRadians(0), Math.toRadians(135));
pathChain = builder.build();
robot.followPath(pathChain);
}
}

View File

@ -0,0 +1,50 @@
package org.firstinspires.ftc.teamcode.subsystem;
import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierLine;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathBuilder;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathChain;
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point;
/*
AutoLine# - This file does something of a path......
*/
public class HighBasketAutoPath6 {
public void moveToParkPath6(Follower robot) {
PathChain pathChain;
PathBuilder builder = new PathBuilder();
builder
.addPath(
// Line 1
new BezierLine(
new Point(18.000, 126.000, Point.CARTESIAN),
new Point(18.000, 126.000, Point.CARTESIAN)
)
)
.setLinearHeadingInterpolation(Math.toRadians(135), Math.toRadians(270))
.addPath(
// Line 2
new BezierLine(
new Point(18.000, 126.000, Point.CARTESIAN),
new Point(81.000, 125.000, Point.CARTESIAN)
)
)
.setLinearHeadingInterpolation(Math.toRadians(270), Math.toRadians(270))
.addPath(
// Line 3
new BezierLine(
new Point(81.000, 125.000, Point.CARTESIAN),
new Point(81.000, 100.000, Point.CARTESIAN)
)
)
.setLinearHeadingInterpolation(Math.toRadians(270), Math.toRadians(270));
pathChain = builder.build();
robot.followPath(pathChain);
}
}