Upgrade to 2022

* Update license
* Remove arcade drive
* Correct indentation
* Disable RobotGyro (new gyro is untested)
This commit is contained in:
nathanrsxtn
2022-01-11 11:05:52 -07:00
parent 731310fbc8
commit 71563e6759
38 changed files with 1507 additions and 1541 deletions
@@ -12,22 +12,20 @@ import com.ctre.phoenix.motorcontrol.can.WPI_TalonFX;
import com.ctre.phoenix.sensors.CANCoder;
import com.ctre.phoenix.sensors.CANCoderConfiguration;
import edu.wpi.first.wpilibj.geometry.Rotation2d;
import edu.wpi.first.wpilibj.kinematics.SwerveModuleState;
import edu.wpi.first.wpilibj.simulation.EncoderSim;
import edu.wpi.first.wpilibj.util.Units;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc4388.robot.Constants.SwerveDriveConstants;
import frc4388.utility.Gains;
public class SwerveModule extends SubsystemBase {
private WPI_TalonFX driveMotor;
private WPI_TalonFX angleMotor;
private CANCoder canCoder;
public static Gains m_swerveGains = SwerveDriveConstants.SWERVE_GAINS;
private static double kEncoderTicksPerRotation = 4096;
private WPI_TalonFX driveMotor;
private WPI_TalonFX angleMotor;
private CANCoder canCoder;
public static Gains m_swerveGains = SwerveDriveConstants.SWERVE_GAINS;
private static double kEncoderTicksPerRotation = 4096;
/** Creates a new SwerveModule. */
public SwerveModule(WPI_TalonFX driveMotor, WPI_TalonFX angleMotor, CANCoder canCoder) {
@@ -47,30 +45,32 @@ public class SwerveModule extends SubsystemBase {
angleTalonFXConfiguration.primaryPID.selectedFeedbackSensor = FeedbackDevice.RemoteSensor0;
angleMotor.configAllSettings(angleTalonFXConfiguration);
/*TalonFXConfiguration driveTalonFXConfiguration = new TalonFXConfiguration();
driveTalonFXConfiguration.slot0.kP = kDriveP;
driveTalonFXConfiguration.slot0.kI = kDriveI;
driveTalonFXConfiguration.slot0.kD = kDriveD;
driveTalonFXConfiguration.slot0.kF = kDriveF;
driveMotor.configAllSettings(driveTalonFXConfiguration);*/
/*
* TalonFXConfiguration driveTalonFXConfiguration = new TalonFXConfiguration();
*
* driveTalonFXConfiguration.slot0.kP = kDriveP;
* driveTalonFXConfiguration.slot0.kI = kDriveI;
* driveTalonFXConfiguration.slot0.kD = kDriveD;
* driveTalonFXConfiguration.slot0.kF = kDriveF;
*
* driveMotor.configAllSettings(driveTalonFXConfiguration);
*/
CANCoderConfiguration canCoderConfiguration = new CANCoderConfiguration();
//CANCODER CONFIG
// CANCODER CONFIG
canCoder.configAllSettings(canCoderConfiguration);
}
public Rotation2d getAngle() {
// Note: This assumes the CANCoders are setup with the default feedback coefficient
// and the sesnor value reports degrees.
// Note: This assumes the CANCoders are setup with the default feedback coefficient and the sesnor value reports degrees.
return Rotation2d.fromDegrees(canCoder.getAbsolutePosition());
}
/**
* Set the speed + rotation of the swerve module from a SwerveModuleState object
* @param desiredState - A SwerveModuleState representing the desired new state of the module
*
* @param desiredState - A SwerveModuleState representing the desired new state
* of the module
*/
public void setDesiredState(SwerveModuleState desiredState) {
Rotation2d currentRotation = getAngle();
@@ -86,7 +86,6 @@ public class SwerveModule extends SubsystemBase {
double desiredTicks = currentTicks + deltaTicks;
angleMotor.set(TalonFXControlMode.Position, desiredTicks);
double feetPerSecond = Units.metersToFeet(state.speedMetersPerSecond);
driveMotor.set(angleMotor.get() + feetPerSecond / SwerveDriveConstants.SPEED_FEET_PER_SECOND_AT_FULL_POWER);
}