mirror of
https://github.com/Team4388/Robot-Essentials.git
synced 2026-06-09 00:38:01 -06:00
New Code
This commit is contained in:
Vendored
+2
-1
@@ -58,5 +58,6 @@
|
|||||||
"edu.wpi.first.math.**.struct.*",
|
"edu.wpi.first.math.**.struct.*",
|
||||||
],
|
],
|
||||||
"java.jdt.ls.vmargs": "-XX:+UseParallelGC -XX:GCTimeRatio=4 -XX:AdaptiveSizePolicyWeight=90 -Dsun.zip.disableMemoryMapping=true -Xmx2G -Xms100m -Xlog:disable",
|
"java.jdt.ls.vmargs": "-XX:+UseParallelGC -XX:GCTimeRatio=4 -XX:AdaptiveSizePolicyWeight=90 -Dsun.zip.disableMemoryMapping=true -Xmx2G -Xms100m -Xlog:disable",
|
||||||
"wpilib.autoStartRioLog": false
|
"wpilib.autoStartRioLog": false,
|
||||||
|
"java.debug.settings.onBuildFailureProceed": true
|
||||||
}
|
}
|
||||||
|
|||||||
File diff suppressed because one or more lines are too long
@@ -0,0 +1,54 @@
|
|||||||
|
{
|
||||||
|
"version": "2025.0",
|
||||||
|
"waypoints": [
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 2.0,
|
||||||
|
"y": 7.0
|
||||||
|
},
|
||||||
|
"prevControl": null,
|
||||||
|
"nextControl": {
|
||||||
|
"x": 3.0,
|
||||||
|
"y": 7.0
|
||||||
|
},
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": null
|
||||||
|
},
|
||||||
|
{
|
||||||
|
"anchor": {
|
||||||
|
"x": 4.0,
|
||||||
|
"y": 6.0
|
||||||
|
},
|
||||||
|
"prevControl": {
|
||||||
|
"x": 3.0,
|
||||||
|
"y": 6.0
|
||||||
|
},
|
||||||
|
"nextControl": null,
|
||||||
|
"isLocked": false,
|
||||||
|
"linkedName": null
|
||||||
|
}
|
||||||
|
],
|
||||||
|
"rotationTargets": [],
|
||||||
|
"constraintZones": [],
|
||||||
|
"pointTowardsZones": [],
|
||||||
|
"eventMarkers": [],
|
||||||
|
"globalConstraints": {
|
||||||
|
"maxVelocity": 3.0,
|
||||||
|
"maxAcceleration": 3.0,
|
||||||
|
"maxAngularVelocity": 540.0,
|
||||||
|
"maxAngularAcceleration": 720.0,
|
||||||
|
"nominalVoltage": 12.0,
|
||||||
|
"unlimited": false
|
||||||
|
},
|
||||||
|
"goalEndState": {
|
||||||
|
"velocity": 0,
|
||||||
|
"rotation": 0.0
|
||||||
|
},
|
||||||
|
"reversed": false,
|
||||||
|
"folder": null,
|
||||||
|
"idealStartingState": {
|
||||||
|
"velocity": 0,
|
||||||
|
"rotation": 0.0
|
||||||
|
},
|
||||||
|
"useDefaultConstraints": true
|
||||||
|
}
|
||||||
@@ -0,0 +1,32 @@
|
|||||||
|
{
|
||||||
|
"robotWidth": 0.9,
|
||||||
|
"robotLength": 0.9,
|
||||||
|
"holonomicMode": true,
|
||||||
|
"pathFolders": [],
|
||||||
|
"autoFolders": [],
|
||||||
|
"defaultMaxVel": 3.0,
|
||||||
|
"defaultMaxAccel": 3.0,
|
||||||
|
"defaultMaxAngVel": 540.0,
|
||||||
|
"defaultMaxAngAccel": 720.0,
|
||||||
|
"defaultNominalVoltage": 12.0,
|
||||||
|
"robotMass": 74.088,
|
||||||
|
"robotMOI": 6.883,
|
||||||
|
"robotTrackwidth": 0.546,
|
||||||
|
"driveWheelRadius": 0.048,
|
||||||
|
"driveGearing": 5.143,
|
||||||
|
"maxDriveSpeed": 5.45,
|
||||||
|
"driveMotorType": "krakenX60",
|
||||||
|
"driveCurrentLimit": 60.0,
|
||||||
|
"wheelCOF": 1.2,
|
||||||
|
"flModuleX": 0.273,
|
||||||
|
"flModuleY": 0.273,
|
||||||
|
"frModuleX": 0.273,
|
||||||
|
"frModuleY": -0.273,
|
||||||
|
"blModuleX": -0.273,
|
||||||
|
"blModuleY": 0.273,
|
||||||
|
"brModuleX": -0.273,
|
||||||
|
"brModuleY": -0.273,
|
||||||
|
"bumperOffsetX": 0.0,
|
||||||
|
"bumperOffsetY": 0.0,
|
||||||
|
"robotFeatures": []
|
||||||
|
}
|
||||||
@@ -40,9 +40,6 @@ import frc4388.robot.commands.MoveUntilSuply;
|
|||||||
import frc4388.robot.commands.alignment.DriveToReef;
|
import frc4388.robot.commands.alignment.DriveToReef;
|
||||||
import frc4388.robot.commands.alignment.DriveUntilLiDAR;
|
import frc4388.robot.commands.alignment.DriveUntilLiDAR;
|
||||||
import frc4388.robot.commands.alignment.LidarAlign;
|
import frc4388.robot.commands.alignment.LidarAlign;
|
||||||
import frc4388.robot.commands.wait.waitElevatorRefrence;
|
|
||||||
import frc4388.robot.commands.wait.waitEndefectorRefrence;
|
|
||||||
import frc4388.robot.commands.wait.waitFeedCoral;
|
|
||||||
import frc4388.robot.commands.wait.waitSupplier;
|
import frc4388.robot.commands.wait.waitSupplier;
|
||||||
import frc4388.robot.constants.Constants;
|
import frc4388.robot.constants.Constants;
|
||||||
import frc4388.robot.constants.Constants.AutoConstants;
|
import frc4388.robot.constants.Constants.AutoConstants;
|
||||||
@@ -55,8 +52,8 @@ import com.pathplanner.lib.commands.PathPlannerAuto;
|
|||||||
|
|
||||||
// Subsystems
|
// Subsystems
|
||||||
import frc4388.robot.subsystems.LED;
|
import frc4388.robot.subsystems.LED;
|
||||||
import frc4388.robot.subsystems.elevator.Elevator;
|
//Rimport frc4388.robot.subsystems.elevator.Elevator;
|
||||||
import frc4388.robot.subsystems.elevator.Elevator.CoordinationState;
|
//Rimport frc4388.robot.subsystems.elevator.Elevator.CoordinationState;
|
||||||
import frc4388.robot.subsystems.lidar.LiDAR;
|
import frc4388.robot.subsystems.lidar.LiDAR;
|
||||||
import frc4388.robot.subsystems.swerve.SwerveDrive;
|
import frc4388.robot.subsystems.swerve.SwerveDrive;
|
||||||
import frc4388.robot.subsystems.vision.Vision;
|
import frc4388.robot.subsystems.vision.Vision;
|
||||||
@@ -80,7 +77,7 @@ public class RobotContainer {
|
|||||||
/* Subsystems */
|
/* Subsystems */
|
||||||
public final LED m_robotLED = new LED();
|
public final LED m_robotLED = new LED();
|
||||||
public final Vision m_vision = new Vision(m_robotMap.leftCamera, m_robotMap.rightCamera);
|
public final Vision m_vision = new Vision(m_robotMap.leftCamera, m_robotMap.rightCamera);
|
||||||
public final Elevator m_robotElevator = new Elevator(m_robotMap.elevatorIO, m_robotLED);
|
//Rpublic final Elevator m_robotElevator = new Elevator(m_robotMap.elevatorIO, m_robotLED);
|
||||||
public final SwerveDrive m_robotSwerveDrive = new SwerveDrive(m_robotMap.swerveDrivetrain, m_vision);
|
public final SwerveDrive m_robotSwerveDrive = new SwerveDrive(m_robotMap.swerveDrivetrain, m_vision);
|
||||||
// public final SwerveDrive m_robotSwerveDrive = new SwerveDrive(m_robotMap.swerveDrivetrain);
|
// public final SwerveDrive m_robotSwerveDrive = new SwerveDrive(m_robotMap.swerveDrivetrain);
|
||||||
|
|
||||||
|
|||||||
@@ -17,12 +17,9 @@ import com.ctre.phoenix6.hardware.CANcoder;
|
|||||||
import com.ctre.phoenix6.swerve.SwerveDrivetrain;
|
import com.ctre.phoenix6.swerve.SwerveDrivetrain;
|
||||||
import edu.wpi.first.math.geometry.Rotation2d;
|
import edu.wpi.first.math.geometry.Rotation2d;
|
||||||
import edu.wpi.first.wpilibj.DigitalInput;
|
import edu.wpi.first.wpilibj.DigitalInput;
|
||||||
import frc4388.robot.constants.Constants.ElevatorConstants;
|
|
||||||
import frc4388.robot.constants.Constants.LiDARConstants;
|
import frc4388.robot.constants.Constants.LiDARConstants;
|
||||||
import frc4388.robot.constants.Constants.SimConstants;
|
import frc4388.robot.constants.Constants.SimConstants;
|
||||||
import frc4388.robot.constants.Constants.VisionConstants;
|
import frc4388.robot.constants.Constants.VisionConstants;
|
||||||
import frc4388.robot.subsystems.elevator.ElevatorIO;
|
|
||||||
import frc4388.robot.subsystems.elevator.ElevatorReal;
|
|
||||||
import frc4388.robot.subsystems.lidar.LiDAR;
|
import frc4388.robot.subsystems.lidar.LiDAR;
|
||||||
import frc4388.robot.subsystems.lidar.LidarIO;
|
import frc4388.robot.subsystems.lidar.LidarIO;
|
||||||
import frc4388.robot.subsystems.lidar.LidarReal;
|
import frc4388.robot.subsystems.lidar.LidarReal;
|
||||||
@@ -59,8 +56,6 @@ public class RobotMap {
|
|||||||
/* Swreve Drive Subsystem */
|
/* Swreve Drive Subsystem */
|
||||||
public final SwerveIO swerveDrivetrain;
|
public final SwerveIO swerveDrivetrain;
|
||||||
|
|
||||||
/* Elevator Subsystem */
|
|
||||||
public final ElevatorIO elevatorIO;
|
|
||||||
|
|
||||||
public RobotMap(SimConstants.Mode mode) {
|
public RobotMap(SimConstants.Mode mode) {
|
||||||
switch (mode) {
|
switch (mode) {
|
||||||
@@ -88,25 +83,13 @@ public class RobotMap {
|
|||||||
|
|
||||||
swerveDrivetrain = new SwerveReal(swerveDrivetrainReal);
|
swerveDrivetrain = new SwerveReal(swerveDrivetrainReal);
|
||||||
|
|
||||||
// Configure elevator
|
|
||||||
|
|
||||||
TalonFX elevator = new TalonFX(ElevatorConstants.ELEVATOR_ID.id);
|
|
||||||
TalonFX endeffector = new TalonFX(ElevatorConstants.ENDEFFECTOR_ID.id);
|
|
||||||
|
|
||||||
|
|
||||||
DigitalInput basinLimitSwitch = new DigitalInput(ElevatorConstants.BASIN_LIMIT_SWITCH);
|
|
||||||
DigitalInput endeffectorLimitSwitch = new DigitalInput(ElevatorConstants.ENDEFFECTOR_LIMIT_SWITCH);
|
|
||||||
DigitalInput IRIntakeBeam = new DigitalInput(ElevatorConstants.INTAKE_LIMIT_SWITCH);
|
|
||||||
|
|
||||||
elevatorIO = new ElevatorReal(elevator, endeffector, basinLimitSwitch, endeffectorLimitSwitch, IRIntakeBeam);
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// Fault
|
// Fault
|
||||||
FaultPidgeon2.addDevice(swerveDrivetrainReal.getPigeon2(), "Gyro");
|
FaultPidgeon2.addDevice(swerveDrivetrainReal.getPigeon2(), "Gyro");
|
||||||
|
|
||||||
FaultTalonFX.addDevice(elevator, "Elevator");
|
//FaultTalonFX.addDevice(elevator, "Elevator");
|
||||||
FaultTalonFX.addDevice(endeffector, "Endeffector");
|
//FaultTalonFX.addDevice(endeffector, "Endeffector");
|
||||||
|
|
||||||
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getDriveMotor(), "Module 0 Drive");
|
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getDriveMotor(), "Module 0 Drive");
|
||||||
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getSteerMotor(), "Module 0 Steer");
|
FaultTalonFX.addDevice(swerveDrivetrainReal.getModule(0).getSteerMotor(), "Module 0 Steer");
|
||||||
@@ -130,7 +113,6 @@ public class RobotMap {
|
|||||||
reefLidar = new LidarIO() {};
|
reefLidar = new LidarIO() {};
|
||||||
reverseLidar = new LidarIO() {};
|
reverseLidar = new LidarIO() {};
|
||||||
swerveDrivetrain = new SwerveIO() {};
|
swerveDrivetrain = new SwerveIO() {};
|
||||||
elevatorIO = new ElevatorIO() {};
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|||||||
@@ -1,4 +1,4 @@
|
|||||||
package frc4388.robot.commands.autos;
|
package frc4388.robot.commands.Autos;
|
||||||
// package frc4388.robot.commands.Autos;
|
// package frc4388.robot.commands.Autos;
|
||||||
|
|
||||||
// import java.io.File;
|
// import java.io.File;
|
||||||
|
|||||||
@@ -2,7 +2,7 @@
|
|||||||
// Open Source Software; you can modify and/or share it under the terms of
|
// 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.
|
// the WPILib BSD license file in the root directory of this project.
|
||||||
|
|
||||||
package frc4388.robot.commands.swerve;
|
package frc4388.robot.commands.Swerve;
|
||||||
|
|
||||||
import edu.wpi.first.math.geometry.Translation2d;
|
import edu.wpi.first.math.geometry.Translation2d;
|
||||||
import frc4388.robot.commands.PID;
|
import frc4388.robot.commands.PID;
|
||||||
|
|||||||
@@ -1,4 +1,4 @@
|
|||||||
package frc4388.robot.commands.swerve;
|
package frc4388.robot.commands.Swerve;
|
||||||
|
|
||||||
import java.io.FileInputStream;
|
import java.io.FileInputStream;
|
||||||
import java.util.ArrayList;
|
import java.util.ArrayList;
|
||||||
|
|||||||
@@ -1,4 +1,4 @@
|
|||||||
package frc4388.robot.commands.swerve;
|
package frc4388.robot.commands.Swerve;
|
||||||
|
|
||||||
import java.io.FileOutputStream;
|
import java.io.FileOutputStream;
|
||||||
import java.util.ArrayList;
|
import java.util.ArrayList;
|
||||||
|
|||||||
@@ -5,14 +5,14 @@ package frc4388.robot.constants;
|
|||||||
*/
|
*/
|
||||||
public final class BuildConstants {
|
public final class BuildConstants {
|
||||||
public static final String MAVEN_GROUP = "";
|
public static final String MAVEN_GROUP = "";
|
||||||
public static final String MAVEN_NAME = "2025RidgeScape";
|
public static final String MAVEN_NAME = "Robot-Essentials";
|
||||||
public static final String VERSION = "unspecified";
|
public static final String VERSION = "unspecified";
|
||||||
public static final int GIT_REVISION = 173;
|
public static final int GIT_REVISION = 123;
|
||||||
public static final String GIT_SHA = "2b7bb1224195b9e001e60b895ee04d63abdfc513";
|
public static final String GIT_SHA = "56841636f984f1a691134b4f1ae8862353846b54";
|
||||||
public static final String GIT_DATE = "2025-07-17 09:15:19 MDT";
|
public static final String GIT_DATE = "2025-10-30 16:40:04 MDT";
|
||||||
public static final String GIT_BRANCH = "advantagekit";
|
public static final String GIT_BRANCH = "Confiruagble-Contants";
|
||||||
public static final String BUILD_DATE = "2025-07-17 11:55:31 MDT";
|
public static final String BUILD_DATE = "2025-10-30 17:42:04 MDT";
|
||||||
public static final long BUILD_UNIX_TIME = 1752774931371L;
|
public static final long BUILD_UNIX_TIME = 1761867724046L;
|
||||||
public static final int DIRTY = 1;
|
public static final int DIRTY = 1;
|
||||||
|
|
||||||
private BuildConstants(){}
|
private BuildConstants(){}
|
||||||
|
|||||||
@@ -69,6 +69,8 @@ public final class Constants {
|
|||||||
public static final double MIN_ROT_PID_OUTPUT = 0.0;
|
public static final double MIN_ROT_PID_OUTPUT = 0.0;
|
||||||
|
|
||||||
public static final double VELOCITY_THRESHHOLD = 0.01;
|
public static final double VELOCITY_THRESHHOLD = 0.01;
|
||||||
|
public static final double X_SCORING_POSITION_OFFSET = 2;
|
||||||
|
public static final double STOP_VELOCITY = 2;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@@ -0,0 +1,31 @@
|
|||||||
|
package frc4388.utility.configurable;
|
||||||
|
import frc4388.robot.constants.Constants;
|
||||||
|
import edu.wpi.first.networktables.GenericEntry;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.BuiltInWidgets;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.ComplexWidget;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||||
|
import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
|
||||||
|
|
||||||
|
public class TunableNumber {
|
||||||
|
private final String name;
|
||||||
|
private final ShuffleboardTab tab;
|
||||||
|
private final double defaultValue;
|
||||||
|
private GenericEntry entry;
|
||||||
|
|
||||||
|
public TunableNumber(String tabName, String name, double defaultValue) {
|
||||||
|
this.name = name;
|
||||||
|
this.tab = Shuffleboard.getTab(tabName);
|
||||||
|
this.defaultValue = defaultValue;
|
||||||
|
this.entry = tab.add(name, defaultValue)
|
||||||
|
.withWidget(BuiltInWidgets.kTextView)
|
||||||
|
.getEntry();
|
||||||
|
}
|
||||||
|
|
||||||
|
public double get() {
|
||||||
|
return entry.getDouble(defaultValue);
|
||||||
|
}
|
||||||
|
|
||||||
|
public void set(double value) {
|
||||||
|
entry.setDouble(value);
|
||||||
|
}
|
||||||
|
}
|
||||||
Reference in New Issue
Block a user