diff --git a/build.gradle b/build.gradle index 1478f2b..d141f06 100644 --- a/build.gradle +++ b/build.gradle @@ -68,7 +68,7 @@ dependencies { simulationRelease wpi.sim.enableRelease() testImplementation 'org.junit.jupiter:junit-jupiter:5.10.1' - testRuntimeOnly 'org.junit.platform:junit-platform-launcher' + //testRuntimeOnly 'org.junit.platform:junit-platform-launcher' } test { diff --git a/networktables.json b/networktables.json new file mode 100644 index 0000000..fe51488 --- /dev/null +++ b/networktables.json @@ -0,0 +1 @@ +[] diff --git a/simgui-ds.json b/simgui-ds.json new file mode 100644 index 0000000..69b1a3c --- /dev/null +++ b/simgui-ds.json @@ -0,0 +1,97 @@ +{ + "keyboardJoysticks": [ + { + "axisConfig": [ + { + "decKey": 65, + "incKey": 68 + }, + { + "decKey": 87, + "incKey": 83 + }, + { + "decKey": 69, + "decayRate": 0.0, + "incKey": 82, + "keyRate": 0.009999999776482582 + } + ], + "axisCount": 3, + "buttonCount": 4, + "buttonKeys": [ + 90, + 88, + 67, + 86 + ], + "povConfig": [ + { + "key0": 328, + "key135": 323, + "key180": 322, + "key225": 321, + "key270": 324, + "key315": 327, + "key45": 329, + "key90": 326 + } + ], + "povCount": 1 + }, + { + "axisConfig": [ + { + "decKey": 74, + "incKey": 76 + }, + { + "decKey": 73, + "incKey": 75 + } + ], + "axisCount": 2, + "buttonCount": 4, + "buttonKeys": [ + 77, + 44, + 46, + 47 + ], + "povCount": 0 + }, + { + "axisConfig": [ + { + "decKey": 263, + "incKey": 262 + }, + { + "decKey": 265, + "incKey": 264 + } + ], + "axisCount": 2, + "buttonCount": 6, + "buttonKeys": [ + 260, + 268, + 266, + 261, + 269, + 267 + ], + "povCount": 0 + }, + { + "axisCount": 0, + "buttonCount": 0, + "povCount": 0 + } + ], + "robotJoysticks": [ + { + "guid": "Keyboard0" + } + ] +} diff --git a/simgui.json b/simgui.json new file mode 100644 index 0000000..905d0ec --- /dev/null +++ b/simgui.json @@ -0,0 +1,18 @@ +{ + "NTProvider": { + "types": { + "/FMSInfo": "FMSInfo", + "/SmartDashboard/Field": "Field2d" + }, + "windows": { + "/SmartDashboard/Field": { + "window": { + "visible": true + } + } + } + }, + "NetworkTables Info": { + "visible": true + } +} diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java new file mode 100644 index 0000000..882171d --- /dev/null +++ b/src/main/java/frc/robot/Constants.java @@ -0,0 +1,161 @@ +package frc.robot; + +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.networktables.NetworkTableInstance; +import edu.wpi.first.math.kinematics.SwerveDriveKinematics; + +/** + * The Constants class provides a convenient place for teams to hold robot-wide + * numerical or boolean + * constants. This class should not be used for any other purpose. All constants + * should be declared + * globally (i.e. public static). Do not put anything functional in this class. + * + *

+ * It is advised to statically import this class (or one of its inner classes) + * wherever the + * constants are needed, to reduce verbosity. + */ +public final class Constants { + + /** + * Input/Output constants + */ + public static class IOConstants { + public static final int kDriverControllerPort = 0; + + public static final double kControllerDeadband = 0.2; + public static final double kSlowModeScalar = 0.8; + } + + public static final class DriveConstants { + // TODO: set motor and encoder constants + public static final int kFrontLeftDriveMotorPort = 1; + public static final int kRearLeftDriveMotorPort = 3; + public static final int kFrontRightDriveMotorPort = 5; + public static final int kRearRightDriveMotorPort = 7; + + public static final int kFrontLeftTurningMotorPort = 2; + public static final int kRearLeftTurningMotorPort = 4; + public static final int kFrontRightTurningMotorPort = 6; + public static final int kRearRightTurningMotorPort = 8; + + public static final int kFrontLeftTurningEncoderPort = 9; + public static final int kRearLeftTurningEncoderPort = 10; + public static final int kFrontRightTurningEncoderPort = 11; + public static final int kRearRightTurningEncoderPort = 12; + + public static final double kFrontLeftTurningEncoderOffset = 0; + public static final double kRearLeftTurningEncoderOffset = 0; + public static final double kFrontRightTurningEncoderOffset = 0; + public static final double kRearRightTurningEncoderOffset = 0; + + // TODO: Test motor orientations before driving on an actual robot + public static final boolean kFrontLeftDriveMotorReversed = false; + public static final boolean kRearLeftDriveMotorReversed = false; + public static final boolean kFrontRightDriveMotorReversed = true; + public static final boolean kRearRightDriveMotorReversed = true; + + /** Distance between centers of right and left wheels on robot (in meters). */ + public static final double kTrackWidth = 0.5; + + /** Distance between front and back wheels on robot (in meters). */ + public static final double kWheelBase = 0.5; + + /** Diameter of each wheel in the SDS MK4i swerve module (in meters) */ + public static final double kWheelDiameterMeters = 0.1; + + /** Gear ratio between the motor and the wheel. */ + public static final double kDrivingGearRatio = 8.14; // SDS MK4i's in L1 configuration + + // TODO: Tune this PID before running on a robot on the ground + public static final double kPModuleTurningController = 0.3; + + public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics( + new Translation2d(kWheelBase / 2, kTrackWidth / 2), + new Translation2d(kWheelBase / 2, -kTrackWidth / 2), + new Translation2d(-kWheelBase / 2, kTrackWidth / 2), + new Translation2d(-kWheelBase / 2, -kTrackWidth / 2)); + + /** For a a SDS Mk4i L1 swerve base with Neos */ + public static final double kMaxSpeedMetersPerSecond = 3.6576; + /** For a a SDS Mk4i L1 swerve base with Neos */ + public static final double kMaxAngularSpeedRadiansPerSecond = 15.24 / 3; + + /** Heading Correction */ + public static final double kHeadingCorrectionTurningStopTime = 0.2; + // TODO: Tune this PID before running on a robot on the ground + public static final double kPHeadingCorrectionController = 5; + } + + public final static class TagAlignConstants { + public final static double kTagPIDkPxy = 0; // xy PID constants + public final static double kTagPIDkIxy = 0; + public final static double kTagPIDkDxy = 0; + + public final static double kTagPIDkPomega = 0; // omega PID constants + public final static double kTagPIDkIomega = 0; + public final static double kTagPIDkDomega = 0; + + public static final Pose2d[] kTargetPoses = new Pose2d[] { + new Pose2d(new Translation2d(585.75, 313), new Rotation2d(Math.toRadians(270))), //Amp //Change y based on length of robot using 28in long, Red side + + //Asumed that these are positions for a single source, so that you have 3 positions for the source on the left + //Left , center, right, all on same obj //TODO: Make sure these work with robot demensions/bumpers + new Pose2d(new Translation2d(590, 9), new Rotation2d(Math.toRadians(120))), //SourceLeft + new Pose2d(new Translation2d(631.125, 20.625), new Rotation2d(Math.toRadians(120))), //etc. + new Pose2d(new Translation2d(637, 34), new Rotation2d(Math.toRadians(120))), + + new Pose2d(new Translation2d(598.125, 222.75), new Rotation2d(0)), //TODO: Check this (Red speaker) + new Pose2d(new Translation2d(464.5, 117.315), new Rotation2d(Math.toRadians(300))), + new Pose2d(new Translation2d(421.115, 161.62), new Rotation2d(Math.toRadians(180))), + new Pose2d(new Translation2d(459.75, 197.725), new Rotation2d(Math.toRadians(60))), + new Pose2d(new Translation2d(186.855, 195.662), new Rotation2d(Math.toRadians(120))), + new Pose2d(new Translation2d(182.245, 161.62), new Rotation2d(0)), + new Pose2d(new Translation2d(193.875, 123.75), new Rotation2d(Math.toRadians(240))), + new Pose2d(new Translation2d(78.375, 165), new Rotation2d(0)), + new Pose2d(new Translation2d(330, 165), new Rotation2d(0)), //Switch angle by 1pi if you want opposite rotation + new Pose2d(new Translation2d(585.75, 165), new Rotation2d(0)) //StageCenterRight + }; // Poses are in the same order as the enumerator. + // TODO: populate poses + + //TODO: tune all these parameters + public static final double kTolxy = 0.1; // tolerance in meters for x and y + public static final double kTolomega = 0.1; // tolerance in radians for omega + public static final double kConsectol = 10; // onsecutive cycles of being within tolerance needed to end command + public static final double kMinProx = 1; // minimum proximity radius in meters. + // To avoid accidents, the robot must be + // within the minimum proximity for the tag alignment command to run. + // If the robot exceeds the minimum proximity the command will finish + + public static enum AlignPosition { // DON'T CHANGE THE ORDER OF THESE. Add new items to the end + Amp, + SourceLeft, + SourceCenter, + SourceRight, + Speaker, + StageLeftLeft, // The left side of the left stage + StageLeftCenter, // the center side of the left stage + StageLeftRight, // etc. + StageRightLeft, + StageRightCenter, + StageRightRight, + StageCenterLeft, + StageCenterCenter, + StageCenterRight // the right side of the center stage + } //stage left, stage right, and stage center are the locations written in the game manual pg. 28 + + public static final double kFieldWidth = 651.25 * 0.0254; // Width of the field in meters + + public static final NetworkTableInstance kNTInstance = NetworkTableInstance.create(); // Ideally all network table + // instances should be put in + // a wrapper and only the + // default instance should be + // used. + // TODO: write unit tests that write to NT limelight and verify PID output + // direction is correct. Needs to be implemented after drive since it uses pose + // estimator. + } +} diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index de2c9d0..07889d9 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -4,15 +4,70 @@ package frc.robot; +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.wpilibj.XboxController; +import edu.wpi.first.wpilibj.XboxController.Button; import edu.wpi.first.wpilibj2.command.Command; import edu.wpi.first.wpilibj2.command.Commands; +import edu.wpi.first.wpilibj2.command.InstantCommand; +import edu.wpi.first.wpilibj2.command.RunCommand; +import edu.wpi.first.wpilibj2.command.button.JoystickButton; +import frc.robot.Constants.DriveConstants; +import frc.robot.Constants.IOConstants; +import frc.robot.subsystems.DriveSubsystem; + public class RobotContainer { + // The robot's subsystems and commands are defined here + private final DriveSubsystem m_robotDrive = new DriveSubsystem(); + + private final XboxController m_driverController = new XboxController(IOConstants.kDriverControllerPort); + + /** + * The container for the robot. Contains subsystems, OI devices, and commands. + */ public RobotContainer() { + // Configure the trigger bindings configureBindings(); + + m_robotDrive.setDefaultCommand( + new RunCommand( + () -> m_robotDrive.drive( + MathUtil.applyDeadband( + -m_driverController.getLeftY(), + IOConstants.kControllerDeadband) + * DriveConstants.kMaxSpeedMetersPerSecond + * (1 - m_driverController + .getLeftTriggerAxis() + * IOConstants.kSlowModeScalar) + * 0.8, + MathUtil.applyDeadband( + -m_driverController.getLeftX(), + IOConstants.kControllerDeadband) + * DriveConstants.kMaxSpeedMetersPerSecond + * (1 - m_driverController + .getLeftTriggerAxis() + * IOConstants.kSlowModeScalar) + * 0.8, + MathUtil.applyDeadband( + m_driverController.getRightX(), + IOConstants.kControllerDeadband) + * DriveConstants.kMaxAngularSpeedRadiansPerSecond + * (1 - m_driverController + .getLeftTriggerAxis() + * IOConstants.kSlowModeScalar) + / 2, + !m_driverController.getRightBumper()), + m_robotDrive)); } - private void configureBindings() {} + /** + * Use this method to define your button->command mappings. + */ + private void configureBindings() { + new JoystickButton(m_driverController, Button.kStart.value) + .onTrue(new InstantCommand(m_robotDrive::zeroHeading, m_robotDrive)); + } public Command getAutonomousCommand() { return Commands.print("No autonomous command configured"); diff --git a/src/main/java/frc/robot/commands/AlignToTagCommand.java b/src/main/java/frc/robot/commands/AlignToTagCommand.java new file mode 100644 index 0000000..cf02d5e --- /dev/null +++ b/src/main/java/frc/robot/commands/AlignToTagCommand.java @@ -0,0 +1,102 @@ +package frc.robot.commands; + +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.controller.PIDController; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.wpilibj.DriverStation; +import edu.wpi.first.wpilibj.DriverStation.Alliance; +import edu.wpi.first.wpilibj2.command.Command; +import frc.robot.Constants.TagAlignConstants; +import frc.robot.Constants.TagAlignConstants.AlignPosition; +import frc.robot.subsystems.DriveSubsystem; + +public class AlignToTagCommand extends Command { + + final DriveSubsystem m_subsystem; + final Pose2d m_target; // Desired pose + final PIDController m_PIDxy; + final PIDController m_PIDomega; // Omega is used to denote robot heading in radians + + double m_consecCount; // counter of number of consecutive cycles within tolerance + + /** + * + * @param subsystem Subsystem to require + * @param alignPos Position to align to + */ + public AlignToTagCommand(DriveSubsystem subsystem, AlignPosition alignPos) { + m_subsystem = subsystem; + addRequirements(m_subsystem); + + final Pose2d redTarget = TagAlignConstants.kTargetPoses[alignPos.ordinal()]; + + // Blue positions are determined by flipping the x position and angle across the + // center. If this logic does not work, then hard coded values may be better + // (and faster). Indexing can be done by adding a constant to the ordinal when + // indexing the array. This will allows accessing the blue positions which + // should be put in the array after the red ones. + m_target = DriverStation.getAlliance().get().compareTo(Alliance.Red) == 0 ? redTarget + : new Pose2d(new Translation2d( // Flip poses of alliance is blue + TagAlignConstants.kFieldWidth - redTarget.getX(), + redTarget.getY()), + new Rotation2d(MathUtil.angleModulus(Math.PI - redTarget.getRotation().getRadians()))); + + m_PIDxy = new PIDController(TagAlignConstants.kTagPIDkPxy, TagAlignConstants.kTagPIDkIxy, + TagAlignConstants.kTagPIDkDxy); // A feed forward control might also be needed here to overcome static friction + m_PIDomega = new PIDController(TagAlignConstants.kTagPIDkPomega, TagAlignConstants.kTagPIDkIomega, + TagAlignConstants.kTagPIDkDomega); + + m_PIDomega.enableContinuousInput(-Math.PI, Math.PI); + } + + @Override + public void initialize() { + m_PIDxy.reset(); // If a command instance is never reused then these three lines won't be needed + m_PIDomega.reset(); + m_consecCount = 0; + } + + @Override + public void execute() { + Pose2d current = m_subsystem.getPose(); + + double xSpeed = MathUtil.clamp(m_PIDxy.calculate(current.getX(), m_target.getX()), + -0, 0); // TODO: change clamp parameters and units + + double ySpeed = MathUtil.clamp( + m_PIDxy.calculate(current.getY(), m_target.getY()), + -0, 0); // TODO: change clamp parameters and units + + double omegaSpeed = MathUtil.clamp( + m_PIDomega.calculate(current.getRotation().getRadians(), m_target.getRotation().getRadians()), + -0, 0); // TODO: change clamp parameters and units + + // Check if within tolerance + if (Math.abs(current.getX() - m_target.getX()) < TagAlignConstants.kTolxy && // x within range + Math.abs(current.getY() - m_target.getY()) < TagAlignConstants.kTolxy && // y within range + Math.abs( // omega within range + current.getRotation().getRadians() - m_target.getRotation().getRadians()) < TagAlignConstants.kTolomega) { + m_consecCount++; + } else + m_consecCount = 0; + + m_subsystem.drive(xSpeed, ySpeed, omegaSpeed, true); + } + + @Override + public void end(boolean interrupted) { + // TODO: log finish reason to NT (either reached, proximity, or interrupted) + // This is also a good place to start an instant command to move the outake to + // the correct position + } + + @Override + public boolean isFinished() { + Pose2d current = m_subsystem.getPose(); + return Math.pow(current.getX() - m_target.getX(), 2) + Math.pow(current.getY() - m_target.getY(), 2) > Math + .pow(TagAlignConstants.kMinProx, 2) || // Exceed proximity. + m_consecCount >= TagAlignConstants.kConsectol; // Reached setpoint + } +} \ No newline at end of file diff --git a/src/main/java/frc/robot/subsystems/DriveSubsystem.java b/src/main/java/frc/robot/subsystems/DriveSubsystem.java new file mode 100644 index 0000000..396777c --- /dev/null +++ b/src/main/java/frc/robot/subsystems/DriveSubsystem.java @@ -0,0 +1,254 @@ +// 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 frc.robot.subsystems; + +import com.kauailabs.navx.frc.AHRS; + +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.networktables.DoubleArrayEntry; +import edu.wpi.first.networktables.NetworkTable; +import frc.robot.Constants.TagAlignConstants; +import edu.wpi.first.math.MathUtil; +import edu.wpi.first.math.controller.PIDController; +import edu.wpi.first.math.estimator.SwerveDrivePoseEstimator; +import edu.wpi.first.math.geometry.Pose2d; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.kinematics.ChassisSpeeds; +import edu.wpi.first.math.kinematics.SwerveDriveKinematics; +import edu.wpi.first.math.kinematics.SwerveModulePosition; +import edu.wpi.first.math.kinematics.SwerveModuleState; +import edu.wpi.first.wpilibj.Timer; +import edu.wpi.first.wpilibj.smartdashboard.Field2d; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; +import edu.wpi.first.wpilibj2.command.SubsystemBase; +import frc.robot.Constants.DriveConstants; +import frc.robot.Robot; + +public class DriveSubsystem extends SubsystemBase { + private final SwerveModule m_frontLeft = new SwerveModule( + DriveConstants.kFrontLeftDriveMotorPort, + DriveConstants.kFrontLeftTurningMotorPort, + DriveConstants.kFrontLeftTurningEncoderPort, + DriveConstants.kFrontLeftDriveMotorReversed, + DriveConstants.kFrontLeftTurningEncoderOffset); + + private final SwerveModule m_rearLeft = new SwerveModule( + DriveConstants.kRearLeftDriveMotorPort, + DriveConstants.kRearLeftTurningMotorPort, + DriveConstants.kRearLeftTurningEncoderPort, + DriveConstants.kRearLeftDriveMotorReversed, + DriveConstants.kRearLeftTurningEncoderOffset); + + private final SwerveModule m_frontRight = new SwerveModule( + DriveConstants.kFrontRightDriveMotorPort, + DriveConstants.kFrontRightTurningMotorPort, + DriveConstants.kFrontRightTurningEncoderPort, + DriveConstants.kFrontRightDriveMotorReversed, + DriveConstants.kFrontRightTurningEncoderOffset); + + private final SwerveModule m_rearRight = new SwerveModule( + DriveConstants.kRearRightDriveMotorPort, + DriveConstants.kRearRightTurningMotorPort, + DriveConstants.kRearRightTurningEncoderPort, + DriveConstants.kRearRightDriveMotorReversed, + DriveConstants.kRearRightTurningEncoderOffset); + + private final AHRS m_gyro = new AHRS(); + private double m_gyroAngle; + + private final Timer m_headingCorrectionTimer = new Timer(); + private final PIDController m_headingCorrectionPID = new PIDController(DriveConstants.kPHeadingCorrectionController, + 0, 0); + private SwerveModulePosition[] m_swerveModulePositions = new SwerveModulePosition[] { + m_frontLeft.getPosition(), + m_frontRight.getPosition(), + m_rearLeft.getPosition(), + m_rearRight.getPosition() + }; + + // TODO: Experiment with different std devs in the pose estimator + private final SwerveDrivePoseEstimator m_poseEstimator = new SwerveDrivePoseEstimator(DriveConstants.kDriveKinematics, + m_gyro.getRotation2d(), m_swerveModulePositions, new Pose2d()); + + private final Field2d m_field = new Field2d(); + + /** Creates a new DriveSubsystem. */ + public DriveSubsystem() { + SmartDashboard.putData("Field", m_field); + m_headingCorrectionTimer.restart(); + m_headingCorrectionPID.enableContinuousInput(-Math.PI, Math.PI); + } + + @Override + public void periodic() { + // This method will be called once per scheduler run + + m_swerveModulePositions = new SwerveModulePosition[] { + m_frontLeft.getPosition(), + m_frontRight.getPosition(), + m_rearLeft.getPosition(), + m_rearRight.getPosition() + }; + + NetworkTable tb = TagAlignConstants.kNTInstance.getTable("limelight"); + + DoubleArrayEntry botpose = null; // index 0: x, 1: y, 2: z, 3: roll, 4: pitch, 5: yaw, 6: timestamp. all angles + // are in degrees + + try { + botpose = tb.getDoubleArrayTopic("botpose").getEntry(new double[0]); + double[] bp = botpose.getAtomic().value; // Not sure how threading works in WPIlib w/ command scheduler. If it is + // thread safe then atomic wont be needed. There is no need to use the + // atomic timestamp since the topic has the timestamp stored in it (7th + // element) + + if (botpose.exists()) { + Pose2d visionPose = new Pose2d(new Translation2d(bp[0], bp[1]), new Rotation2d(bp[5] * Math.PI / 180)); + m_poseEstimator.addVisionMeasurement(visionPose, Timer.getFPGATimestamp() - (bp[6] / 1000)); + } else { + // TODO: log limelight failure + } + + } finally { + if (botpose != null && botpose.isValid()) + botpose.close(); // TODO: verify this logic: make sure it will never throw an exception, + // otherwise add another trycatch block + } + + m_poseEstimator.update(Robot.isReal() ? m_gyro.getRotation2d() : new Rotation2d(m_gyroAngle), m_swerveModulePositions); + + m_field.setRobotPose(m_poseEstimator.getEstimatedPosition()); + + SmartDashboard.putNumber("gyro angle", m_gyro.getAngle()); + SmartDashboard.putNumber("odometryX", m_poseEstimator.getEstimatedPosition().getX()); + SmartDashboard.putNumber("odometryY", m_poseEstimator.getEstimatedPosition().getY()); + + // AdvantageScope Logging + double[] logData = { + m_frontLeft.getPosition().angle.getDegrees(), m_frontLeft.driveOutput, + m_frontRight.getPosition().angle.getDegrees(), m_frontRight.driveOutput, + m_rearLeft.getPosition().angle.getDegrees(), m_rearLeft.driveOutput, + m_rearRight.getPosition().angle.getDegrees(), m_rearRight.driveOutput, + }; + SmartDashboard.putNumberArray("AdvantageScope Swerve States", logData); + } + + /** + * Returns the currently-estimated pose of the robot. + * + * @return The pose. + */ + public Pose2d getPose() { + return m_poseEstimator.getEstimatedPosition(); + } + + /** + * Method to drive the robot using joystick info. + * + * @param xSpeed Speed of the robot in the x direction (forward). + * @param ySpeed Speed of the robot in the y direction (sideways). + * @param rotation Angular rotation speed of the robot. + * @param fieldRelative Whether the provided x and y speeds are relative to the + * field. + */ + public void drive(double xSpeed, double ySpeed, double rotation, boolean fieldRelative) { + // If we are rotating, reset the timer + if (rotation != 0) { + m_headingCorrectionTimer.reset(); + } + + /* + * Heading correction helps maintain the same heading and + * prevents rotational drive while our robot is translating + * + * For heading correction we use a timer to ensure that we + * lose all rotational momentum before saving the heading + * that we want to maintain + */ + + // TODO: Test heading correction without timer + // TODO: Test heading correction using gyro's rotational velocity (if it is 0 + // then set heading instead of timer) + + // Save our desired rotation to a variable we can add our heading correction + // adjustments to + double calculatedRotation = rotation; + + double currentAngle = MathUtil.angleModulus(m_gyro.getRotation2d().getRadians()); + + // If we are not translating or if not enough time has passed since the last + // time we rotated + if ((xSpeed == 0 && ySpeed == 0) + || m_headingCorrectionTimer.get() < DriveConstants.kHeadingCorrectionTurningStopTime) { + // Update our desired angle + m_headingCorrectionPID.setSetpoint(currentAngle); + } else { + // If we are translating or if we have not rotated for a long enough time + // then maintain our desired angle + calculatedRotation = m_headingCorrectionPID.calculate(currentAngle); + } + + // Depending on whether the robot is being driven in field relative, calculate + // the desired states for each of the modules + SwerveModuleState[] swerveModuleStates = DriveConstants.kDriveKinematics.toSwerveModuleStates( + fieldRelative + ? ChassisSpeeds.fromFieldRelativeSpeeds(xSpeed, ySpeed, calculatedRotation, + Robot.isReal() ? m_gyro.getRotation2d() : new Rotation2d(m_gyroAngle)) + : new ChassisSpeeds(xSpeed, ySpeed, calculatedRotation)); + + setModuleStates(swerveModuleStates); + } + + /** + * Resets the odometry to the specified pose. + * + * @param pose The pose to which to set the odometry. + */ + public void resetOdometry(Pose2d pose) { + m_poseEstimator.resetPosition( + Robot.isReal() ? m_gyro.getRotation2d() : new Rotation2d(m_gyroAngle), + new SwerveModulePosition[] { + m_frontLeft.getPosition(), + m_frontRight.getPosition(), + m_rearLeft.getPosition(), + m_rearRight.getPosition() + }, + pose); + } + + /** Zeroes the heading of the robot. */ + public void zeroHeading() { + m_gyro.reset(); + m_gyroAngle = 0; + } + + /** + * Sets the swerve ModuleStates. + * + * @param desiredStates The desired SwerveModule states. + */ + public void setModuleStates(SwerveModuleState[] desiredStates) { + SwerveDriveKinematics.desaturateWheelSpeeds( + desiredStates, DriveConstants.kMaxSpeedMetersPerSecond); + m_frontLeft.setDesiredState(desiredStates[0]); + m_frontRight.setDesiredState(desiredStates[1]); + m_rearLeft.setDesiredState(desiredStates[2]); + m_rearRight.setDesiredState(desiredStates[3]); + + // AdvantageScope Logging + double[] logData = { + desiredStates[0].angle.getDegrees(), desiredStates[0].speedMetersPerSecond, + desiredStates[1].angle.getDegrees(), desiredStates[1].speedMetersPerSecond, + desiredStates[2].angle.getDegrees(), desiredStates[2].speedMetersPerSecond, + desiredStates[3].angle.getDegrees(), desiredStates[3].speedMetersPerSecond, + }; + SmartDashboard.putNumberArray("AdvantageScope Swerve Desired States", logData); + + // Takes the integral of the rotation speed to find the current angle for the + // simulator + m_gyroAngle += DriveConstants.kDriveKinematics.toChassisSpeeds(desiredStates).omegaRadiansPerSecond + * Robot.kDefaultPeriod; + } +} diff --git a/src/main/java/frc/robot/subsystems/SwerveModule.java b/src/main/java/frc/robot/subsystems/SwerveModule.java new file mode 100644 index 0000000..40578b8 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/SwerveModule.java @@ -0,0 +1,106 @@ +// 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 frc.robot.subsystems; + +import com.ctre.phoenix6.configs.CANcoderConfiguration; +import com.ctre.phoenix6.hardware.CANcoder; +import com.revrobotics.CANSparkFlex; +import com.revrobotics.CANSparkBase.IdleMode; +import com.revrobotics.CANSparkLowLevel.MotorType; + +import edu.wpi.first.math.controller.PIDController; +import edu.wpi.first.math.geometry.Rotation2d; +import edu.wpi.first.math.kinematics.SwerveModulePosition; +import edu.wpi.first.math.kinematics.SwerveModuleState; +import edu.wpi.first.units.Units; +import frc.robot.Constants.DriveConstants; +import frc.robot.Robot; + +/** Add your docs here. */ +public class SwerveModule { + private final CANSparkFlex m_driveMotor; + private final CANSparkFlex m_turningMotor; + + private final CANcoder m_turningEncoder; + + private final PIDController m_turningPIDController = new PIDController(DriveConstants.kPModuleTurningController, 0, + 0); + + private SwerveModuleState m_state = new SwerveModuleState(); + private double m_distance; + + public double driveOutput; + public double turnOutput; + + /** + * Constructs a {@link SwerveModule}. + * + * @param driveMotorPort The port of the drive motor. + * @param turningMotorPort The port of the turning motor. + * @param turningEncoderPort The port of the turning encoder. + * @param driveMotorReversed Whether the drive motor is reversed. + * @param turningEncoderOffset Offset of the turning encoder. + */ + public SwerveModule( + int driveMotorPort, + int turningMotorPort, + int turningEncoderPort, + boolean driveMotorReversed, + double turningEncoderOffset) { + m_driveMotor = new CANSparkFlex(driveMotorPort, MotorType.kBrushless); + m_turningMotor = new CANSparkFlex(turningMotorPort, MotorType.kBrushless); + m_turningEncoder = new CANcoder(turningEncoderPort); + + // converts default units to meters per second + m_driveMotor.getEncoder().setVelocityConversionFactor( + DriveConstants.kWheelDiameterMeters * Math.PI / 60 / DriveConstants.kDrivingGearRatio); + + m_driveMotor.setInverted(driveMotorReversed); + + m_turningMotor.setIdleMode(IdleMode.kBrake); + + m_turningEncoder.getConfigurator().apply(new CANcoderConfiguration().MagnetSensor.withMagnetOffset(-turningEncoderOffset)); + + m_turningPIDController.enableContinuousInput(-Math.PI, Math.PI); + } + + /** + * Returns the current position of the module. + * + * @return The current position of the module. + */ + public SwerveModulePosition getPosition() { + m_distance += m_state.speedMetersPerSecond * Robot.kDefaultPeriod; + + // If the robot is real, then return the swerve module state by reading from the + // actual encoders + // If the robot is simulated, then return the swerve module state using the + // expected values + + + ; + return Robot.isReal() + ? new SwerveModulePosition(m_driveMotor.getEncoder().getPosition(), + new Rotation2d(Units.RadiansPerSecond.convertFrom(m_turningEncoder.getAbsolutePosition().getValueAsDouble(), Units.RotationsPerSecond))) + : new SwerveModulePosition(m_distance, m_state.angle); + } + + /** + * Sets the desired state for the module. + * + * @param desiredState Desired state with speed and angle. + */ + public void setDesiredState(SwerveModuleState desiredState) { + m_state = SwerveModuleState.optimize(desiredState, new Rotation2d(Units.RadiansPerSecond.convertFrom(m_turningEncoder.getAbsolutePosition().getValueAsDouble(), Units.RotationsPerSecond))); + + driveOutput = m_state.speedMetersPerSecond / DriveConstants.kMaxSpeedMetersPerSecond; + + turnOutput = m_turningPIDController.calculate(Units.RadiansPerSecond.convertFrom(m_turningEncoder.getAbsolutePosition().getValueAsDouble(), Units.RotationsPerSecond), + m_state.angle.getRadians()); + + m_driveMotor.set(driveOutput); + m_turningMotor.set(turnOutput); + } +} diff --git a/vendordeps/NavX.json b/vendordeps/NavX.json new file mode 100644 index 0000000..e978a5f --- /dev/null +++ b/vendordeps/NavX.json @@ -0,0 +1,40 @@ +{ + "fileName": "NavX.json", + "name": "NavX", + "version": "2024.1.0", + "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", + "frcYear": "2024", + "mavenUrls": [ + "https://dev.studica.com/maven/release/2024/" + ], + "jsonUrl": "https://dev.studica.com/releases/2024/NavX.json", + "javaDependencies": [ + { + "groupId": "com.kauailabs.navx.frc", + "artifactId": "navx-frc-java", + "version": "2024.1.0" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "com.kauailabs.navx.frc", + "artifactId": "navx-frc-cpp", + "version": "2024.1.0", + "headerClassifier": "headers", + "sourcesClassifier": "sources", + "sharedLibrary": false, + "libName": "navx_frc", + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "linuxathena", + "linuxraspbian", + "linuxarm32", + "linuxarm64", + "linuxx86-64", + "osxuniversal", + "windowsx86-64" + ] + } + ] +} \ No newline at end of file diff --git a/vendordeps/Phoenix6.json b/vendordeps/Phoenix6.json new file mode 100644 index 0000000..69a4079 --- /dev/null +++ b/vendordeps/Phoenix6.json @@ -0,0 +1,339 @@ +{ + "fileName": "Phoenix6.json", + "name": "CTRE-Phoenix (v6)", + "version": "24.1.0", + "frcYear": 2024, + "uuid": "e995de00-2c64-4df5-8831-c1441420ff19", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2024-latest.json", + "conflictsWith": [ + { + "uuid": "3fcf3402-e646-4fa6-971e-18afe8173b1a", + "errorMessage": "The combined Phoenix-6-And-5 vendordep is no longer supported. Please remove the vendordep and instead add both the latest Phoenix 6 vendordep and Phoenix 5 vendordep.", + "offlineFileName": "Phoenix6And5.json" + } + ], + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-java", + "version": "24.1.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "24.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "24.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "24.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonFX", + "version": "24.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "24.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "24.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "24.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "24.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "24.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "24.1.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix6", + "artifactId": "wpiapi-cpp", + "version": "24.1.0", + "libName": "CTRE_Phoenix6_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "24.1.0", + "libName": "CTRE_PhoenixTools", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "24.1.0", + "libName": "CTRE_Phoenix6_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "24.1.0", + "libName": "CTRE_PhoenixTools_Sim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "24.1.0", + "libName": "CTRE_SimTalonSRX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonFX", + "version": "24.1.0", + "libName": "CTRE_SimTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "24.1.0", + "libName": "CTRE_SimVictorSPX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "24.1.0", + "libName": "CTRE_SimPigeonIMU", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "24.1.0", + "libName": "CTRE_SimCANCoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "24.1.0", + "libName": "CTRE_SimProTalonFX", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "24.1.0", + "libName": "CTRE_SimProCANcoder", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "24.1.0", + "libName": "CTRE_SimProPigeon2", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + } + ] +} \ No newline at end of file diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json new file mode 100644 index 0000000..0f3520e --- /dev/null +++ b/vendordeps/REVLib.json @@ -0,0 +1,74 @@ +{ + "fileName": "REVLib.json", + "name": "REVLib", + "version": "2024.2.0", + "frcYear": "2024", + "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", + "mavenUrls": [ + "https://maven.revrobotics.com/" + ], + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2024.json", + "javaDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-java", + "version": "2024.2.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2024.2.0", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-cpp", + "version": "2024.2.0", + "libName": "REVLib", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + }, + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2024.2.0", + "libName": "REVLibDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ] +} \ No newline at end of file