Compare commits
17 Commits
branch-sil
...
59f06440d3
Author | SHA1 | Date | |
---|---|---|---|
59f06440d3 | |||
939a36e138 | |||
b14e91b094 | |||
70d0a17d75 | |||
2be683701b | |||
52e21fd468 | |||
839837c844 | |||
71b91fa3ff | |||
a08dd82de2 | |||
2cb8ce41dd | |||
93ff65ee53 | |||
e1be70c23f | |||
2a1513a2ba | |||
172c6659dc | |||
4975e0f5ca | |||
1a878eea1c | |||
8c6ce96ae4 |
@ -0,0 +1,115 @@
|
||||
package org.firstinspires.ftc.teamcode;
|
||||
/*
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.acmerobotics.roadrunner.SleepAction;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
||||
import com.qualcomm.robotcore.util.ElapsedTime;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.Telemetry;
|
||||
import org.firstinspires.ftc.teamcode.cometbots.CometBotTeleopCompetition;
|
||||
import org.firstinspires.ftc.teamcode.configs.RobotConstants;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierCurve;
|
||||
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;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.AutoPark;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.HighBasketAutoPath1;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.HighBasketAutoPath2;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.LiftActionsSubsystem;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.SkyHookSubsystem;
|
||||
|
||||
@Autonomous(name = "Auto Test Competition", group = "Dev")
|
||||
public class BlueBasketAuto extends OpMode {
|
||||
private Follower follower;
|
||||
private int state;
|
||||
|
||||
private HighBasketAutoPath1 path1;
|
||||
private HighBasketAutoPath2 path2;
|
||||
private AutoPark pathPark;
|
||||
private SkyHookSubsystem hook;
|
||||
private CometBotTeleopCompetition comp;
|
||||
private ElapsedTime runtime;
|
||||
|
||||
private LiftActionsSubsystem liftActionsSubsystem;
|
||||
|
||||
@Override
|
||||
public void init() {
|
||||
follower = new Follower(hardwareMap);
|
||||
follower.setMaxPower(.75);
|
||||
path1 = new HighBasketAutoPath1();
|
||||
path2 = new HighBasketAutoPath2();
|
||||
pathPark = new AutoPark();
|
||||
|
||||
comp = new CometBotTeleopCompetition(hardwareMap, telemetry, gamepad1, gamepad2);
|
||||
comp.initCloseClaw();
|
||||
runtime = new ElapsedTime();
|
||||
hook = new SkyHookSubsystem(hardwareMap);
|
||||
state = 0;
|
||||
|
||||
}
|
||||
|
||||
|
||||
@Override
|
||||
public void loop() {
|
||||
switch(state) {
|
||||
case 0:
|
||||
telemetry.addData("case0", "case0");
|
||||
|
||||
path1.moveToPath1(follower);
|
||||
state = 1;
|
||||
runtime.reset();
|
||||
case 1:
|
||||
if (runtime.seconds() > 5) {
|
||||
telemetry.addData("case1", "case1");
|
||||
|
||||
new SleepAction(.5);
|
||||
comp.highBucketDropAuto();
|
||||
|
||||
state = 2;
|
||||
}
|
||||
case 2:
|
||||
if (runtime.seconds() > 15) {
|
||||
telemetry.addData("case2", "case2");
|
||||
|
||||
// new SleepAsction(.5);
|
||||
//path2.moveToPath1(follower);
|
||||
|
||||
//For next time, add encoder control to skyhook and extend here
|
||||
//comp.moveSkyHook();
|
||||
|
||||
//pathPark.moveToPark(follower);
|
||||
|
||||
state = 3;
|
||||
}
|
||||
case 3:
|
||||
if (runtime.seconds() > 15) {
|
||||
telemetry.addData("case3", "case3");
|
||||
hook.toLevel1Position();
|
||||
|
||||
|
||||
state = 4;
|
||||
}
|
||||
case 4:
|
||||
if (runtime.seconds() > 15) {
|
||||
telemetry.addData("case3", "case3");
|
||||
hook.toLevel1Position();
|
||||
|
||||
|
||||
state = 4;
|
||||
}
|
||||
//System.out.println("default");
|
||||
//telemetry.addData("default", "default");
|
||||
//telemetry.update();
|
||||
}
|
||||
telemetry.update();
|
||||
follower.update();
|
||||
//follower.telemetryDebug(telemetry);
|
||||
}
|
||||
}
|
||||
*/
|
@ -46,7 +46,7 @@ public class PedroConstants {
|
||||
// Robot encoder direction
|
||||
public static final double LEFT_ENCODER_DIRECTION = Encoder.FORWARD;
|
||||
public static final double RIGHT_ENCODER_DIRECTION = Encoder.REVERSE;
|
||||
public static final double BACK_ENCODER_DIRECTION = Encoder.FORWARD;
|
||||
public static final double BACK_ENCODER_DIRECTION = Encoder.REVERSE;
|
||||
|
||||
// Arm config
|
||||
public static final String LIFT_SLIDE_LEFT_MOTOR = "lift-slide-left";
|
||||
@ -55,6 +55,7 @@ public class PedroConstants {
|
||||
public static final String WRIST_SERVO = "wrist-servo";
|
||||
public static final String ARM_SERVO = "arm-servo";
|
||||
public static final String THUMB_SERVO = "thumb-servo";
|
||||
public static final String HOOK = "skyhook";
|
||||
|
||||
/*
|
||||
Pedro's parameters
|
||||
@ -64,16 +65,16 @@ public class PedroConstants {
|
||||
public static final double ROBOT_WEIGHT_IN_KG = 9;
|
||||
|
||||
// Maximum velocity of the robot going forward
|
||||
public static final double ROBOT_SPEED_FORWARD = 53.223;
|
||||
public static final double ROBOT_SPEED_FORWARD = 50.02;
|
||||
|
||||
// Maximum velocity of the robot going right
|
||||
public static final double ROBOT_SPEED_LATERAL = 41.4081;
|
||||
public static final double ROBOT_SPEED_LATERAL = 36.07;
|
||||
|
||||
// Rate of deceleration when power is cut-off when the robot is moving forward
|
||||
public static final double FORWARD_ZERO_POWER_ACCEL = -76.8421;
|
||||
public static final double FORWARD_ZERO_POWER_ACCEL = -91.4557;
|
||||
|
||||
// Rate of deceleration when power is cut-off when the robot is moving to the right
|
||||
public static final double LATERAL_ZERO_POWER_ACCEL = -93.4183;
|
||||
public static final double LATERAL_ZERO_POWER_ACCEL = -98.514;
|
||||
|
||||
// Determines how fast your robot will decelerate as a factor of how fast your robot will coast to a stop
|
||||
public static final double ZERO_POWER_ACCEL_MULT = 4.0;
|
||||
|
@ -15,8 +15,12 @@ import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
import org.firstinspires.ftc.robotcore.external.Telemetry;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower;
|
||||
import org.firstinspires.ftc.teamcode.states.FieldStates;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.ArmSubsystem;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.ClawSubsystem;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.DualMotorSliderSubsystem;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.HangMotorSubsystem;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.MotorsSubsystem;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.WristSubsystem;
|
||||
|
||||
public class CometBotAutoDevelopment {
|
||||
|
||||
@ -24,7 +28,10 @@ public class CometBotAutoDevelopment {
|
||||
Subsystems
|
||||
*/
|
||||
private DualMotorSliderSubsystem dualSlides;
|
||||
|
||||
private ClawSubsystem claw;
|
||||
private WristSubsystem wrist;
|
||||
private ArmSubsystem arm;
|
||||
private HangMotorSubsystem hang;
|
||||
/*
|
||||
Controllers
|
||||
*/
|
||||
@ -35,10 +42,16 @@ public class CometBotAutoDevelopment {
|
||||
public Gamepad previousGamepad1;
|
||||
public Gamepad previousGamepad2;
|
||||
|
||||
|
||||
private Follower follower;
|
||||
|
||||
public CometBotAutoDevelopment(HardwareMap hardwareMap, Gamepad gamepad1, Gamepad gamepad2) {
|
||||
dualSlides = new DualMotorSliderSubsystem(hardwareMap);
|
||||
claw = new ClawSubsystem(hardwareMap);
|
||||
arm = new ArmSubsystem(hardwareMap);
|
||||
wrist = new WristSubsystem(hardwareMap);
|
||||
hang = new HangMotorSubsystem(hardwareMap);
|
||||
|
||||
this.gamepad1 = gamepad1;
|
||||
this.gamepad2 = gamepad2;
|
||||
currentGamepad1 = new Gamepad();
|
||||
@ -50,6 +63,9 @@ public class CometBotAutoDevelopment {
|
||||
|
||||
public void init() {
|
||||
dualSlides.init();
|
||||
claw.init();
|
||||
wrist.initTeleOp();
|
||||
arm.initTeleOp();
|
||||
follower.setMaxPower(MAX_POWER);
|
||||
follower.startTeleopDrive();
|
||||
}
|
||||
@ -60,25 +76,130 @@ public class CometBotAutoDevelopment {
|
||||
previousGamepad2.copy(currentGamepad2);
|
||||
currentGamepad2.copy(gamepad2);
|
||||
|
||||
/*
|
||||
Check if dpad_up/down is being pressed for slides
|
||||
*/
|
||||
//slides
|
||||
dualSlides.update();
|
||||
dualSlidesToLowBucketPosition();
|
||||
dualSlidesToHighBucketPosition();
|
||||
|
||||
dualSlidesToFloorPosition();
|
||||
//arm
|
||||
armToParkPosition();
|
||||
armAndWristToFloor();
|
||||
armToBucketPosition();
|
||||
//claw
|
||||
openClaw();
|
||||
openThumb();
|
||||
//hang
|
||||
grabBlueberrySkyhook();
|
||||
hangSkyhook();
|
||||
robotDown();
|
||||
robotUp();
|
||||
stopHook();
|
||||
follower.setTeleOpMovementVectors(-gamepad1.left_stick_y, -gamepad1.left_stick_x, -gamepad1.right_stick_x);
|
||||
follower.update();
|
||||
}
|
||||
private void grabBlueberrySkyhook () {
|
||||
if(currentGamepad1.x){
|
||||
claw.grabBlueberry();
|
||||
wrist.grabBlueberrySkyhook();
|
||||
arm.grabBlueberrySkyhook();
|
||||
}
|
||||
if(arm.getState() == ArmSubsystem.ArmState.GRAB_BLUEBERRY_SKYHOOK)
|
||||
claw.init();
|
||||
}
|
||||
private void hangSkyhook (){
|
||||
dualSlides.toHangHeight();
|
||||
wrist.hangBlueberrySkyhook();
|
||||
try {
|
||||
Thread.sleep(1000);
|
||||
} catch (InterruptedException e) {
|
||||
throw new RuntimeException(e);
|
||||
}
|
||||
arm.hangBlueberrySkyhook();
|
||||
if(arm.getState() == ArmSubsystem.ArmState.HANG_BLUEBERRY_SKYHOOK){
|
||||
try {
|
||||
Thread.sleep(1000);
|
||||
} catch (InterruptedException e) {
|
||||
throw new RuntimeException(e);
|
||||
}claw.closeClaw();
|
||||
}
|
||||
|
||||
private void dualSlidesToHighBucketPosition() {
|
||||
if (currentGamepad1.dpad_up && !previousGamepad1.dpad_up) {
|
||||
dualSlides.toHighBucketPosition();
|
||||
}
|
||||
|
||||
private void openClaw(){
|
||||
if(currentGamepad2.right_bumper && !previousGamepad2.right_bumper){
|
||||
claw.switchState();
|
||||
}
|
||||
}
|
||||
private void openThumb(){
|
||||
if(currentGamepad2.left_bumper && !previousGamepad2.left_bumper){
|
||||
claw.switchTState();
|
||||
}
|
||||
}
|
||||
private void armAndWristToFloor(){
|
||||
if(currentGamepad2.a && !previousGamepad2.a){
|
||||
|
||||
double increment = 0.7 - arm.getPosition();
|
||||
for(int i = 0; i < 3; i ++){
|
||||
arm.setPosition(arm.getPosition() + increment);
|
||||
try {
|
||||
Thread.sleep(50);
|
||||
} catch (InterruptedException e) {
|
||||
throw new RuntimeException(e);
|
||||
}
|
||||
}
|
||||
arm.toFloorPosition();
|
||||
}
|
||||
if(currentGamepad2.a && !previousGamepad2.a ){
|
||||
wrist.switchState();
|
||||
}
|
||||
|
||||
|
||||
|
||||
}
|
||||
private void armToBucketPosition(){
|
||||
if(currentGamepad2.dpad_up && !previousGamepad2.dpad_up){
|
||||
arm.toBucketPosition();
|
||||
wrist.toBucketPosition();
|
||||
|
||||
}
|
||||
}
|
||||
private void armToParkPosition(){
|
||||
if(currentGamepad2.x && !previousGamepad2.x){
|
||||
arm.toParkPosition();
|
||||
wrist.toFloorPosition();
|
||||
}
|
||||
}
|
||||
|
||||
private void dualSlidesToHighBucketPosition() {
|
||||
if (currentGamepad2.y && !previousGamepad2.y) {
|
||||
dualSlides.toHighBucketPosition();
|
||||
}
|
||||
}
|
||||
private void robotUp(){
|
||||
if(currentGamepad1.dpad_up && !previousGamepad1.dpad_up){
|
||||
dualSlides.toHangBelowFloor();
|
||||
dualSlides.update();
|
||||
hang.hangRobot();
|
||||
}
|
||||
|
||||
}
|
||||
private void robotDown(){
|
||||
if(currentGamepad1.dpad_down && !previousGamepad1.dpad_down){
|
||||
hang.robotToFloor();
|
||||
}
|
||||
}
|
||||
private void stopHook(){
|
||||
if(gamepad1.left_bumper){
|
||||
hang.disableMotor();
|
||||
}
|
||||
}
|
||||
private void dualSlidesToFloorPosition() {
|
||||
if (currentGamepad2.dpad_down && !previousGamepad2.dpad_down) {
|
||||
dualSlides.toFloorPosition();
|
||||
}
|
||||
}
|
||||
private void dualSlidesToLowBucketPosition() {
|
||||
if (currentGamepad1.dpad_down && !previousGamepad1.dpad_down) {
|
||||
if (currentGamepad2.b && !previousGamepad2.b) {
|
||||
dualSlides.toLowBucketPosition();
|
||||
}
|
||||
}
|
||||
|
@ -0,0 +1,302 @@
|
||||
package org.firstinspires.ftc.teamcode.cometbots.paths;
|
||||
|
||||
import static com.qualcomm.hardware.lynx.commands.core.LynxSetMotorPIDFControlLoopCoefficientsCommand.InternalMotorControlAlgorithm.Max;
|
||||
|
||||
import androidx.annotation.NonNull;
|
||||
|
||||
import com.acmerobotics.dashboard.telemetry.TelemetryPacket;
|
||||
import com.acmerobotics.roadrunner.Action;
|
||||
import com.acmerobotics.roadrunner.SequentialAction;
|
||||
import com.acmerobotics.roadrunner.SleepAction;
|
||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
||||
import com.qualcomm.robotcore.util.ElapsedTime;
|
||||
|
||||
//import org.firstinspires.ftc.teamcode.cometbots.CometBotTeleopCompetition;
|
||||
//import org.firstinspires.ftc.teamcode.cometbots.paths.HighBasketPath1;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower;
|
||||
//import org.firstinspires.ftc.teamcode.subsystem.AutoPark;
|
||||
import org.firstinspires.ftc.teamcode.cometbots.paths.HighBasketPath1;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.ArmSubsystem;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.ClawSubsystem;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.DualMotorSliderSubsystem;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.WristSubsystem;
|
||||
//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;
|
||||
|
||||
|
||||
@Autonomous(name = "Auto Test Competition V2", group = "Dev")
|
||||
public class CometBotDriveV2 extends OpMode {
|
||||
private Follower follower;
|
||||
private int state;
|
||||
|
||||
private HighBasketPath1 path1;
|
||||
private HighBasketPath2 path2;
|
||||
private HighBasketPath3 path3;
|
||||
|
||||
|
||||
|
||||
//private CometBotTeleopCompetition comp;
|
||||
private static ElapsedTime runtime;
|
||||
private static boolean initalized = false;
|
||||
private static boolean followingPath = false;
|
||||
private DualMotorSliderSubsystem lift;
|
||||
private ClawSubsystem claw;
|
||||
private WristSubsystem wrist;
|
||||
private ArmSubsystem arm;
|
||||
|
||||
@Override
|
||||
public void init() {
|
||||
follower = new Follower(hardwareMap);
|
||||
follower.setMaxPower(.75);
|
||||
|
||||
path1 = new HighBasketPath1();
|
||||
path2 = new HighBasketPath2();
|
||||
path3 = new HighBasketPath3();
|
||||
lift = new DualMotorSliderSubsystem(hardwareMap);
|
||||
arm = new ArmSubsystem(hardwareMap);
|
||||
wrist = new WristSubsystem(hardwareMap);
|
||||
claw = new ClawSubsystem(hardwareMap);
|
||||
|
||||
|
||||
|
||||
lift.init();
|
||||
arm.initAuto();
|
||||
wrist.InitAuto();
|
||||
claw.init();
|
||||
|
||||
//comp = new CometBotTeleopCompetition(hardwareMap, telemetry, gamepad1, gamepad2);
|
||||
// comp.initCloseClaw();
|
||||
|
||||
}
|
||||
|
||||
|
||||
public void loop() {
|
||||
telemetry.addData("state", state);
|
||||
telemetry.addData("followingPath", followingPath);
|
||||
telemetry.addData("busy", follower.isBusy());
|
||||
if (runtime != null) {
|
||||
telemetry.addData("Runtime (seconds)", runtime.seconds());
|
||||
}
|
||||
switch (state) {
|
||||
case 0:
|
||||
moveToPathOneAndHighBucket();
|
||||
break;
|
||||
case 1:
|
||||
doArmThing();
|
||||
state = 2;
|
||||
break;
|
||||
case 2:
|
||||
moveToPathTwoAndPickSampleUp();
|
||||
break;
|
||||
case 3:
|
||||
// doPickUpThing();
|
||||
state = 4;
|
||||
break;
|
||||
case 4:
|
||||
// moveToBasketPath3();
|
||||
break;
|
||||
// case 5:
|
||||
// theArmThing();
|
||||
// break;
|
||||
// case 6:
|
||||
// moveToPickupAgainPath4();
|
||||
// break;
|
||||
// case 7:
|
||||
// doPickUpThingAgain();
|
||||
// break;
|
||||
// case 8:
|
||||
// moveToPickupAgainPath5();
|
||||
// break;
|
||||
// case 9:
|
||||
// //theArmThingAgain();
|
||||
// break;
|
||||
// case 10:
|
||||
// //moveToParkPath6();
|
||||
// break;
|
||||
// case 11:
|
||||
|
||||
|
||||
}
|
||||
telemetry.update();
|
||||
|
||||
follower.update();
|
||||
|
||||
|
||||
}
|
||||
|
||||
private void moveToPathOneAndHighBucket() {
|
||||
path1.moveToPath1(follower);
|
||||
state = 1;
|
||||
}
|
||||
|
||||
public class SetStateAction implements Action {
|
||||
|
||||
private int value;
|
||||
|
||||
public SetStateAction(int value) {
|
||||
this.value = value;
|
||||
}
|
||||
@Override
|
||||
public boolean run(@NonNull TelemetryPacket telemetryPacket) {
|
||||
state = value;
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
private Action setStateValue(int value) {
|
||||
return new SetStateAction(value);
|
||||
}
|
||||
|
||||
private void doArmThing() {
|
||||
|
||||
lift.toHighBucketReverseDrop();
|
||||
arm.toBucketPosition();
|
||||
wrist.toBucketPosition();
|
||||
claw.openClaw();
|
||||
wrist.toFloorPosition();
|
||||
|
||||
state = 2;
|
||||
}
|
||||
|
||||
|
||||
// private void theArmThing() {
|
||||
// telemetry.addData("busy?", follower.isBusy());
|
||||
// telemetry.addData("end?", follower.atParametricEnd());
|
||||
// if (follower.atParametricEnd()){
|
||||
// follower.breakFollowing();
|
||||
// comp.highBucketDropAuto();
|
||||
// state = 6;
|
||||
// }
|
||||
// follower.breakFollowing();
|
||||
// }
|
||||
|
||||
// private void theArmThingAgain() {
|
||||
// follower.breakFollowing();
|
||||
// comp.highBucketDropAuto();
|
||||
// state = 10;
|
||||
// }
|
||||
|
||||
private void moveToPathTwoAndPickSampleUp() {
|
||||
if (!follower.isBusy()) {
|
||||
path2.moveToPath2(follower);
|
||||
state = 3;
|
||||
}
|
||||
}
|
||||
//
|
||||
private void moveToBasketPath3() {
|
||||
if (!follower.isBusy()) {
|
||||
path3.moveToBasketPath3(follower);
|
||||
state = 5;
|
||||
}
|
||||
}
|
||||
|
||||
// private void moveToPickupAgainPath4() {
|
||||
// if (!followingPath) {
|
||||
// path4.moveToPickupAgainPath4(follower);
|
||||
// followingPath = true;
|
||||
// }
|
||||
// if (runtime != null) {
|
||||
// telemetry.addData("Runtime (seconds)", runtime.seconds());
|
||||
// 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);
|
||||
// followingPath = true;
|
||||
// }
|
||||
// if (runtime != null) {
|
||||
// telemetry.addData("Runtime (seconds)", runtime.seconds());
|
||||
// if (follower.atParametricEnd() || runtime.seconds() > 10.0) {
|
||||
// state = 5;
|
||||
// followingPath = false;
|
||||
// }
|
||||
// }
|
||||
// }
|
||||
//
|
||||
// private void thePickUpAuto() {
|
||||
// Actions.runBlocking(new SequentialAction(
|
||||
// new SleepAction(.1),
|
||||
// comp.claw.openClaw(),
|
||||
// new SleepAction(.2),
|
||||
// comp.wrist.toPickupPosition(),
|
||||
// new SleepAction(.2),
|
||||
// comp.arm.toSubmarinePosition(),
|
||||
// new SleepAction(.5),
|
||||
// comp.claw.closeClaw(),
|
||||
// new SleepAction(.3),
|
||||
// comp.wrist.toFloorPosition(),
|
||||
// new SleepAction(.2),
|
||||
// comp.arm.toParkPosition(),
|
||||
// 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();
|
||||
// thePickUpAuto();
|
||||
// state = 4;
|
||||
// }
|
||||
//
|
||||
// private void doPickUpThingAgain() {
|
||||
// follower.breakFollowing();
|
||||
// thePickUpAuto();
|
||||
// state = 8;
|
||||
// }
|
||||
//
|
||||
//
|
||||
}
|
||||
|
@ -0,0 +1,39 @@
|
||||
package org.firstinspires.ftc.teamcode.cometbots.paths;
|
||||
|
||||
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierCurve;
|
||||
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 HighBasketPath1 {
|
||||
|
||||
private final Pose startPose = new Pose(10, 89);
|
||||
|
||||
public void moveToPath1(Follower robot) {
|
||||
PathChain pathChain;
|
||||
robot.setStartingPose(startPose);
|
||||
PathBuilder builder = new PathBuilder();
|
||||
builder
|
||||
.addPath(
|
||||
// Line 1
|
||||
new BezierLine(
|
||||
new Point(10.000, 89.000, Point.CARTESIAN),
|
||||
new Point(20.000, 130.000, Point.CARTESIAN)
|
||||
)
|
||||
)
|
||||
.setLinearHeadingInterpolation(Math.toRadians(0), Math.toRadians(320));
|
||||
pathChain = builder.build();
|
||||
robot.followPath(pathChain);
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -0,0 +1,36 @@
|
||||
package org.firstinspires.ftc.teamcode.cometbots.paths;
|
||||
|
||||
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose;
|
||||
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 HighBasketPath2 {
|
||||
|
||||
|
||||
public void moveToPath2(Follower robot) {
|
||||
PathChain pathChain;
|
||||
PathBuilder builder = new PathBuilder();
|
||||
builder
|
||||
.addPath(
|
||||
// Line 1
|
||||
new BezierLine(
|
||||
new Point(20.000, 130.000, Point.CARTESIAN),
|
||||
new Point(26.000, 117.000, Point.CARTESIAN)
|
||||
)
|
||||
)
|
||||
.setLinearHeadingInterpolation(Math.toRadians(0), Math.toRadians(0));
|
||||
pathChain = builder.build();
|
||||
robot.followPath(pathChain);
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -0,0 +1,35 @@
|
||||
package org.firstinspires.ftc.teamcode.cometbots.paths;
|
||||
|
||||
|
||||
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 HighBasketPath3 {
|
||||
|
||||
|
||||
public void moveToBasketPath3(Follower robot) {
|
||||
PathChain pathChain;
|
||||
PathBuilder builder = new PathBuilder();
|
||||
builder
|
||||
.addPath(
|
||||
// Line 1
|
||||
new BezierLine(
|
||||
new Point(26.000, 117.000, Point.CARTESIAN),
|
||||
new Point(10.000, 89.00, Point.CARTESIAN)
|
||||
)
|
||||
)
|
||||
.setLinearHeadingInterpolation(Math.toRadians(0), Math.toRadians(320));
|
||||
pathChain = builder.build();
|
||||
robot.followPath(pathChain);
|
||||
}
|
||||
|
||||
}
|
||||
|
@ -56,7 +56,7 @@ public class ArmTest extends LinearOpMode {
|
||||
Gamepad currentGamepad1 = new Gamepad();
|
||||
Gamepad previousGamepad1 = new Gamepad();
|
||||
|
||||
arm.init();
|
||||
arm.initTeleOp();
|
||||
waitForStart();
|
||||
runtime.reset();
|
||||
|
||||
|
@ -57,7 +57,7 @@ public class WristTest extends LinearOpMode {
|
||||
Gamepad currentGamepad1 = new Gamepad();
|
||||
Gamepad previousGamepad1 = new Gamepad();
|
||||
|
||||
wrist.init();
|
||||
wrist.initTeleOp();
|
||||
waitForStart();
|
||||
runtime.reset();
|
||||
|
||||
|
@ -4,32 +4,45 @@ import com.acmerobotics.dashboard.config.Config;
|
||||
|
||||
@Config
|
||||
public class RobotConstants {
|
||||
public final static double clawClose = 0.85;
|
||||
public final static double clawClose = 0.95;
|
||||
public final static double clawOpen = 0.05;
|
||||
|
||||
public final static double armFloor = 0.6375;
|
||||
public final static double armFloor = 0.7;
|
||||
public final static double armSubmarine = 0.55;
|
||||
public final static double armPark = 0.1250;
|
||||
public final static double armBucket = 0.25;
|
||||
|
||||
public final static double wristPickup = 0.6;
|
||||
public final static double wristBucket = 0.3;
|
||||
public final static double wristFloor = 0.125;
|
||||
public final static double armReverseBucket = 0.08;
|
||||
public final static double armPark = 0.33;
|
||||
//value for grabbing the hook Specimen
|
||||
public final static double grabBlueberry = 0.35;
|
||||
public final static double armGrabBlueberrySkyhook = 0.15;
|
||||
public final static double wristGrabBlueberrySkyhook = 0.15;
|
||||
public final static double armHangBlueberrySkyhook = 0.23;
|
||||
public final static double wristHangBlueberrySkyhook = 0.7;
|
||||
public final static int slideHangBlueberrySkyhook = 500;
|
||||
public final static int slideBelowFloor = -150;
|
||||
public final static int backwardBucketDrop = 4670;
|
||||
public final static double armBucket = 0.45;
|
||||
public final static double armInit = 0.135;
|
||||
public final static double wristInit = 0.25;
|
||||
public final static double wristPickup = 0.475;
|
||||
public final static double wristBucket = 0.56;
|
||||
public final static double wristFloor = 0.75;
|
||||
public final static double wristBackwardBucket = 0.775;
|
||||
|
||||
public final static double wristRung = 0.55;
|
||||
|
||||
public final static double wristSpeciemen = 0.1;
|
||||
|
||||
|
||||
public final static int toBar = 500;
|
||||
public final static int toFloor = 0;
|
||||
public final static int liftToFloorPos = 350;
|
||||
public final static int liftToSubmarinePos = 350;
|
||||
public final static int liftToLowBucketPos = 2650;
|
||||
public final static int liftToLowBucketPos = 1750;
|
||||
public final static int liftToHighRung = 2100;
|
||||
public final static int dropToHighRung = 1675;
|
||||
|
||||
public final static int liftToHighRungAttach = 1050;
|
||||
|
||||
|
||||
public final static int liftToHighBucketPos = 4900;
|
||||
public final static int liftToHighBucketPos = 4000;
|
||||
public final static double liftPower = 1;
|
||||
}
|
@ -31,7 +31,7 @@ public class FollowerConstants {
|
||||
public static String rightFrontMotorName = FRONT_RIGHT_MOTOR;
|
||||
public static String rightRearMotorName = BACK_RIGHT_MOTOR;
|
||||
|
||||
public static DcMotorSimple.Direction leftFrontMotorDirection = FRONT_RIGHT_MOTOR_DIRECTION;
|
||||
public static DcMotorSimple.Direction leftFrontMotorDirection = FRONT_LEFT_MOTOR_DIRECTION;
|
||||
public static DcMotorSimple.Direction rightFrontMotorDirection = FRONT_RIGHT_MOTOR_DIRECTION;
|
||||
public static DcMotorSimple.Direction leftRearMotorDirection = BACK_LEFT_MOTOR_DIRECTION;
|
||||
public static DcMotorSimple.Direction rightRearMotorDirection = BACK_RIGHT_MOTOR_DIRECTION;
|
||||
@ -48,7 +48,7 @@ public class FollowerConstants {
|
||||
public static CustomPIDFCoefficients translationalPIDFCoefficients = new CustomPIDFCoefficients(
|
||||
.25,
|
||||
0,
|
||||
0.0375,
|
||||
0.02,
|
||||
0);
|
||||
|
||||
// Translational Integral
|
||||
@ -75,7 +75,7 @@ public class FollowerConstants {
|
||||
|
||||
// Drive PIDF coefficients
|
||||
public static CustomFilteredPIDFCoefficients drivePIDFCoefficients = new CustomFilteredPIDFCoefficients(
|
||||
0.00375,
|
||||
0.00235,
|
||||
0,
|
||||
0.00003,
|
||||
0.8,
|
||||
|
@ -0,0 +1,136 @@
|
||||
package org.firstinspires.ftc.teamcode.states;
|
||||
|
||||
import com.acmerobotics.dashboard.FtcDashboard;
|
||||
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.OpMode;
|
||||
|
||||
import org.firstinspires.ftc.robotcore.external.Telemetry;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.follower.Follower;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.localization.Pose;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierCurve;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.BezierLine;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.PathChain;
|
||||
import org.firstinspires.ftc.teamcode.pedroPathing.pathGeneration.Point;
|
||||
|
||||
@Autonomous(name = "Blue Basket Auto States", group = "Competition")
|
||||
public class BlueBasketAutoStates extends OpMode {
|
||||
private Telemetry telemetryA;
|
||||
|
||||
private Follower follower;
|
||||
|
||||
private PathChain path;
|
||||
|
||||
private final Pose startPose = new Pose(11.25, 95.75);
|
||||
|
||||
@Override
|
||||
public void init() {
|
||||
follower = new Follower(hardwareMap);
|
||||
|
||||
follower.setMaxPower(.45);
|
||||
|
||||
follower.setStartingPose(startPose);
|
||||
|
||||
path = follower.pathBuilder()
|
||||
.addPath(
|
||||
// Line 1
|
||||
new BezierLine(
|
||||
new Point(11.250, 95.750, Point.CARTESIAN),
|
||||
new Point(37.000, 108.000, Point.CARTESIAN)
|
||||
)
|
||||
)
|
||||
.setConstantHeadingInterpolation(Math.toRadians(0))
|
||||
.addPath(
|
||||
// Line 2
|
||||
new BezierCurve(
|
||||
new Point(37.000, 108.000, Point.CARTESIAN),
|
||||
new Point(73.286, 111.536, Point.CARTESIAN),
|
||||
new Point(67.821, 120.536, Point.CARTESIAN)
|
||||
)
|
||||
)
|
||||
.setConstantHeadingInterpolation(Math.toRadians(0))
|
||||
.addPath(
|
||||
// Line 3
|
||||
new BezierLine(
|
||||
new Point(67.821, 120.536, Point.CARTESIAN),
|
||||
new Point(28.000, 121.500, Point.CARTESIAN)
|
||||
)
|
||||
)
|
||||
.setConstantHeadingInterpolation(Math.toRadians(0))
|
||||
.addPath(
|
||||
// Line 4
|
||||
new BezierLine(
|
||||
new Point(28.000, 121.500, Point.CARTESIAN),
|
||||
new Point(18.000, 130.179, Point.CARTESIAN)
|
||||
)
|
||||
)
|
||||
.setConstantHeadingInterpolation(Math.toRadians(0))
|
||||
.addPath(
|
||||
// Line 5
|
||||
new BezierCurve(
|
||||
new Point(18.000, 130.179, Point.CARTESIAN),
|
||||
new Point(59.000, 102.500, Point.CARTESIAN),
|
||||
new Point(68.700, 130.500, Point.CARTESIAN)
|
||||
)
|
||||
)
|
||||
.setConstantHeadingInterpolation(Math.toRadians(0))
|
||||
.addPath(
|
||||
// Line 6
|
||||
new BezierLine(
|
||||
new Point(68.700, 130.500, Point.CARTESIAN),
|
||||
new Point(18.000, 130.339, Point.CARTESIAN)
|
||||
)
|
||||
)
|
||||
.setConstantHeadingInterpolation(Math.toRadians(0))
|
||||
.addPath(
|
||||
// Line 7
|
||||
new BezierCurve(
|
||||
new Point(18.000, 130.339, Point.CARTESIAN),
|
||||
new Point(49.018, 121.179, Point.CARTESIAN),
|
||||
new Point(63.804, 135.321, Point.CARTESIAN)
|
||||
)
|
||||
)
|
||||
.setConstantHeadingInterpolation(Math.toRadians(0))
|
||||
.addPath(
|
||||
// Line 8
|
||||
new BezierLine(
|
||||
new Point(63.804, 135.321, Point.CARTESIAN),
|
||||
new Point(53.036, 135.161, Point.CARTESIAN)
|
||||
)
|
||||
)
|
||||
.setConstantHeadingInterpolation(Math.toRadians(0))
|
||||
.addPath(
|
||||
// Line 9
|
||||
new BezierLine(
|
||||
new Point(53.036, 135.161, Point.CARTESIAN),
|
||||
new Point(18.643, 135.000, Point.CARTESIAN)
|
||||
)
|
||||
)
|
||||
.setConstantHeadingInterpolation(Math.toRadians(0))
|
||||
.addPath(
|
||||
// Line 10
|
||||
new BezierLine(
|
||||
new Point(18.643, 135.000, Point.CARTESIAN),
|
||||
new Point(72.300, 97.400, Point.CARTESIAN)
|
||||
)
|
||||
)
|
||||
.addPath(
|
||||
// Line 11
|
||||
new BezierLine(
|
||||
new Point(18.643, 135.000, Point.CARTESIAN),
|
||||
new Point(83.250, 95.464, Point.CARTESIAN)
|
||||
)
|
||||
)
|
||||
.setLinearHeadingInterpolation(Math.toRadians(0), Math.toRadians(270)).build();
|
||||
follower.followPath(path);
|
||||
|
||||
telemetryA = new MultipleTelemetry(this.telemetry, FtcDashboard.getInstance().getTelemetry());
|
||||
telemetryA.update();
|
||||
}
|
||||
|
||||
@Override
|
||||
public void loop() {
|
||||
follower.update();
|
||||
follower.telemetryDebug(telemetryA);
|
||||
}
|
||||
}
|
@ -3,7 +3,11 @@ package org.firstinspires.ftc.teamcode.subsystem;
|
||||
import static org.firstinspires.ftc.teamcode.PedroConstants.ARM_SERVO;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.armBucket;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.armFloor;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.armGrabBlueberrySkyhook;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.armHangBlueberrySkyhook;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.armInit;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.armPark;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.armReverseBucket;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
import com.qualcomm.robotcore.hardware.ServoImplEx;
|
||||
@ -11,7 +15,7 @@ import com.qualcomm.robotcore.hardware.ServoImplEx;
|
||||
public class ArmSubsystem {
|
||||
|
||||
public enum ArmState {
|
||||
PARK, FLOOR, BUCKET, SUBMARINE
|
||||
PARK, FLOOR, BUCKET, SUBMARINE, GRAB_BLUEBERRY_SKYHOOK, HANG_BLUEBERRY_SKYHOOK, INIT, REVERE_BUCKET
|
||||
}
|
||||
|
||||
private ServoImplEx arm;
|
||||
@ -20,7 +24,18 @@ public class ArmSubsystem {
|
||||
public ArmSubsystem(HardwareMap hardwareMap) {
|
||||
this.arm = hardwareMap.get(ServoImplEx.class, ARM_SERVO);
|
||||
}
|
||||
|
||||
public void grabBlueberrySkyhook(){
|
||||
setState(ArmState.GRAB_BLUEBERRY_SKYHOOK);
|
||||
arm.setPosition(armGrabBlueberrySkyhook);
|
||||
}
|
||||
public void hangBlueberrySkyhook(){
|
||||
setState(ArmState.HANG_BLUEBERRY_SKYHOOK);
|
||||
arm.setPosition(armHangBlueberrySkyhook);
|
||||
}
|
||||
public void toReverseBucket(){
|
||||
arm.setPosition(armReverseBucket);
|
||||
setState(ArmState.REVERE_BUCKET);
|
||||
}
|
||||
public void toParkPosition() {
|
||||
arm.setPosition(armPark);
|
||||
setState(ArmState.PARK);
|
||||
@ -35,6 +50,10 @@ public class ArmSubsystem {
|
||||
arm.setPosition(armBucket);
|
||||
setState(ArmState.BUCKET);
|
||||
}
|
||||
public void toInitPosition(){
|
||||
arm.setPosition(armInit);
|
||||
setState(ArmState.INIT);
|
||||
}
|
||||
|
||||
public void setState(ArmState armState) {
|
||||
this.state = armState;
|
||||
@ -44,10 +63,14 @@ public class ArmSubsystem {
|
||||
return this.state;
|
||||
}
|
||||
|
||||
public void init() {
|
||||
public void initTeleOp() {
|
||||
arm.resetDeviceConfigurationForOpMode();
|
||||
toParkPosition();
|
||||
}
|
||||
public void initAuto(){
|
||||
arm.resetDeviceConfigurationForOpMode();
|
||||
toInitPosition();
|
||||
}
|
||||
|
||||
public double getPosition() {
|
||||
return this.arm.getPosition();
|
||||
|
@ -4,6 +4,7 @@ import static org.firstinspires.ftc.teamcode.PedroConstants.CLAW_NAME;
|
||||
import static org.firstinspires.ftc.teamcode.PedroConstants.THUMB_SERVO;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.clawClose;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.clawOpen;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.grabBlueberry;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
@ -11,11 +12,11 @@ import com.qualcomm.robotcore.hardware.Servo;
|
||||
public class ClawSubsystem {
|
||||
|
||||
public enum ClawState {
|
||||
CLOSED, OPEN
|
||||
CLOSED, OPEN, GRAB_BLUEBERRY
|
||||
}
|
||||
|
||||
public enum ThumbState {
|
||||
DOWN, UP
|
||||
DOWN, UP, AWAY
|
||||
}
|
||||
|
||||
private Servo claw;
|
||||
@ -27,14 +28,19 @@ public class ClawSubsystem {
|
||||
claw = hardwareMap.get(Servo.class, CLAW_NAME);
|
||||
thumb = hardwareMap.get(Servo.class, THUMB_SERVO);
|
||||
}
|
||||
|
||||
public void grabBlueberry(){
|
||||
claw.setPosition(grabBlueberry);
|
||||
state = ClawState.GRAB_BLUEBERRY;
|
||||
}
|
||||
public void closeClaw() {
|
||||
claw.setPosition(clawClose);
|
||||
|
||||
state = ClawState.CLOSED;
|
||||
}
|
||||
|
||||
public void openClaw() {
|
||||
claw.setPosition(clawOpen);
|
||||
|
||||
state = ClawState.OPEN;
|
||||
}
|
||||
|
||||
@ -68,13 +74,18 @@ public class ClawSubsystem {
|
||||
}
|
||||
|
||||
public void thumbUp() {
|
||||
thumb.setPosition(0.95);
|
||||
thumb.setPosition(0.5);
|
||||
tState = ThumbState.UP;
|
||||
}
|
||||
|
||||
public void thumbDown() {
|
||||
thumb.setPosition(0.05);
|
||||
thumb.setPosition(0.00);
|
||||
tState = ThumbState.DOWN;
|
||||
}
|
||||
|
||||
public void thumbOutOfTheWay() {
|
||||
thumb.setPosition(0.95);
|
||||
tState = ThumbState.AWAY;
|
||||
}
|
||||
|
||||
}
|
@ -2,9 +2,15 @@ package org.firstinspires.ftc.teamcode.subsystem;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.PedroConstants.LIFT_SLIDE_LEFT_MOTOR;
|
||||
import static org.firstinspires.ftc.teamcode.PedroConstants.LIFT_SLIDE_RIGHT_MOTOR;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.backwardBucketDrop;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToHighBucketPos;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.liftToLowBucketPos;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.slideBelowFloor;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.slideHangBlueberrySkyhook;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
import com.qualcomm.robotcore.util.ElapsedTime;
|
||||
|
||||
@ -68,7 +74,9 @@ public class DualMotorSliderSubsystem {
|
||||
liftSlideLeft = hardwareMap.get(DcMotorEx.class, LIFT_SLIDE_LEFT_MOTOR);
|
||||
liftSlideRight = hardwareMap.get(DcMotorEx.class, LIFT_SLIDE_RIGHT_MOTOR);
|
||||
}
|
||||
|
||||
public int getCurrentPosition(){
|
||||
return liftSlideLeft.getCurrentPosition();
|
||||
}
|
||||
public void init() {
|
||||
/*
|
||||
Initialize the motors with the following settings (assuming slide is at the very bottom position):
|
||||
@ -81,7 +89,8 @@ public class DualMotorSliderSubsystem {
|
||||
liftSlideLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||
liftSlideLeft.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
liftSlideLeft.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||
|
||||
liftSlideLeft.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
liftSlideRight.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
liftSlideRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||
liftSlideRight.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
liftSlideRight.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||
@ -121,11 +130,30 @@ public class DualMotorSliderSubsystem {
|
||||
}
|
||||
|
||||
public void toLowBucketPosition() {
|
||||
setTargetPosition(1500);
|
||||
setTargetPosition(liftToLowBucketPos);
|
||||
}
|
||||
|
||||
public void toHighBucketPosition() {
|
||||
setTargetPosition(3000);
|
||||
setTargetPosition(liftToHighBucketPos);
|
||||
}
|
||||
|
||||
public void toFixedPosition(int value) {
|
||||
setTargetPosition(value);
|
||||
}
|
||||
public void toHangHeight(){
|
||||
setTargetPosition(slideHangBlueberrySkyhook);
|
||||
|
||||
}
|
||||
public void toHangBelowFloor(){
|
||||
setTargetPosition(slideBelowFloor);
|
||||
|
||||
}
|
||||
|
||||
public int getFixedPosition() {
|
||||
return liftSlideLeft.getCurrentPosition();
|
||||
}
|
||||
|
||||
public void toFloorPosition(){setTargetPosition(0);}
|
||||
public void toHighBucketReverseDrop(){setTargetPosition(backwardBucketDrop);}
|
||||
|
||||
}
|
||||
|
@ -0,0 +1,60 @@
|
||||
package org.firstinspires.ftc.teamcode.subsystem;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.PedroConstants.HOOK;
|
||||
import static org.firstinspires.ftc.teamcode.PedroConstants.LIFT_SLIDE_LEFT_MOTOR;
|
||||
import static org.firstinspires.ftc.teamcode.PedroConstants.LIFT_SLIDE_RIGHT_MOTOR;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
import com.qualcomm.robotcore.hardware.HardwareMap;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.toBar;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.toFloor;
|
||||
|
||||
public class HangMotorSubsystem {
|
||||
private DcMotorEx hang;
|
||||
|
||||
public HangMotorSubsystem(HardwareMap hardwareMap) {
|
||||
|
||||
hang = hardwareMap.get(DcMotorEx.class, HOOK);
|
||||
|
||||
|
||||
}
|
||||
|
||||
public int getCurrentPosition(){
|
||||
int Return = hang.getCurrentPosition();
|
||||
return Return;
|
||||
}
|
||||
public void init(){
|
||||
hang.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
|
||||
hang.setDirection(DcMotorSimple.Direction.FORWARD);
|
||||
hang.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
hang.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
}
|
||||
public void hangRobot(){
|
||||
hang.setTargetPosition(toBar);
|
||||
|
||||
}
|
||||
public void robotToFloor(){
|
||||
hang.setTargetPosition(toFloor);
|
||||
}
|
||||
public void disableMotor(){
|
||||
hang.setPower(0);
|
||||
hang.setMotorDisable();
|
||||
|
||||
}
|
||||
public void setPower(double power){
|
||||
hang.setPower(power);
|
||||
}
|
||||
public void stopMotor(){
|
||||
hang.setPower(0);
|
||||
|
||||
|
||||
}
|
||||
public void toHangPosition(int Position){
|
||||
//write in limits for protection
|
||||
hang.setPower(Position);
|
||||
}
|
||||
|
||||
}
|
@ -0,0 +1,141 @@
|
||||
package org.firstinspires.ftc.teamcode.subsystem;
|
||||
|
||||
/* Copyright (c) 2021 FIRST. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without modification,
|
||||
* are permitted (subject to the limitations in the disclaimer below) provided that
|
||||
* the following conditions are met:
|
||||
*
|
||||
* Redistributions of source code must retain the above copyright notice, this list
|
||||
* of conditions and the following disclaimer.
|
||||
*
|
||||
* Redistributions in binary form must reproduce the above copyright notice, this
|
||||
* list of conditions and the following disclaimer in the documentation and/or
|
||||
* other materials provided with the distribution.
|
||||
*
|
||||
* Neither the name of FIRST nor the names of its contributors may be used to endorse or
|
||||
* promote products derived from this software without specific prior written permission.
|
||||
*
|
||||
* NO EXPRESS OR IMPLIED LICENSES TO ANY PARTY'S PATENT RIGHTS ARE GRANTED BY THIS
|
||||
* LICENSE. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO,
|
||||
* THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
|
||||
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE
|
||||
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
*/
|
||||
|
||||
import com.acmerobotics.roadrunner.SequentialAction;
|
||||
import com.acmerobotics.roadrunner.SleepAction;
|
||||
import com.acmerobotics.roadrunner.ftc.Actions;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
import com.qualcomm.robotcore.hardware.Gamepad;
|
||||
import com.qualcomm.robotcore.util.ElapsedTime;
|
||||
|
||||
import org.firstinspires.ftc.teamcode.subsystem.ArmSubsystem;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.DualMotorSliderSubsystem;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.WristSubsystem;
|
||||
import org.firstinspires.ftc.teamcode.subsystem.ClawSubsystem;
|
||||
|
||||
|
||||
@TeleOp(name = "Lift Wrist Arm Test", group = "Debug")
|
||||
public class LiftArmWrist extends LinearOpMode {
|
||||
|
||||
private final ElapsedTime runtime = new ElapsedTime();
|
||||
|
||||
@Override
|
||||
public void runOpMode() {
|
||||
|
||||
/*
|
||||
* Instantiate Lift
|
||||
*/
|
||||
DualMotorSliderSubsystem lift = new DualMotorSliderSubsystem(hardwareMap);
|
||||
WristSubsystem wrist = new WristSubsystem(hardwareMap);
|
||||
ArmSubsystem arm = new ArmSubsystem(hardwareMap);
|
||||
ClawSubsystem claw = new ClawSubsystem(hardwareMap);
|
||||
HangMotorSubsystem hang = new HangMotorSubsystem(hardwareMap);
|
||||
|
||||
|
||||
/*
|
||||
* Instantiate gamepad state holders
|
||||
*/
|
||||
Gamepad currentGamepad1 = new Gamepad();
|
||||
Gamepad previousGamepad1 = new Gamepad();
|
||||
|
||||
lift.init();
|
||||
wrist.initTeleOp();
|
||||
arm.initTeleOp();
|
||||
claw.init();
|
||||
waitForStart();
|
||||
runtime.reset();
|
||||
|
||||
|
||||
// run until the end of the match (driver presses STOP)
|
||||
while (opModeIsActive()) {
|
||||
|
||||
previousGamepad1.copy(currentGamepad1);
|
||||
currentGamepad1.copy(gamepad1);
|
||||
|
||||
if (currentGamepad1.dpad_up && !previousGamepad1.dpad_up) {
|
||||
arm.setPosition(arm.getPosition() + .05);
|
||||
}
|
||||
|
||||
if (currentGamepad1.dpad_down && !previousGamepad1.dpad_down) {
|
||||
arm.setPosition(arm.getPosition() - .05);
|
||||
}
|
||||
|
||||
if (currentGamepad1.b && !previousGamepad1.b) {
|
||||
claw.switchState();
|
||||
}
|
||||
|
||||
if (currentGamepad1.dpad_right && !previousGamepad1.dpad_right) {
|
||||
lift.toHighBucketPosition();
|
||||
}
|
||||
|
||||
if (currentGamepad1.dpad_left && !previousGamepad1.dpad_left) {
|
||||
lift.toLowBucketPosition();
|
||||
}
|
||||
|
||||
if (currentGamepad1.y && !previousGamepad1.y) {
|
||||
wrist.setPosition(wrist.getPosition() + .05);
|
||||
}
|
||||
|
||||
if (currentGamepad1.a && !previousGamepad1.a) {
|
||||
wrist.setPosition(wrist.getPosition() - .05);
|
||||
}
|
||||
|
||||
|
||||
if (currentGamepad1.right_bumper && !previousGamepad1.right_bumper) {
|
||||
lift.toHighBucketPosition();
|
||||
}
|
||||
|
||||
if (currentGamepad1.left_bumper && !previousGamepad1.left_bumper) {
|
||||
lift.toLowBucketPosition();
|
||||
|
||||
}
|
||||
if(currentGamepad1.left_trigger > 0){
|
||||
hang.setPower((double) currentGamepad1.left_trigger);
|
||||
}
|
||||
if(currentGamepad1.right_trigger > 0){
|
||||
hang.setPower((double) currentGamepad1.right_trigger);
|
||||
}
|
||||
|
||||
lift.update();
|
||||
|
||||
// Show the elapsed game time and wheel power.
|
||||
|
||||
telemetry.addData("Status", "Run Time: " + runtime.toString());
|
||||
telemetry.addData("Lift Drive Position", lift.getFixedPosition());
|
||||
telemetry.addData("Wrist Position", wrist.getPosition());
|
||||
telemetry.addData("Arm Position", arm.getPosition());
|
||||
telemetry.addData("Slide Ticks", lift.getCurrentPosition());
|
||||
telemetry.addData("Hook Ticks", hang.getCurrentPosition());
|
||||
telemetry.update();
|
||||
}
|
||||
}
|
||||
}
|
@ -1,8 +1,12 @@
|
||||
package org.firstinspires.ftc.teamcode.subsystem;
|
||||
|
||||
import static org.firstinspires.ftc.teamcode.PedroConstants.WRIST_SERVO;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.wristBackwardBucket;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.wristBucket;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.wristFloor;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.wristGrabBlueberrySkyhook;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.wristHangBlueberrySkyhook;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.wristInit;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.wristPickup;
|
||||
import static org.firstinspires.ftc.teamcode.configs.RobotConstants.wristSpeciemen;
|
||||
|
||||
@ -17,7 +21,7 @@ import com.qualcomm.robotcore.hardware.ServoImplEx;
|
||||
public class WristSubsystem {
|
||||
|
||||
public enum WristState {
|
||||
FLOOR, BUCKET, PICKUP, RUNG, SPECIMEN
|
||||
FLOOR, BUCKET, PICKUP, RUNG, SPECIMEN, GRAB_BLUEBERRY_SKYHOOK, HANG_BLUEBERRY_SKYHOOK, INIT, REVERSE_BUCKET
|
||||
}
|
||||
|
||||
public ServoImplEx wrist;
|
||||
@ -44,7 +48,16 @@ public class WristSubsystem {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
public void grabBlueberrySkyhook(){
|
||||
setState(WristState.GRAB_BLUEBERRY_SKYHOOK);
|
||||
wrist.setPosition(wristGrabBlueberrySkyhook);
|
||||
}
|
||||
|
||||
|
||||
public void hangBlueberrySkyhook(){
|
||||
setState(WristState.HANG_BLUEBERRY_SKYHOOK);
|
||||
wrist.setPosition(wristHangBlueberrySkyhook);
|
||||
}
|
||||
public void toFloorPosition() {
|
||||
setState(WristState.FLOOR);
|
||||
wrist.setPosition(wristFloor);
|
||||
@ -59,6 +72,15 @@ public class WristSubsystem {
|
||||
setState(WristState.PICKUP);
|
||||
wrist.setPosition(wristPickup);
|
||||
}
|
||||
public void toInitPosition(){
|
||||
setState(WristState.INIT);
|
||||
wrist.setPosition(wristInit);
|
||||
}
|
||||
public void InitAuto(){
|
||||
wrist.resetDeviceConfigurationForOpMode();
|
||||
toInitPosition();
|
||||
|
||||
}
|
||||
|
||||
public void setState(WristState wristState) {
|
||||
this.state = wristState;
|
||||
@ -71,12 +93,15 @@ public class WristSubsystem {
|
||||
toFloorPosition();
|
||||
}
|
||||
}
|
||||
|
||||
public void toReverseBucket(){
|
||||
wrist.setPosition(wristBackwardBucket);
|
||||
setState(WristState.REVERSE_BUCKET);
|
||||
}
|
||||
public WristState getState() {
|
||||
return this.state;
|
||||
}
|
||||
|
||||
public void init() {
|
||||
public void initTeleOp() {
|
||||
wrist.resetDeviceConfigurationForOpMode();
|
||||
toPickupPosition();
|
||||
}
|
||||
|
Reference in New Issue
Block a user