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/Main.java b/src/main/java/frc/robot/Main.java index fe215d7..8776e5d 100644 --- a/src/main/java/frc/robot/Main.java +++ b/src/main/java/frc/robot/Main.java @@ -6,9 +6,19 @@ import edu.wpi.first.wpilibj.RobotBase; +/** + * Do NOT add any static variables to this class, or any initialization at all. Unless you know what + * you are doing, do not modify this file except to change the parameter class to the startRobot + * call. + */ public final class Main { private Main() {} + /** + * Main initialization function. Do not perform any initialization here. + * + *

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 44b12f6..d2a8fd9 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -4,34 +4,37 @@ 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.IntakeConstants; -import frc.robot.Constants.ShooterConstants; import frc.robot.subsystems.IntakeSubsystem; 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 { - //The robots subsystems are defined here - public final ShooterSubsystem m_ShooterSubsystem = new ShooterSubsystem(); - public final IntakeSubsystem m_IntakeSubsystem = new IntakeSubsystem(); + public final ShooterSubsystem m_shooterSubsystem = new ShooterSubsystem(); + public final IntakeSubsystem m_intakeSubsystem = new IntakeSubsystem(); private boolean IntakeDropped = false; private boolean lastAButton = false; private XboxController controller = new XboxController(0); public RobotContainer() { + // Configure the trigger bindings configureBindings(); - m_IntakeSubsystem.setDefaultCommand(new InstantCommand(()-> m_IntakeSubsystem.load(controller.getRightTriggerAxis()-controller.getLeftTriggerAxis(),IntakeDropped ? IntakeConstants.kIntakeDroppedAngle : IntakeConstants.kIntakeRaisedAngle),m_IntakeSubsystem)); + m_intakeSubsystem.setDefaultCommand(new InstantCommand(()-> m_IntakeSubsystem.load(controller.getRightTriggerAxis()-controller.getLeftTriggerAxis(),IntakeDropped ? IntakeConstants.IntakeDroppedAngle : IntakeConstants.IntakeRaisedAngle),m_IntakeSubsystem)); } - - /** - * checks for intake button on controller every tick - */ public void periodic(){ if(controller.getAButton()){ lastAButton = true; @@ -43,18 +46,20 @@ public void periodic(){ } } - /** - * Use this method to define your button->command mappings. - */ private void configureBindings() { new JoystickButton(controller, Button.kB.value) - .onTrue(new InstantCommand(() -> m_ShooterSubsystem.spin(ShooterConstants.kSpinSpeedTrue), m_ShooterSubsystem)) - .onFalse(new InstantCommand(() -> m_ShooterSubsystem.spin(ShooterConstants.kSpinSpeedFalse), m_ShooterSubsystem)); + .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(-ShooterConstants.kSpinSpeedTrue), m_ShooterSubsystem)) - .onFalse(new InstantCommand(() -> m_ShooterSubsystem.spin(ShooterConstants.kSpinSpeedFalse), m_ShooterSubsystem)); + .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 1ea808c..e69de29 100644 --- a/src/main/java/frc/robot/subsystems/ShooterSubsystem.java +++ b/src/main/java/frc/robot/subsystems/ShooterSubsystem.java @@ -1,29 +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 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; - -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() { - - - } - 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 - // SmartDashboard.putNumber("Speed", m_bottom.); - } -} 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 getMeasurement() { + TimestampedDoubleArray[] updates = m_botPose.readQueue(); + + // If we have had no updates since the last time this method ran then return + // nothing + if (updates.length == 0) { + return Optional.empty(); + } + + TimestampedDoubleArray update = updates[updates.length - 1]; + + // If the latest update is empty then return nothing + if (Arrays.equals(update.value, new double[6])) { + return Optional.empty(); + } + + double x = update.value[0]; + double y = update.value[1]; + double z = update.value[2]; + double roll = Units.degreesToRadians(update.value[3]); + double pitch = Units.degreesToRadians(update.value[4]); + double yaw = Units.degreesToRadians(update.value[5]); + + double latency = m_cl.get() + m_tl.get(); + + double timestamp = (update.timestamp * 1e-6) - (latency * 1e-3); + Pose3d pose = new Pose3d(new Translation3d(x, y, z), new Rotation3d(roll, pitch, yaw)); + + /* + * The limelight returns 3D field poses where (0, 0, 0) is located at the center + * of the field + * + * So to input this pose into our pose estimator we need to tranform so that (0, + * 0, 0) is the right corner of the blue driver stations + */ + // TODO: Check if we actually need to do this... + // pose.transformBy(new Transform3d(new Translation3d(VisionConstants.kFieldLength, VisionConstants.kFieldWidth, 0.0), new Rotation3d())); + + return Optional.of(new Measurement( + timestamp, + pose, + VisionConstants.kVisionSTDDevs)); + } + + public static class Measurement { + public double timestamp; + public Pose3d pose; + public Matrix stdDeviation; + + public Measurement(double timestamp, Pose3d pose, Matrix stdDeviation) { + this.timestamp = timestamp; + this.pose = pose; + this.stdDeviation = stdDeviation; + } + } +} 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