From 78cfcda534f94bfe594abbb8cb217d59813b80ac Mon Sep 17 00:00:00 2001 From: TruffleMedia Date: Wed, 6 Nov 2024 18:53:38 -0500 Subject: [PATCH] refined it a little --- .../org/pikerobodevils/frc24/robot/BUILD.java | 10 +++--- .../pikerobodevils/frc24/robot/Constants.java | 4 +-- .../frc24/robot/RobotContainer.java | 14 ++++---- .../frc24/robot/subsystems/Camera.java | 35 ------------------- .../robot/subsystems/drive/REALDriveIO.java | 4 +-- 5 files changed, 15 insertions(+), 52 deletions(-) delete mode 100644 src/main/java/org/pikerobodevils/frc24/robot/subsystems/Camera.java diff --git a/src/main/java/org/pikerobodevils/frc24/robot/BUILD.java b/src/main/java/org/pikerobodevils/frc24/robot/BUILD.java index e2073d9..d06535e 100644 --- a/src/main/java/org/pikerobodevils/frc24/robot/BUILD.java +++ b/src/main/java/org/pikerobodevils/frc24/robot/BUILD.java @@ -7,12 +7,12 @@ public final class BUILD { public static final String MAVEN_GROUP = ""; public static final String MAVEN_NAME = "FRC-1018-2024"; public static final String VERSION = "unspecified"; - public static final int GIT_REVISION = 75; - public static final String GIT_SHA = "296122e5781a48025866c08a3716e689c6ef3c05"; - public static final String GIT_DATE = "2024-10-22 19:38:08 EDT"; + public static final int GIT_REVISION = 76; + public static final String GIT_SHA = "d6d8d2403a159a9b96c9ad2532ddcfee70ab4531"; + public static final String GIT_DATE = "2024-10-30 15:02:59 EDT"; public static final String GIT_BRANCH = "master"; - public static final String BUILD_DATE = "2024-10-30 14:58:22 EDT"; - public static final long BUILD_UNIX_TIME = 1730314702442L; + public static final String BUILD_DATE = "2024-11-06 18:32:31 EST"; + public static final long BUILD_UNIX_TIME = 1730935951547L; public static final int DIRTY = 1; private BUILD(){} diff --git a/src/main/java/org/pikerobodevils/frc24/robot/Constants.java b/src/main/java/org/pikerobodevils/frc24/robot/Constants.java index 059baa5..8d7ee91 100644 --- a/src/main/java/org/pikerobodevils/frc24/robot/Constants.java +++ b/src/main/java/org/pikerobodevils/frc24/robot/Constants.java @@ -146,8 +146,8 @@ public static class DrivetrainConstants { public static final double kTrackwidthMeters = 0.6; // Double check this public static final DifferentialDriveKinematics kDriveKinematics = new DifferentialDriveKinematics(kTrackwidthMeters); - public static final double VOLTRAMP = 0.34; - public static final double SlewRateLimiter = 3; // FLAPJACK NEED THIS VERY MUCH + public static final double VOLTRAMP = 0.25; + public static final double SlewRateLimiter = 2; // FLAPJACK NEED THIS VERY MUCH } public static class ClimbConstants { diff --git a/src/main/java/org/pikerobodevils/frc24/robot/RobotContainer.java b/src/main/java/org/pikerobodevils/frc24/robot/RobotContainer.java index 38b4764..dbc2ffb 100644 --- a/src/main/java/org/pikerobodevils/frc24/robot/RobotContainer.java +++ b/src/main/java/org/pikerobodevils/frc24/robot/RobotContainer.java @@ -20,7 +20,6 @@ import org.pikerobodevils.frc24.robot.subsystems.Arm.SUBArm.ArmPosition; import org.pikerobodevils.frc24.robot.subsystems.Intake; import org.pikerobodevils.frc24.robot.subsystems.Shooter; -import org.pikerobodevils.frc24.robot.subsystems.Camera; import org.pikerobodevils.frc24.robot.subsystems.climb.BotGoClimb; import org.pikerobodevils.frc24.robot.subsystems.climb.ClimbIO; import org.pikerobodevils.frc24.robot.subsystems.drive.DriveIO; @@ -41,7 +40,6 @@ public class RobotContainer { private final Shooter shooterSubsystem = new Shooter(); private final BotGoClimb climber = new BotGoClimb(ClimbIO.isReal()); private final SUBArm arm = new SUBArm(ArmIO.isReal()); - private final Camera vision = new Camera(); private final ShuffleboardTab shuffleboard = Shuffleboard.getTab("Driver Dashboard"); // private final SendableChooser autoChooser = new SendableChooser<>(); @@ -58,13 +56,13 @@ public RobotContainer() { // drivetrain // .tankDriveCommand(controlboard::getSpeed, controlboard::getSpeedRIGHT)); - drivetrain - .arcadeDriveCommand(controlboard::getSpeed, controlboard::getTurn) - .withName("Default Drive Command")); + // drivetrain + // .arcadeDriveCommand(controlboard::getSpeed, controlboard::getTurn) + // .withName("Default Drive Command")); - // drivetrain - // .carDriveCommand(controlboard::getSpeed, controlboard::getTurn) - // .withName("Default Drive Command")); + drivetrain + .carDriveCommand(controlboard::getSpeed, controlboard::getTurn) + .withName("Default Drive Command")); NamedCommands.registerCommand("INTAKE", intakeSubsystem.runIntakeLIMIT()); NamedCommands.registerCommand("SPIN", shooterSubsystem.spinUp(ShooterConstants.SHOOT_SPEED)); diff --git a/src/main/java/org/pikerobodevils/frc24/robot/subsystems/Camera.java b/src/main/java/org/pikerobodevils/frc24/robot/subsystems/Camera.java deleted file mode 100644 index c332959..0000000 --- a/src/main/java/org/pikerobodevils/frc24/robot/subsystems/Camera.java +++ /dev/null @@ -1,35 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -package org.pikerobodevils.frc24.robot.subsystems; - -import edu.wpi.first.networktables.NetworkTable; -import edu.wpi.first.networktables.NetworkTableEntry; -import edu.wpi.first.networktables.NetworkTableInstance; -import edu.wpi.first.wpilibj2.command.SubsystemBase; - -public class Camera extends SubsystemBase { - /** Creates a new Vision. */ - NetworkTable table = NetworkTableInstance.getDefault().getTable("limelight"); - - NetworkTableEntry tx = table.getEntry("tx"); - NetworkTableEntry ty = table.getEntry("ty"); - NetworkTableEntry ta = table.getEntry("ta"); - - public Camera() {} - - public double getTx() { - return tx.getDouble(0.0); - } - - public double getTy() { - return ty.getDouble(0.0); - } - - @Override - public void periodic() { - // This method will be called once per scheduler run - - } -} diff --git a/src/main/java/org/pikerobodevils/frc24/robot/subsystems/drive/REALDriveIO.java b/src/main/java/org/pikerobodevils/frc24/robot/subsystems/drive/REALDriveIO.java index 37eb1b0..2f403ce 100644 --- a/src/main/java/org/pikerobodevils/frc24/robot/subsystems/drive/REALDriveIO.java +++ b/src/main/java/org/pikerobodevils/frc24/robot/subsystems/drive/REALDriveIO.java @@ -54,8 +54,8 @@ public REALDriveIO() { // leftLeader.enableVoltageCompensation(12.0); //bad for flapjack :( // rightLeader.enableVoltageCompensation(12.0); //bad for flapjack :( - leftLeader.setSmartCurrentLimit(40,DrivetrainConstants.CURRENT_LIMIT); - rightLeader.setSmartCurrentLimit(40,DrivetrainConstants.CURRENT_LIMIT); + leftLeader.setSmartCurrentLimit(DrivetrainConstants.CURRENT_LIMIT); + rightLeader.setSmartCurrentLimit(DrivetrainConstants.CURRENT_LIMIT); leftLeader.burnFlash();