From c677ac323b181603903a922123e711c80c91cda6 Mon Sep 17 00:00:00 2001 From: mebrahimaleem Date: Sat, 6 Jan 2024 12:45:52 -0800 Subject: [PATCH 1/6] feat: swerve code from swerve-base --- src/main/java/frc/robot/Constants.java | 93 ++++ src/main/java/frc/robot/RobotContainer.java | 57 ++- .../frc/robot/subsystems/DriveSubsystem.java | 226 ++++++++++ .../frc/robot/subsystems/SwerveModule.java | 104 +++++ vendordeps/NavX.json | 39 ++ vendordeps/Phoenix.json | 423 ++++++++++++++++++ vendordeps/REVLib.json | 73 +++ 7 files changed, 1014 insertions(+), 1 deletion(-) create mode 100644 src/main/java/frc/robot/Constants.java create mode 100644 src/main/java/frc/robot/subsystems/DriveSubsystem.java create mode 100644 src/main/java/frc/robot/subsystems/SwerveModule.java create mode 100644 vendordeps/NavX.json create mode 100644 vendordeps/Phoenix.json create mode 100644 vendordeps/REVLib.json diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java new file mode 100644 index 0000000..0da951c --- /dev/null +++ b/src/main/java/frc/robot/Constants.java @@ -0,0 +1,93 @@ +// 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.geometry.Translation2d; +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; + } +} 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/subsystems/DriveSubsystem.java b/src/main/java/frc/robot/subsystems/DriveSubsystem.java new file mode 100644 index 0000000..aebcf73 --- /dev/null +++ b/src/main/java/frc/robot/subsystems/DriveSubsystem.java @@ -0,0 +1,226 @@ +// 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.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() + }; + + 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..9647e5b --- /dev/null +++ b/src/main/java/frc/robot/subsystems/SwerveModule.java @@ -0,0 +1,104 @@ +// 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.phoenix.sensors.CANCoder; +import com.ctre.phoenix.sensors.SensorTimeBase; +import com.revrobotics.CANSparkMax; +import com.revrobotics.CANSparkMax.IdleMode; +import com.revrobotics.CANSparkMaxLowLevel.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 frc.robot.Constants.DriveConstants; +import frc.robot.Robot; + +/** Add your docs here. */ +public class SwerveModule { + private final CANSparkMax m_driveMotor; + private final CANSparkMax 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 CANSparkMax(driveMotorPort, MotorType.kBrushless); + m_turningMotor = new CANSparkMax(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); + + // converts default units of CANCoders to radians + m_turningEncoder.configFeedbackCoefficient(Math.toRadians(0.087890625), "radians", SensorTimeBase.PerSecond); + m_turningEncoder.configMagnetOffset(-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(m_turningEncoder.getAbsolutePosition())) + : 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(m_turningEncoder.getAbsolutePosition())); + + driveOutput = m_state.speedMetersPerSecond / DriveConstants.kMaxSpeedMetersPerSecond; + + turnOutput = m_turningPIDController.calculate(m_turningEncoder.getAbsolutePosition(), + 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..33d81f6 --- /dev/null +++ b/vendordeps/NavX.json @@ -0,0 +1,39 @@ +{ + "fileName": "NavX.json", + "name": "KauaiLabs_navX_FRC", + "version": "2023.0.4", + "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", + "mavenUrls": [ + "https://dev.studica.com/maven/release/2023/" + ], + "jsonUrl": "https://dev.studica.com/releases/2023/NavX.json", + "javaDependencies": [ + { + "groupId": "com.kauailabs.navx.frc", + "artifactId": "navx-frc-java", + "version": "2023.0.4" + } + ], + "jniDependencies": [], + "cppDependencies": [ + { + "groupId": "com.kauailabs.navx.frc", + "artifactId": "navx-frc-cpp", + "version": "2023.0.4", + "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/Phoenix.json b/vendordeps/Phoenix.json new file mode 100644 index 0000000..614dc3a --- /dev/null +++ b/vendordeps/Phoenix.json @@ -0,0 +1,423 @@ +{ + "fileName": "Phoenix.json", + "name": "CTRE-Phoenix (v5)", + "version": "5.31.0+23.2.2", + "frcYear": 2023, + "uuid": "ab676553-b602-441f-a38d-f1296eff6537", + "mavenUrls": [ + "https://maven.ctr-electronics.com/release/" + ], + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2023-latest.json", + "javaDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-java", + "version": "5.31.0" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-java", + "version": "5.31.0" + } + ], + "jniDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.31.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.31.0", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonSRX", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simTalonFX", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simVictorSPX", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simPigeonIMU", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simCANCoder", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProTalonFX", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProCANcoder", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "simProPigeon2", + "version": "23.2.2", + "isJar": false, + "skipInvalidPlatforms": true, + "validPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + } + ], + "cppDependencies": [ + { + "groupId": "com.ctre.phoenix", + "artifactId": "wpiapi-cpp", + "version": "5.31.0", + "libName": "CTRE_Phoenix_WPI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "api-cpp", + "version": "5.31.0", + "libName": "CTRE_Phoenix", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix", + "artifactId": "cci", + "version": "5.31.0", + "libName": "CTRE_PhoenixCCI", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix6", + "artifactId": "tools", + "version": "23.2.2", + "libName": "CTRE_PhoenixTools", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "linuxathena" + ], + "simMode": "hwsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "wpiapi-cpp-sim", + "version": "5.31.0", + "libName": "CTRE_Phoenix_WPISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "api-cpp-sim", + "version": "5.31.0", + "libName": "CTRE_PhoenixSim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix.sim", + "artifactId": "cci-sim", + "version": "5.31.0", + "libName": "CTRE_PhoenixCCISim", + "headerClassifier": "headers", + "sharedLibrary": true, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "linuxx86-64", + "osxuniversal" + ], + "simMode": "swsim" + }, + { + "groupId": "com.ctre.phoenix6.sim", + "artifactId": "tools-sim", + "version": "23.2.2", + "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": "23.2.2", + "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": "23.2.2", + "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": "23.2.2", + "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": "23.2.2", + "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": "23.2.2", + "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": "23.2.2", + "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": "23.2.2", + "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": "23.2.2", + "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..f2d0b7d --- /dev/null +++ b/vendordeps/REVLib.json @@ -0,0 +1,73 @@ +{ + "fileName": "REVLib.json", + "name": "REVLib", + "version": "2023.1.3", + "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", + "mavenUrls": [ + "https://maven.revrobotics.com/" + ], + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2023.json", + "javaDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-java", + "version": "2023.1.3" + } + ], + "jniDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-driver", + "version": "2023.1.3", + "skipInvalidPlatforms": true, + "isJar": false, + "validPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ], + "cppDependencies": [ + { + "groupId": "com.revrobotics.frc", + "artifactId": "REVLib-cpp", + "version": "2023.1.3", + "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": "2023.1.3", + "libName": "REVLibDriver", + "headerClassifier": "headers", + "sharedLibrary": false, + "skipInvalidPlatforms": true, + "binaryPlatforms": [ + "windowsx86-64", + "windowsx86", + "linuxarm64", + "linuxx86-64", + "linuxathena", + "linuxarm32", + "osxuniversal" + ] + } + ] +} \ No newline at end of file From 7eee9bb3dadaa1b24a7400d638b43717fd6e4dd3 Mon Sep 17 00:00:00 2001 From: ProgrammingSR Date: Mon, 8 Jan 2024 16:42:36 -0800 Subject: [PATCH 2/6] Changed motor controller to SparkFlex --- .../java/frc/robot/subsystems/SwerveModule.java | 14 +++++++------- vendordeps/REVLib.json | 13 +++++++------ 2 files changed, 14 insertions(+), 13 deletions(-) diff --git a/src/main/java/frc/robot/subsystems/SwerveModule.java b/src/main/java/frc/robot/subsystems/SwerveModule.java index 9647e5b..2651af0 100644 --- a/src/main/java/frc/robot/subsystems/SwerveModule.java +++ b/src/main/java/frc/robot/subsystems/SwerveModule.java @@ -6,9 +6,9 @@ import com.ctre.phoenix.sensors.CANCoder; import com.ctre.phoenix.sensors.SensorTimeBase; -import com.revrobotics.CANSparkMax; -import com.revrobotics.CANSparkMax.IdleMode; -import com.revrobotics.CANSparkMaxLowLevel.MotorType; +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; @@ -19,8 +19,8 @@ /** Add your docs here. */ public class SwerveModule { - private final CANSparkMax m_driveMotor; - private final CANSparkMax m_turningMotor; + private final CANSparkFlex m_driveMotor; + private final CANSparkFlex m_turningMotor; private final CANCoder m_turningEncoder; @@ -48,8 +48,8 @@ public SwerveModule( int turningEncoderPort, boolean driveMotorReversed, double turningEncoderOffset) { - m_driveMotor = new CANSparkMax(driveMotorPort, MotorType.kBrushless); - m_turningMotor = new CANSparkMax(turningMotorPort, MotorType.kBrushless); + 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 diff --git a/vendordeps/REVLib.json b/vendordeps/REVLib.json index f2d0b7d..0f3520e 100644 --- a/vendordeps/REVLib.json +++ b/vendordeps/REVLib.json @@ -1,24 +1,25 @@ { "fileName": "REVLib.json", "name": "REVLib", - "version": "2023.1.3", + "version": "2024.2.0", + "frcYear": "2024", "uuid": "3f48eb8c-50fe-43a6-9cb7-44c86353c4cb", "mavenUrls": [ "https://maven.revrobotics.com/" ], - "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2023.json", + "jsonUrl": "https://software-metadata.revrobotics.com/REVLib-2024.json", "javaDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-java", - "version": "2023.1.3" + "version": "2024.2.0" } ], "jniDependencies": [ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2023.1.3", + "version": "2024.2.0", "skipInvalidPlatforms": true, "isJar": false, "validPlatforms": [ @@ -36,7 +37,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-cpp", - "version": "2023.1.3", + "version": "2024.2.0", "libName": "REVLib", "headerClassifier": "headers", "sharedLibrary": false, @@ -54,7 +55,7 @@ { "groupId": "com.revrobotics.frc", "artifactId": "REVLib-driver", - "version": "2023.1.3", + "version": "2024.2.0", "libName": "REVLibDriver", "headerClassifier": "headers", "sharedLibrary": false, From 2bfaef86907dcb38c48f337c9e4dc393b22cd58e Mon Sep 17 00:00:00 2001 From: ProgrammingSR Date: Fri, 19 Jan 2024 17:03:39 -0800 Subject: [PATCH 3/6] feat: imported to 2024 --- build.gradle | 2 +- networktables.json | 1 + simgui-ds.json | 97 ++++++++++ simgui.json | 18 ++ src/main/java/frc/robot/Constants.java | 2 +- .../frc/robot/subsystems/SwerveModule.java | 24 +-- vendordeps/NavX.json | 13 +- vendordeps/{Phoenix.json => Phoenix6.json} | 166 +++++------------- 8 files changed, 179 insertions(+), 144 deletions(-) create mode 100644 networktables.json create mode 100644 simgui-ds.json create mode 100644 simgui.json rename vendordeps/{Phoenix.json => Phoenix6.json} (69%) 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 index 0da951c..ddfa1bf 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -72,7 +72,7 @@ public static final class DriveConstants { 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 double kPModuleTurningController = 0.3; public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics( new Translation2d(kWheelBase / 2, kTrackWidth / 2), diff --git a/src/main/java/frc/robot/subsystems/SwerveModule.java b/src/main/java/frc/robot/subsystems/SwerveModule.java index 2651af0..40578b8 100644 --- a/src/main/java/frc/robot/subsystems/SwerveModule.java +++ b/src/main/java/frc/robot/subsystems/SwerveModule.java @@ -4,8 +4,8 @@ package frc.robot.subsystems; -import com.ctre.phoenix.sensors.CANCoder; -import com.ctre.phoenix.sensors.SensorTimeBase; +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; @@ -14,6 +14,7 @@ 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; @@ -22,7 +23,7 @@ public class SwerveModule { private final CANSparkFlex m_driveMotor; private final CANSparkFlex m_turningMotor; - private final CANCoder m_turningEncoder; + private final CANcoder m_turningEncoder; private final PIDController m_turningPIDController = new PIDController(DriveConstants.kPModuleTurningController, 0, 0); @@ -50,7 +51,7 @@ public SwerveModule( double turningEncoderOffset) { m_driveMotor = new CANSparkFlex(driveMotorPort, MotorType.kBrushless); m_turningMotor = new CANSparkFlex(turningMotorPort, MotorType.kBrushless); - m_turningEncoder = new CANCoder(turningEncoderPort); + m_turningEncoder = new CANcoder(turningEncoderPort); // converts default units to meters per second m_driveMotor.getEncoder().setVelocityConversionFactor( @@ -59,10 +60,8 @@ public SwerveModule( m_driveMotor.setInverted(driveMotorReversed); m_turningMotor.setIdleMode(IdleMode.kBrake); - - // converts default units of CANCoders to radians - m_turningEncoder.configFeedbackCoefficient(Math.toRadians(0.087890625), "radians", SensorTimeBase.PerSecond); - m_turningEncoder.configMagnetOffset(-turningEncoderOffset); + + m_turningEncoder.getConfigurator().apply(new CANcoderConfiguration().MagnetSensor.withMagnetOffset(-turningEncoderOffset)); m_turningPIDController.enableContinuousInput(-Math.PI, Math.PI); } @@ -79,9 +78,12 @@ public SwerveModulePosition getPosition() { // 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(m_turningEncoder.getAbsolutePosition())) + new Rotation2d(Units.RadiansPerSecond.convertFrom(m_turningEncoder.getAbsolutePosition().getValueAsDouble(), Units.RotationsPerSecond))) : new SwerveModulePosition(m_distance, m_state.angle); } @@ -91,11 +93,11 @@ public SwerveModulePosition getPosition() { * @param desiredState Desired state with speed and angle. */ public void setDesiredState(SwerveModuleState desiredState) { - m_state = SwerveModuleState.optimize(desiredState, new Rotation2d(m_turningEncoder.getAbsolutePosition())); + 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(m_turningEncoder.getAbsolutePosition(), + turnOutput = m_turningPIDController.calculate(Units.RadiansPerSecond.convertFrom(m_turningEncoder.getAbsolutePosition().getValueAsDouble(), Units.RotationsPerSecond), m_state.angle.getRadians()); m_driveMotor.set(driveOutput); diff --git a/vendordeps/NavX.json b/vendordeps/NavX.json index 33d81f6..e978a5f 100644 --- a/vendordeps/NavX.json +++ b/vendordeps/NavX.json @@ -1,17 +1,18 @@ { "fileName": "NavX.json", - "name": "KauaiLabs_navX_FRC", - "version": "2023.0.4", + "name": "NavX", + "version": "2024.1.0", "uuid": "cb311d09-36e9-4143-a032-55bb2b94443b", + "frcYear": "2024", "mavenUrls": [ - "https://dev.studica.com/maven/release/2023/" + "https://dev.studica.com/maven/release/2024/" ], - "jsonUrl": "https://dev.studica.com/releases/2023/NavX.json", + "jsonUrl": "https://dev.studica.com/releases/2024/NavX.json", "javaDependencies": [ { "groupId": "com.kauailabs.navx.frc", "artifactId": "navx-frc-java", - "version": "2023.0.4" + "version": "2024.1.0" } ], "jniDependencies": [], @@ -19,7 +20,7 @@ { "groupId": "com.kauailabs.navx.frc", "artifactId": "navx-frc-cpp", - "version": "2023.0.4", + "version": "2024.1.0", "headerClassifier": "headers", "sourcesClassifier": "sources", "sharedLibrary": false, diff --git a/vendordeps/Phoenix.json b/vendordeps/Phoenix6.json similarity index 69% rename from vendordeps/Phoenix.json rename to vendordeps/Phoenix6.json index 614dc3a..69a4079 100644 --- a/vendordeps/Phoenix.json +++ b/vendordeps/Phoenix6.json @@ -1,56 +1,32 @@ { - "fileName": "Phoenix.json", - "name": "CTRE-Phoenix (v5)", - "version": "5.31.0+23.2.2", - "frcYear": 2023, - "uuid": "ab676553-b602-441f-a38d-f1296eff6537", + "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/phoenix/Phoenix5-frc2023-latest.json", - "javaDependencies": [ + "jsonUrl": "https://maven.ctr-electronics.com/release/com/ctre/phoenix6/latest/Phoenix6-frc2024-latest.json", + "conflictsWith": [ { - "groupId": "com.ctre.phoenix", - "artifactId": "api-java", - "version": "5.31.0" - }, + "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.phoenix", + "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-java", - "version": "5.31.0" + "version": "24.1.0" } ], "jniDependencies": [ - { - "groupId": "com.ctre.phoenix", - "artifactId": "cci", - "version": "5.31.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "cci-sim", - "version": "5.31.0", - "isJar": false, - "skipInvalidPlatforms": true, - "validPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -63,7 +39,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -76,7 +52,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -89,7 +65,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonFX", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -102,7 +78,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -115,7 +91,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -128,7 +104,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -141,7 +117,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -154,7 +130,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -167,7 +143,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "23.2.2", + "version": "24.1.0", "isJar": false, "skipInvalidPlatforms": true, "validPlatforms": [ @@ -180,40 +156,10 @@ ], "cppDependencies": [ { - "groupId": "com.ctre.phoenix", + "groupId": "com.ctre.phoenix6", "artifactId": "wpiapi-cpp", - "version": "5.31.0", - "libName": "CTRE_Phoenix_WPI", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix", - "artifactId": "api-cpp", - "version": "5.31.0", - "libName": "CTRE_Phoenix", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "linuxathena" - ], - "simMode": "hwsim" - }, - { - "groupId": "com.ctre.phoenix", - "artifactId": "cci", - "version": "5.31.0", - "libName": "CTRE_PhoenixCCI", + "version": "24.1.0", + "libName": "CTRE_Phoenix6_WPI", "headerClassifier": "headers", "sharedLibrary": true, "skipInvalidPlatforms": true, @@ -227,7 +173,7 @@ { "groupId": "com.ctre.phoenix6", "artifactId": "tools", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_PhoenixTools", "headerClassifier": "headers", "sharedLibrary": true, @@ -240,40 +186,10 @@ "simMode": "hwsim" }, { - "groupId": "com.ctre.phoenix.sim", + "groupId": "com.ctre.phoenix6.sim", "artifactId": "wpiapi-cpp-sim", - "version": "5.31.0", - "libName": "CTRE_Phoenix_WPISim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "api-cpp-sim", - "version": "5.31.0", - "libName": "CTRE_PhoenixSim", - "headerClassifier": "headers", - "sharedLibrary": true, - "skipInvalidPlatforms": true, - "binaryPlatforms": [ - "windowsx86-64", - "linuxx86-64", - "osxuniversal" - ], - "simMode": "swsim" - }, - { - "groupId": "com.ctre.phoenix.sim", - "artifactId": "cci-sim", - "version": "5.31.0", - "libName": "CTRE_PhoenixCCISim", + "version": "24.1.0", + "libName": "CTRE_Phoenix6_WPISim", "headerClassifier": "headers", "sharedLibrary": true, "skipInvalidPlatforms": true, @@ -287,7 +203,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "tools-sim", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_PhoenixTools_Sim", "headerClassifier": "headers", "sharedLibrary": true, @@ -302,7 +218,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonSRX", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimTalonSRX", "headerClassifier": "headers", "sharedLibrary": true, @@ -317,7 +233,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simTalonFX", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -332,7 +248,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simVictorSPX", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimVictorSPX", "headerClassifier": "headers", "sharedLibrary": true, @@ -347,7 +263,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simPigeonIMU", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimPigeonIMU", "headerClassifier": "headers", "sharedLibrary": true, @@ -362,7 +278,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simCANCoder", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimCANCoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -377,7 +293,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProTalonFX", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimProTalonFX", "headerClassifier": "headers", "sharedLibrary": true, @@ -392,7 +308,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProCANcoder", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimProCANcoder", "headerClassifier": "headers", "sharedLibrary": true, @@ -407,7 +323,7 @@ { "groupId": "com.ctre.phoenix6.sim", "artifactId": "simProPigeon2", - "version": "23.2.2", + "version": "24.1.0", "libName": "CTRE_SimProPigeon2", "headerClassifier": "headers", "sharedLibrary": true, From acbe8ae1eabba13c432522e6999569fb17af4709 Mon Sep 17 00:00:00 2001 From: Anay Nagar Date: Sun, 4 Feb 2024 10:49:02 -0800 Subject: [PATCH 4/6] "Merged" from swerve-base repo --- src/main/java/frc/robot/Constants.java | 30 +++- src/main/java/frc/robot/Main.java | 10 ++ src/main/java/frc/robot/Robot.java | 50 +++++-- src/main/java/frc/robot/RobotContainer.java | 12 +- .../frc/robot/subsystems/DriveSubsystem.java | 12 +- .../frc/robot/subsystems/SwerveModule.java | 46 ++++--- .../frc/robot/subsystems/VisionSubsystem.java | 128 ++++++++++++++++++ 7 files changed, 255 insertions(+), 33 deletions(-) create mode 100644 src/main/java/frc/robot/subsystems/VisionSubsystem.java diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index ddfa1bf..7a147a0 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -4,8 +4,13 @@ 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 @@ -24,7 +29,7 @@ public final class Constants { /** * Input/Output constants */ - public static class IOConstants { + public static final class IOConstants { public static final int kDriverControllerPort = 0; public static final double kControllerDeadband = 0.2; @@ -72,7 +77,7 @@ public static final class DriveConstants { 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 double kPModuleTurningController = -0.3; public static final SwerveDriveKinematics kDriveKinematics = new SwerveDriveKinematics( new Translation2d(kWheelBase / 2, kTrackWidth / 2), @@ -90,4 +95,25 @@ public static final class DriveConstants { // TODO: Tune this PID before running on a robot on the ground public static final double kPHeadingCorrectionController = 5; } + + 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 kOdometrySTDDevs = VecBuilder.fill(0.1, 0.1, 0.1); + public static final Vector kVisionSTDDevs = VecBuilder.fill(0.9, 0.9, 0.9); + + // Field size in meters + public static final double kFieldWidth = 8.21055; + public static final double kFieldLength = 16.54175; + } + } 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 07889d9..1fa8833 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -16,7 +16,12 @@ import frc.robot.Constants.IOConstants; import frc.robot.subsystems.DriveSubsystem; - +/* + * 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 robot's subsystems and commands are defined here private final DriveSubsystem m_robotDrive = new DriveSubsystem(); @@ -69,6 +74,11 @@ private void configureBindings() { .onTrue(new InstantCommand(m_robotDrive::zeroHeading, m_robotDrive)); } + /** + * 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 index aebcf73..f606d5b 100644 --- a/src/main/java/frc/robot/subsystems/DriveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/DriveSubsystem.java @@ -20,6 +20,7 @@ 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 { @@ -64,9 +65,9 @@ public class DriveSubsystem extends SubsystemBase { 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()); + m_gyro.getRotation2d(), m_swerveModulePositions, new Pose2d(), VisionConstants.kOdometrySTDDevs, + VisionConstants.kVisionSTDDevs); private final Field2d m_field = new Field2d(); @@ -88,7 +89,8 @@ public void periodic() { m_rearRight.getPosition() }; - m_poseEstimator.update(Robot.isReal() ? m_gyro.getRotation2d() : new Rotation2d(m_gyroAngle), m_swerveModulePositions); + m_poseEstimator.update(Robot.isReal() ? m_gyro.getRotation2d() : new Rotation2d(m_gyroAngle), + m_swerveModulePositions); m_field.setRobotPose(m_poseEstimator.getEstimatedPosition()); @@ -195,6 +197,10 @@ public void zeroHeading() { m_gyroAngle = 0; } + public void addVisionMeasurement(Pose2d pose, double timestamp) { + m_poseEstimator.addVisionMeasurement(pose, timestamp); + } + /** * Sets the swerve ModuleStates. * diff --git a/src/main/java/frc/robot/subsystems/SwerveModule.java b/src/main/java/frc/robot/subsystems/SwerveModule.java index 40578b8..f4de950 100644 --- a/src/main/java/frc/robot/subsystems/SwerveModule.java +++ b/src/main/java/frc/robot/subsystems/SwerveModule.java @@ -4,26 +4,26 @@ package frc.robot.subsystems; -import com.ctre.phoenix6.configs.CANcoderConfiguration; +import com.ctre.phoenix6.configs.CANcoderConfigurator; +import com.ctre.phoenix6.configs.MagnetSensorConfigs; import com.ctre.phoenix6.hardware.CANcoder; -import com.revrobotics.CANSparkFlex; 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 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 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); @@ -49,9 +49,10 @@ public SwerveModule( int turningEncoderPort, boolean driveMotorReversed, double turningEncoderOffset) { - m_driveMotor = new CANSparkFlex(driveMotorPort, MotorType.kBrushless); - m_turningMotor = new CANSparkFlex(turningMotorPort, MotorType.kBrushless); + 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( @@ -60,8 +61,10 @@ public SwerveModule( m_driveMotor.setInverted(driveMotorReversed); m_turningMotor.setIdleMode(IdleMode.kBrake); - - m_turningEncoder.getConfigurator().apply(new CANcoderConfiguration().MagnetSensor.withMagnetOffset(-turningEncoderOffset)); + + // 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); } @@ -78,12 +81,9 @@ public SwerveModulePosition getPosition() { // 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))) + getEncoderAngle(m_turningEncoder)) : new SwerveModulePosition(m_distance, m_state.angle); } @@ -93,14 +93,26 @@ public SwerveModulePosition getPosition() { * @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))); - + m_state = SwerveModuleState.optimize(desiredState, getEncoderAngle(m_turningEncoder)); driveOutput = m_state.speedMetersPerSecond / DriveConstants.kMaxSpeedMetersPerSecond; - turnOutput = m_turningPIDController.calculate(Units.RadiansPerSecond.convertFrom(m_turningEncoder.getAbsolutePosition().getValueAsDouble(), Units.RotationsPerSecond), + 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 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; + } + } +} From 42212f727800ff8d5437997fb161b9ec52b2e6d3 Mon Sep 17 00:00:00 2001 From: ProgrammingSR Date: Sun, 4 Feb 2024 16:33:03 -0800 Subject: [PATCH 5/6] chore: updated constants with the new chassis --- src/main/java/frc/robot/Constants.java | 28 +++++++++++++------------- 1 file changed, 14 insertions(+), 14 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index ddfa1bf..0c9348d 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -33,20 +33,20 @@ public static class IOConstants { 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 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; From 472fadab6640d676b0aa0e398f3ee49492cbbc16 Mon Sep 17 00:00:00 2001 From: Anay Nagar Date: Sun, 4 Feb 2024 17:30:15 -0800 Subject: [PATCH 6/6] Updated Constants --- src/main/java/frc/robot/Constants.java | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 7a147a0..868d243 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -65,16 +65,17 @@ public static final class DriveConstants { 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; + public static final double kTrackWidth = 0.57785; /** Distance between front and back wheels on robot (in meters). */ - public static final double kWheelBase = 0.5; + 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 = 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; @@ -85,10 +86,11 @@ public static final class DriveConstants { 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; + /** 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;