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..aa4bfd6 --- /dev/null +++ b/src/main/java/frc/robot/Constants.java @@ -0,0 +1,126 @@ +// 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; + +import edu.wpi.first.math.VecBuilder; +import edu.wpi.first.math.Vector; +import edu.wpi.first.math.geometry.Pose3d; +import edu.wpi.first.math.geometry.Rotation3d; +import edu.wpi.first.math.geometry.Translation2d; +import edu.wpi.first.math.kinematics.SwerveDriveKinematics; +import edu.wpi.first.math.numbers.N3; + +/** + * 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 final 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 = 32;
+ public static final int kRearLeftDriveMotorPort = 29;
+ public static final int kFrontRightDriveMotorPort = 38;
+ public static final int kRearRightDriveMotorPort = 34;
+
+ public static final int kFrontLeftTurningMotorPort = 28;
+ public static final int kRearLeftTurningMotorPort = 22;
+ public static final int kFrontRightTurningMotorPort = 37;
+ public static final int kRearRightTurningMotorPort = 26;
+
+ public static final int kFrontLeftTurningEncoderPort = 19;
+ public static final int kRearLeftTurningEncoderPort = 20;
+ public static final int kFrontRightTurningEncoderPort = 18;
+ public static final int kRearRightTurningEncoderPort = 17;
+
+ 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.57785;
+
+ /** Distance between front and back wheels on robot (in meters). */
+ public static final double kWheelBase = 0.57785;
+
+ /** 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
+ // public static final double kDrivingGearRatio = 6.75; // SDS MK4i's in L2 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 Neo Vortexes */
+ public static final double kMaxSpeedMetersPerSecond = 4.4196;
+ /** For a a SDS Mk4i L1 swerve base with Neo Vortexes */
+ public static final double kMaxAngularSpeedRadiansPerSecond = 10.8164;
+ // ^^ Calculated using the method taken from the old SDS github example
+
+ /** 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 static final class ShooterConstants {
+ public static final int kTopShooterMotorPort = 35;
+ public static final int kBottomShooterMotorPort = 20;
+ }
+
+ public static final class VisionConstants {
+ // TODO: Update cam pose relative to center of bot
+ public static final Pose3d kCamPose = new Pose3d(0, 0, 0, new Rotation3d(0, 0, 0));
+ public static final double[] kLimelightCamPose = {
+ kCamPose.getX(),
+ kCamPose.getY(),
+ kCamPose.getZ(),
+ kCamPose.getRotation().getX(),
+ kCamPose.getRotation().getY(),
+ kCamPose.getRotation().getZ() };
+
+ // TODO: Experiment with different std devs in the pose estimator
+ public static final Vector If you change your main robot class, change the parameter type.
+ */
public static void main(String... args) {
RobotBase.startRobot(Robot::new);
}
diff --git a/src/main/java/frc/robot/Robot.java b/src/main/java/frc/robot/Robot.java
index b68462c..687a0a0 100644
--- a/src/main/java/frc/robot/Robot.java
+++ b/src/main/java/frc/robot/Robot.java
@@ -8,66 +8,96 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
+/**
+ * The VM is configured to automatically run this class, and to call the functions corresponding to
+ * each mode, as described in the TimedRobot documentation. If you change the name of this class or
+ * the package after creating this project, you must also update the build.gradle file in the
+ * project.
+ */
public class Robot extends TimedRobot {
private Command m_autonomousCommand;
private RobotContainer m_robotContainer;
+ /**
+ * This function is run when the robot is first started up and should be used for any
+ * initialization code.
+ */
@Override
public void robotInit() {
+ // Instantiate our RobotContainer. This will perform all our button bindings, and put our
+ // autonomous chooser on the dashboard.
m_robotContainer = new RobotContainer();
}
+ /**
+ * This function is called every 20 ms, no matter the mode. Use this for items like diagnostics
+ * that you want ran during disabled, autonomous, teleoperated and test.
+ *
+ * This runs after the mode specific periodic functions, but before LiveWindow and
+ * SmartDashboard integrated updating.
+ */
@Override
public void robotPeriodic() {
+ // Runs the Scheduler. This is responsible for polling buttons, adding newly-scheduled
+ // commands, running already-scheduled commands, removing finished or interrupted commands,
+ // and running subsystem periodic() methods. This must be called from the robot's periodic
+ // block in order for anything in the Command-based framework to work.
CommandScheduler.getInstance().run();
}
+ /** This function is called once each time the robot enters Disabled mode. */
@Override
public void disabledInit() {}
@Override
public void disabledPeriodic() {}
- @Override
- public void disabledExit() {}
-
+ /** This autonomous runs the autonomous command selected by your {@link RobotContainer} class. */
@Override
public void autonomousInit() {
m_autonomousCommand = m_robotContainer.getAutonomousCommand();
+ // schedule the autonomous command (example)
if (m_autonomousCommand != null) {
m_autonomousCommand.schedule();
}
}
+ /** This function is called periodically during autonomous. */
@Override
public void autonomousPeriodic() {}
- @Override
- public void autonomousExit() {}
-
@Override
public void teleopInit() {
+ // This makes sure that the autonomous stops running when
+ // teleop starts running. If you want the autonomous to
+ // continue until interrupted by another command, remove
+ // this line or comment it out.
if (m_autonomousCommand != null) {
m_autonomousCommand.cancel();
}
}
+ /** This function is called periodically during operator control. */
@Override
public void teleopPeriodic() {}
- @Override
- public void teleopExit() {}
-
@Override
public void testInit() {
+ // Cancels all running commands at the start of test mode.
CommandScheduler.getInstance().cancelAll();
}
+ /** This function is called periodically during test mode. */
@Override
public void testPeriodic() {}
+ /** This function is called once when the robot is first started up. */
+ @Override
+ public void simulationInit() {}
+
+ /** This function is called periodically whilst in simulation. */
@Override
- public void testExit() {}
+ public void simulationPeriodic() {}
}
diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java
index 714b9ab..c19c224 100644
--- a/src/main/java/frc/robot/RobotContainer.java
+++ b/src/main/java/frc/robot/RobotContainer.java
@@ -4,31 +4,91 @@
package frc.robot;
-import edu.wpi.first.wpilibj.Joystick;
+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;
import frc.robot.subsystems.ShooterSubsystem;
+/*
+ * This class is where the bulk of the robot should be declared. Since Command-based is a
+ * "declarative" paradigm, very little robot logic should actually be handled in the {@link Robot}
+ * periodic methods (other than the scheduler calls). Instead, the structure of the robot
+ * (including subsystems, commands, and button mappings) should be declared here.
+ */
public class RobotContainer {
- public final ShooterSubsystem m_ShooterSubsystem = new ShooterSubsystem();
- private XboxController controller = new XboxController(0);
+ // The robot's subsystems and commands are defined here
+ private final DriveSubsystem m_robotDrive = new DriveSubsystem();
+ public final ShooterSubsystem m_shooterSubsystem = new ShooterSubsystem();
+
+ 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));
}
+ /**
+ * Use this method to define your button->command mappings.
+ */
private void configureBindings() {
- new JoystickButton(controller, Button.kB.value)
- .onTrue(new InstantCommand(() -> m_ShooterSubsystem.spin(0.75), m_ShooterSubsystem))
- .onFalse(new InstantCommand(() -> m_ShooterSubsystem.spin(0), m_ShooterSubsystem));
- new JoystickButton(controller, Button.kA.value)
- .onTrue(new InstantCommand(() -> m_ShooterSubsystem.spin(-0.75), m_ShooterSubsystem))
- .onFalse(new InstantCommand(() -> m_ShooterSubsystem.spin(0), m_ShooterSubsystem));
+ new JoystickButton(m_driverController, Button.kStart.value)
+ .onTrue(new InstantCommand(m_robotDrive::zeroHeading, m_robotDrive));
+
+ // TODO: Move shoot commands to operator controller
+ new JoystickButton(m_driverController, Button.kB.value)
+ .onTrue(new InstantCommand(() -> m_shooterSubsystem.spin(0.75), m_shooterSubsystem))
+ .onFalse(new InstantCommand(() -> m_shooterSubsystem.spin(0), m_shooterSubsystem));
+ new JoystickButton(m_driverController, Button.kA.value)
+ .onTrue(new InstantCommand(() -> m_shooterSubsystem.spin(-0.75), m_shooterSubsystem))
+ .onFalse(new InstantCommand(() -> m_shooterSubsystem.spin(0), m_shooterSubsystem));
}
+ /**
+ * Use this to pass the autonomous command to the main {@link Robot} class.
+ *
+ * @return the command to run in autonomous
+ */
public Command getAutonomousCommand() {
return Commands.print("No autonomous command configured");
}
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..f606d5b
--- /dev/null
+++ b/src/main/java/frc/robot/subsystems/DriveSubsystem.java
@@ -0,0 +1,232 @@
+// 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.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.Constants.VisionConstants;
+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()
+ };
+
+ private final SwerveDrivePoseEstimator m_poseEstimator = new SwerveDrivePoseEstimator(DriveConstants.kDriveKinematics,
+ m_gyro.getRotation2d(), m_swerveModulePositions, new Pose2d(), VisionConstants.kOdometrySTDDevs,
+ VisionConstants.kVisionSTDDevs);
+
+ 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()
+ };
+
+ 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;
+ }
+
+ public void addVisionMeasurement(Pose2d pose, double timestamp) {
+ m_poseEstimator.addVisionMeasurement(pose, timestamp);
+ }
+
+ /**
+ * 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/ShooterSubsystem.java b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java
index 8ff662b..afdbd19 100644
--- a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java
+++ b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java
@@ -3,23 +3,27 @@
// the WPILib BSD license file in the root directory of this project.
package frc.robot.subsystems;
+
import com.revrobotics.CANSparkFlex;
import com.revrobotics.CANSparkLowLevel.MotorType;
-import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
+import frc.robot.Constants.ShooterConstants;
+
public class ShooterSubsystem extends SubsystemBase {
/** Creates a new ShooterSubsystem. */
- CANSparkFlex m_bottom = new CANSparkFlex(20, MotorType.kBrushless);
- CANSparkFlex m_top = new CANSparkFlex(35, MotorType.kBrushless);
- public ShooterSubsystem() {
+ CANSparkFlex m_bottom = new CANSparkFlex(ShooterConstants.kBottomShooterMotorPort, MotorType.kBrushless);
+ CANSparkFlex m_top = new CANSparkFlex(ShooterConstants.kTopShooterMotorPort, MotorType.kBrushless);
+ public ShooterSubsystem() {
}
- public void spin(double speed){
+
+ public void spin(double speed) {
m_bottom.set(speed);
m_top.set(speed);
}
+
@Override
public void periodic() {
// This method will be called once per scheduler run
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..9d98ea8
--- /dev/null
+++ b/src/main/java/frc/robot/subsystems/SwerveModule.java
@@ -0,0 +1,118 @@
+// 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.CANcoderConfigurator;
+import com.ctre.phoenix6.configs.MagnetSensorConfigs;
+import com.ctre.phoenix6.hardware.CANcoder;
+import com.revrobotics.CANSparkBase.IdleMode;
+import com.revrobotics.CANSparkLowLevel.MotorType;
+import com.revrobotics.CANSparkMax;
+
+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 frc.robot.Constants.DriveConstants;
+import frc.robot.Robot;
+
+public class SwerveModule {
+ private final CANSparkMax m_driveMotor;
+ private final CANSparkMax m_turningMotor;
+
+ private final CANcoder m_turningEncoder;
+ private final CANcoderConfigurator m_turningEncoderConfigurator;
+
+ 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 CANSparkMax(driveMotorPort, MotorType.kBrushless);
+ m_turningMotor = new CANSparkMax(turningMotorPort, MotorType.kBrushless);
+ m_turningEncoder = new CANcoder(turningEncoderPort);
+ m_turningEncoderConfigurator = m_turningEncoder.getConfigurator();
+
+ // 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);
+
+ // TODO: CANcoder offsets are now set on the device manually using Pheonix Tuner
+ // (or maybe Pheonix X)
+ m_turningEncoderConfigurator.apply(new MagnetSensorConfigs().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(),
+ getEncoderAngle(m_turningEncoder))
+ : 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, getEncoderAngle(m_turningEncoder));
+ driveOutput = m_state.speedMetersPerSecond / DriveConstants.kMaxSpeedMetersPerSecond;
+
+ turnOutput = m_turningPIDController.calculate(getEncoderAngle(m_turningEncoder).getRadians(),
+ m_state.angle.getRadians());
+
+ m_driveMotor.set(driveOutput);
+ m_turningMotor.set(turnOutput);
+ }
+
+ /**
+ * Returns the angle of a CANcoder
+ *
+ * The CANcoder now gives values in rotations which is useless, so this method
+ * translates the CANcoder output into a Rotation2D
+ *
+ * @param encoder The encoder to get the absolute angle of.
+ * @return A Rotation2d of the absolute angle.
+ */
+ public static Rotation2d getEncoderAngle(CANcoder encoder) {
+ return new Rotation2d(encoder.getAbsolutePosition().getValueAsDouble() * 2 * Math.PI);
+ }
+}
diff --git a/src/main/java/frc/robot/subsystems/VisionSubsystem.java b/src/main/java/frc/robot/subsystems/VisionSubsystem.java
new file mode 100644
index 0000000..daeea25
--- /dev/null
+++ b/src/main/java/frc/robot/subsystems/VisionSubsystem.java
@@ -0,0 +1,128 @@
+// 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 java.util.Arrays;
+import java.util.Optional;
+
+import edu.wpi.first.math.Matrix;
+import edu.wpi.first.math.geometry.Pose3d;
+import edu.wpi.first.math.geometry.Rotation3d;
+import edu.wpi.first.math.geometry.Translation3d;
+import edu.wpi.first.math.numbers.N1;
+import edu.wpi.first.math.numbers.N3;
+import edu.wpi.first.math.util.Units;
+import edu.wpi.first.networktables.DoubleArraySubscriber;
+import edu.wpi.first.networktables.DoubleSubscriber;
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.networktables.TimestampedDoubleArray;
+import edu.wpi.first.wpilibj2.command.SubsystemBase;
+import frc.robot.Constants.VisionConstants;
+
+/**
+ *
+ * In 3D poses and transforms:
+ *
+ * On the field (0, 0, 0) in 3D space is the right corner of the blue alliance
+ * driver station
+ * Therefore, from the blue driver station: +X is forward, +Y is left, +Z is up
+ *
+ *
+ * In 2D poses and transforms:
+ *
+ *
+ *
+ *
+ *
+ */
+public class VisionSubsystem extends SubsystemBase {
+
+ NetworkTable m_visionNetworkTable = NetworkTableInstance.getDefault().getTable("limelight");
+
+ private final DoubleArraySubscriber m_botPose;
+ private final DoubleSubscriber m_cl;
+ private final DoubleSubscriber m_tl;
+
+ /** Creates a new Limelight. */
+ public VisionSubsystem() {
+ // Provide the limelight with the camera pose relative to the center of the
+ // robot
+ m_visionNetworkTable.getEntry("camerapose_robotspace_set").setDoubleArray(VisionConstants.kLimelightCamPose);
+
+ // Create subscribers to get values from the limelight
+ m_botPose = m_visionNetworkTable.getDoubleArrayTopic("botpose_wpiblue").subscribe(null);
+ m_cl = m_visionNetworkTable.getDoubleTopic("cl").subscribe(0);
+ m_tl = m_visionNetworkTable.getDoubleTopic("tl").subscribe(0);
+ }
+
+ @Override
+ public void periodic() {
+ // This method will be called once per scheduler run
+ }
+
+ public Optional