teleop testing

This commit is contained in:
sihan 2024-03-07 17:16:48 -06:00
parent e2223813dc
commit 8aea72a9cf
5 changed files with 26 additions and 16 deletions

View File

@ -34,6 +34,7 @@ import static org.firstinspires.ftc.teamcode.util.Constants.SLIDERIGHT;
import static org.firstinspires.ftc.teamcode.util.Constants.WRIST;
import com.acmerobotics.dashboard.config.Config;
import com.arcrobotics.ftclib.controller.PController;
import com.arcrobotics.ftclib.gamepad.GamepadEx;
import com.arcrobotics.ftclib.gamepad.GamepadKeys;
import com.qualcomm.hardware.rev.RevBlinkinLedDriver;
@ -84,7 +85,7 @@ public class Robot {
}
public static class Slides {
private DcMotor slidesRight = null;
public DcMotor slidesRight = null;
public DcMotor slidesLeft = null;
public Slides init(HardwareMap hardwareMap) {
@ -92,8 +93,8 @@ public class Robot {
this.slidesRight = hardwareMap.get(DcMotor.class, SLIDERIGHT);
this.slidesLeft.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
this.slidesRight.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
this.slidesRight.setTargetPosition(0);
this.slidesLeft.setTargetPosition(0);
this.slidesRight.setTargetPosition(0);
this.slidesRight.setMode(DcMotor.RunMode.RUN_TO_POSITION);
this.slidesLeft.setMode(DcMotor.RunMode.RUN_TO_POSITION);
@ -195,6 +196,7 @@ public class Robot {
public static class Arm {
private Servo leftArm;
private Servo rightArm;
private PController armController;
public Arm init(HardwareMap hardwareMap) {
@ -336,7 +338,7 @@ public class Robot {
}
break;
case OPEN:
delay = runtime + .2;
delay = runtime + .3;
this.getClaw().open();
pickupMacroState = pickupMacroStates.DROP;
break;
@ -350,7 +352,7 @@ public class Robot {
case CLOSE:
if (runtime > delay) {
this.getClaw().close();
delay= runtime + .1;
delay= runtime + .3;
pickupMacroState = pickupMacroStates.NEUTRAL;
}
break;

View File

@ -45,7 +45,7 @@ public class DriveConstants {
* convenience. Make sure to exclude any gear ratio included in MOTOR_CONFIG from GEAR_RATIO.
*/
public static double WHEEL_RADIUS = 1.88976; // in
public static double GEAR_RATIO = 1; // output (wheel) speed / input (motor) speed
public static double GEAR_RATIO = 16f/24f; // output (wheel) speed / input (motor) speed
public static double TRACK_WIDTH = 12.438; // in
// public static double WHEEL_RADIUS = 1.88976; // in

View File

@ -38,11 +38,11 @@ public class TwoWheelTrackingLocalizer extends TwoTrackingWheelLocalizer {
public static double WHEEL_RADIUS = 0.944882; // in
public static double GEAR_RATIO = 1; // output (wheel) speed / input (encoder) speed
public static double PARALLEL_X = 129.5; // X is the up and down direction
public static double PARALLEL_Y = -4.118; // Y is the strafe direction
public static double PARALLEL_X = 4.84; // X is the up and down direction
public static double PARALLEL_Y = 3.94; // Y is the strafe direction
public static double PERPENDICULAR_X = 3.209;
public static double PERPENDICULAR_Y = -.199;
public static double PERPENDICULAR_X = 5.10;
public static double PERPENDICULAR_Y = 0.20;
public static double X_MULTIPLIER = 1; // Multiplier in the X direction
public static double Y_MULTIPLIER = 1; // Multiplier in the Y direction

View File

@ -6,6 +6,7 @@ import com.qualcomm.robotcore.eventloop.opmode.OpMode;
import org.firstinspires.ftc.teamcode.hardware.Robot;
import org.firstinspires.ftc.teamcode.hardware.roadrunner.drive.MecanumDrive;
import org.firstinspires.ftc.teamcode.util.Configurables;
@com.qualcomm.robotcore.eventloop.opmode.TeleOp(name = "Main TeleOp", group = "Development")
public class MainTeleOp extends OpMode {
@ -43,6 +44,11 @@ public class MainTeleOp extends OpMode {
|| controller2.wasJustReleased(GamepadKeys.Button.DPAD_LEFT)) {
this.robot.getSlides().slideStop();
}
if (gamepad2.left_trigger > .5){
Configurables.SLIDE_POWER_UP = .3;
} else {
Configurables.SLIDE_POWER_UP = .7;
}
////Macros
this.robot.pickupMacro(controller2, getRuntime()); //DPADDOWN
//
@ -71,9 +77,11 @@ public class MainTeleOp extends OpMode {
this.robot.getHang().hangPlane();
}
// int Position = this.robot.getHang().hangRight.getCurrentPosition();
// telemetry.addData("position",(Position));
// telemetry.update();
int PositionLeft = this.robot.getSlides().slidesLeft.getCurrentPosition();
telemetry.addData("positionLeft",(PositionLeft));
int PositionRight = this.robot.getSlides().slidesRight.getCurrentPosition();
telemetry.addData("positionRight",(PositionRight));
telemetry.update();
//
//Plane
if (plane) {

View File

@ -18,10 +18,10 @@ public class Configurables {
public static double ARMSCORE = 0.4;
public static double ARMACCSCORE = .57;
public static double ARMPICKUPSTACK = 0.815;
public static double PICKUP = 0.835;
public static double PICKUP = 0.94;
public static double WRISTPICKUP = 0.3;
public static double WRISTSCORE = .98;
public static double OPEN = 0.483;
public static double OPEN = 0.481;
public static double BIGOPEN = 0.65;
public static double CLOSE = .51;
public static double PLANELOCK = 0.1;
@ -34,8 +34,8 @@ public class Configurables {
public static double SLOWMODE_TURN = 0.3;
//Motor Positions
public static double SLIDE_POWER_UP = 1;
public static double SLIDE_POWER_DOWN = .7;
public static double SLIDE_POWER_UP = .7;
public static double SLIDE_POWER_DOWN = .5;
public static int SLIDELAYERONE = 60;
public static int SLIDEAUTOSTACKS = 250;
public static int SLIDEUP = 1150;