offsets (INCOMPLETE DO NOT TOUCH)

This commit is contained in:
aarav18
2023-01-21 15:16:22 -07:00
parent 3697360963
commit 56ad89a974
6 changed files with 149 additions and 55 deletions
@@ -19,19 +19,21 @@ import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc4388.robot.Constants.SwerveDriveConstants;
import frc4388.utility.Gains;
import frc4388.utility.RobotEncoder;
public class SwerveModule extends SubsystemBase {
public WPI_TalonFX driveMotor;
public WPI_TalonFX angleMotor;
private CANCoder canCoder;
// private CANCoder canCoder;
private CANCoder encoder;
public static Gains swerveGains = SwerveDriveConstants.PIDConstants.SWERVE_GAINS;
/** Creates a new SwerveModule. */
public SwerveModule(WPI_TalonFX driveMotor, WPI_TalonFX angleMotor, CANCoder canCoder, double offset) {
public SwerveModule(WPI_TalonFX driveMotor, WPI_TalonFX angleMotor, /*CANCoder canCoder*/CANCoder encoder, double offset) {
this.driveMotor = driveMotor;
this.angleMotor = angleMotor;
this.canCoder = canCoder;
this.encoder = encoder;
TalonFXConfiguration angleConfig = new TalonFXConfiguration();
angleConfig.slot0.kP = swerveGains.kP;
@@ -39,14 +41,16 @@ public class SwerveModule extends SubsystemBase {
angleConfig.slot0.kD = swerveGains.kD;
// use the CANcoder as the remote sensor for the primary TalonFX PID
angleConfig.remoteFilter0.remoteSensorDeviceID = canCoder.getDeviceID();
angleConfig.remoteFilter0.remoteSensorDeviceID = encoder.getDeviceID();
angleConfig.remoteFilter0.remoteSensorSource = RemoteSensorSource.CANCoder;
angleConfig.primaryPID.selectedFeedbackSensor = FeedbackDevice.RemoteSensor0;
angleMotor.configAllSettings(angleConfig);
CANCoderConfiguration canCoderConfig = new CANCoderConfiguration();
canCoderConfig.magnetOffsetDegrees = offset;
canCoder.configAllSettings(canCoderConfig);
encoder.configAllSettings(canCoderConfig);
// canCoderConfig.magnetOffsetDegrees = 270;
}
/**
@@ -70,7 +74,7 @@ public class SwerveModule extends SubsystemBase {
* @return the CANcoder of the SwerveModule
*/
public CANCoder getEncoder() {
return this.canCoder;
return this.encoder;
}
/**
@@ -79,7 +83,7 @@ public class SwerveModule extends SubsystemBase {
*/
public Rotation2d getAngle() {
// Note: This assumes that the CANCoders are setup with the default feedback coefficient and the sensor value reports degrees.
return Rotation2d.fromDegrees(canCoder.getAbsolutePosition());
return Rotation2d.fromDegrees(encoder.getAbsolutePosition());
}
public void stop() {
@@ -126,15 +130,17 @@ public class SwerveModule extends SubsystemBase {
double deltaTicks = (rotationDelta.getDegrees() / 360.) * SwerveDriveConstants.Conversions.CANCODER_TICKS_PER_ROTATION;
// convert the CANCoder from its position reading to ticks
double currentTicks = canCoder.getPosition() / canCoder.configGetFeedbackCoefficient();
double currentTicks = encoder.getPosition() / encoder.configGetFeedbackCoefficient();
angleMotor.set(TalonFXControlMode.Position, currentTicks + deltaTicks);
double feetPerSecond = Units.metersToFeet(state.speedMetersPerSecond);
driveMotor.set(angleMotor.get() + feetPerSecond / SwerveDriveConstants.MAX_SPEED_FEET_PER_SECOND);
driveMotor.set(/*angleMotor.get() + */feetPerSecond / SwerveDriveConstants.MAX_SPEED_FEET_PER_SECOND);
}
public void reset() {
canCoder.setPositionToAbsolute();
public void reset(double position) {
// encoder.setPosition(position);
encoder.setPositionToAbsolute();
// canCoder.setPosition(1024);
}
public double getCurrent() {