Skip to content

Commit

Permalink
Updated Lifter for new intake
Browse files Browse the repository at this point in the history
  • Loading branch information
wolfowlshield committed Jan 26, 2022
1 parent 6c92b0a commit ca5dd87
Show file tree
Hide file tree
Showing 9 changed files with 22 additions and 19 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ public void runOpMode() throws InterruptedException {

while (!isStopRequested()) {
if (gamepad1.x) {
lifter.barf();
lifter.barf(1);
}

if (gamepad1.y) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -72,7 +72,7 @@ public void runOpMode() throws InterruptedException {
.build());
sleep(1000);

lifter.barf();
lifter.barf(0.8);
sleep(500);

drive.followTrajectory(drive.trajectoryBuilder(drive.getPoseEstimate())
Expand All @@ -85,7 +85,7 @@ public void runOpMode() throws InterruptedException {
drive.followTrajectory(drive.trajectoryBuilder(drive.getPoseEstimate())
.lineToLinearHeading(new Pose2d(0, -25, Math.toRadians(90)))
.build());
carousel.setDirection(DcMotorSimple.Direction.REVERSE);
carousel.setDirection(DcMotorSimple.Direction.FORWARD);
carousel.PowerOn();
sleep(4200);
carousel.PowerOff();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ public void runOpMode() throws InterruptedException {
duckSecond = vision.ducktective();
}

sleep(8000);
// sleep(8000);

drive.followTrajectory(drive.trajectoryBuilder(drive.getPoseEstimate())
.lineToLinearHeading(new Pose2d(23, -30, 0))
Expand All @@ -73,7 +73,7 @@ public void runOpMode() throws InterruptedException {
.build());
sleep(1000);

lifter.barf();
lifter.barf(0.8);
sleep(500);

drive.followTrajectory(drive.trajectoryBuilder(drive.getPoseEstimate())
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -94,8 +94,7 @@ public void runOpMode() throws InterruptedException {
.build());
sleep(1000);

lifter.barf();
lifter.barf();
lifter.barf(1);
sleep(500);

drive.followTrajectory(drive.trajectoryBuilder(drive.getPoseEstimate())
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import com.acmerobotics.roadrunner.trajectory.Trajectory;
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
import com.qualcomm.robotcore.hardware.DcMotorSimple;

import org.firstinspires.ftc.teamcode.drive.BaseBotMecanumDrive;
import org.firstinspires.ftc.teamcode.drive.DriveFactory;
Expand Down Expand Up @@ -71,7 +72,7 @@ public void runOpMode() throws InterruptedException {
.build());
sleep(1000);

lifter.barf();
lifter.barf(0.8);
sleep(500);

drive.followTrajectory(drive.trajectoryBuilder(drive.getPoseEstimate())
Expand All @@ -84,6 +85,7 @@ public void runOpMode() throws InterruptedException {
drive.followTrajectory(drive.trajectoryBuilder(drive.getPoseEstimate())
.lineToLinearHeading(new Pose2d(0, 17, -Math.toRadians(90)))
.build());
carousel.setDirection(DcMotorSimple.Direction.REVERSE);
carousel.PowerOn();
sleep(4200);
carousel.PowerOff();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,7 @@ public void runOpMode() throws InterruptedException {
duckSecond = vision.ducktective();
}

sleep(8000);
// sleep(8000);
drive.followTrajectory(drive.trajectoryBuilder(drive.getPoseEstimate())
.lineToLinearHeading(new Pose2d(21.5, 23, 0))
.build());
Expand All @@ -72,7 +72,7 @@ public void runOpMode() throws InterruptedException {
.build());
sleep(1000);

lifter.barf();
lifter.barf(0.8);
sleep(500);

drive.followTrajectory(drive.trajectoryBuilder(drive.getPoseEstimate())
Expand All @@ -89,10 +89,12 @@ public void runOpMode() throws InterruptedException {
drive.followTrajectory(drive.trajectoryBuilder(drive.getPoseEstimate())
.lineToLinearHeading(new Pose2d(-1, -30, -Math.toRadians(90)))
.build());
drive.followTrajectory(drive.trajectoryBuilder(drive.getPoseEstimate())
/* drive.followTrajectory(drive.trajectoryBuilder(drive.getPoseEstimate())
.lineToLinearHeading(new Pose2d(27, -30, -Math.toRadians(90)))
.build());
*/

vision.shutdown();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,9 @@ public void runOpMode() throws InterruptedException {
if (gamepad2.left_trigger > 0.1) {
lifter.eat();
} else if (gamepad2.right_trigger > 0.1) {
lifter.barf();
lifter.barf(1);
} else if (gamepad2.right_bumper) {
lifter.barf(0.5);
} else {
lifter.intakeStop();
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,6 +5,7 @@
//import com.qualcomm.robotcore.hardware.DcMotorControllerEx;
//import com.qualcomm.robotcore.hardware.DcMotorSimple;
//import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;
import com.qualcomm.robotcore.hardware.Servo;

Expand Down Expand Up @@ -37,13 +38,13 @@ public Lifter(HardwareMap hardwareMap) {


intakeMotor = hardwareMap.get(DcMotor.class, "intakeMotor");
intakeMotor.setDirection(DcMotor.Direction.FORWARD);
intakeMotor.setDirection(DcMotor.Direction.REVERSE);
intakeMotor.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);

}

public void barf() {
intakeMotor.setPower(-1);
public void barf(double power) {
intakeMotor.setPower(-power);
}

public void intakeStop() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -90,11 +90,8 @@ public void init() {
@SuppressLint("DefaultLocale")
public boolean ducktective() {
FtcDashboard dashboard = FtcDashboard.getInstance();
// dashboard.setTelemetryTransmissionInterval(25);


boolean duckDetected = false;

long DETECTION_TIME = 1000; // How long we give it to determine whether or not there is a duck
long startTimeMillis = System.currentTimeMillis();
long deadline = startTimeMillis + DETECTION_TIME;
Expand Down Expand Up @@ -166,7 +163,7 @@ private void initTfod(HardwareMap hardwareMap, int viewId) {
Log.d("packageName: ", packageName);

TFObjectDetector.Parameters tfodParameters = new TFObjectDetector.Parameters(viewId);
tfodParameters.minResultConfidence = 0.8f; // It was already set to 0.4f when we instantiated it. Why are we increasing it?
tfodParameters.minResultConfidence = 0.75f; // It was already set to 0.4f when we instantiated it. Why are we increasing it?
// Are we not satisfied with 40% confidence?
tfodParameters.isModelTensorFlow2 = true;
tfodParameters.inputSize = 320;
Expand Down

0 comments on commit ca5dd87

Please sign in to comment.