mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[examples] Fix swerve examples to use getDistance for turning encoder (#4652)
This commit is contained in:
@@ -73,7 +73,7 @@ public class SwerveModule {
|
||||
// resolution.
|
||||
m_driveEncoder.setDistancePerPulse(2 * Math.PI * kWheelRadius / kEncoderResolution);
|
||||
|
||||
// Set the distance (in this case, angle) per pulse for the turning encoder.
|
||||
// Set the distance (in this case, angle) in radians per pulse for the turning encoder.
|
||||
// This is the the angle through an entire rotation (2 * pi) divided by the
|
||||
// encoder resolution.
|
||||
m_turningEncoder.setDistancePerPulse(2 * Math.PI / kEncoderResolution);
|
||||
@@ -89,7 +89,8 @@ public class SwerveModule {
|
||||
* @return The current state of the module.
|
||||
*/
|
||||
public SwerveModuleState getState() {
|
||||
return new SwerveModuleState(m_driveEncoder.getRate(), new Rotation2d(m_turningEncoder.get()));
|
||||
return new SwerveModuleState(
|
||||
m_driveEncoder.getRate(), new Rotation2d(m_turningEncoder.getDistance()));
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -99,7 +100,7 @@ public class SwerveModule {
|
||||
*/
|
||||
public SwerveModulePosition getPosition() {
|
||||
return new SwerveModulePosition(
|
||||
m_driveEncoder.getDistance(), new Rotation2d(m_turningEncoder.get()));
|
||||
m_driveEncoder.getDistance(), new Rotation2d(m_turningEncoder.getDistance()));
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -110,7 +111,7 @@ public class SwerveModule {
|
||||
public void setDesiredState(SwerveModuleState desiredState) {
|
||||
// Optimize the reference state to avoid spinning further than 90 degrees
|
||||
SwerveModuleState state =
|
||||
SwerveModuleState.optimize(desiredState, new Rotation2d(m_turningEncoder.get()));
|
||||
SwerveModuleState.optimize(desiredState, new Rotation2d(m_turningEncoder.getDistance()));
|
||||
|
||||
// Calculate the drive output from the drive PID controller.
|
||||
final double driveOutput =
|
||||
@@ -120,7 +121,7 @@ public class SwerveModule {
|
||||
|
||||
// Calculate the turning motor output from the turning PID controller.
|
||||
final double turnOutput =
|
||||
m_turningPIDController.calculate(m_turningEncoder.get(), state.angle.getRadians());
|
||||
m_turningPIDController.calculate(m_turningEncoder.getDistance(), state.angle.getRadians());
|
||||
|
||||
final double turnFeedforward =
|
||||
m_turnFeedforward.calculate(m_turningPIDController.getSetpoint().velocity);
|
||||
|
||||
@@ -66,7 +66,7 @@ public class SwerveModule {
|
||||
// Set whether drive encoder should be reversed or not
|
||||
m_driveEncoder.setReverseDirection(driveEncoderReversed);
|
||||
|
||||
// Set the distance (in this case, angle) per pulse for the turning encoder.
|
||||
// Set the distance (in this case, angle) in radians per pulse for the turning encoder.
|
||||
// This is the the angle through an entire rotation (2 * pi) divided by the
|
||||
// encoder resolution.
|
||||
m_turningEncoder.setDistancePerPulse(ModuleConstants.kTurningEncoderDistancePerPulse);
|
||||
@@ -85,7 +85,8 @@ public class SwerveModule {
|
||||
* @return The current state of the module.
|
||||
*/
|
||||
public SwerveModuleState getState() {
|
||||
return new SwerveModuleState(m_driveEncoder.getRate(), new Rotation2d(m_turningEncoder.get()));
|
||||
return new SwerveModuleState(
|
||||
m_driveEncoder.getRate(), new Rotation2d(m_turningEncoder.getDistance()));
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -95,7 +96,7 @@ public class SwerveModule {
|
||||
*/
|
||||
public SwerveModulePosition getPosition() {
|
||||
return new SwerveModulePosition(
|
||||
m_driveEncoder.getDistance(), new Rotation2d(m_turningEncoder.get()));
|
||||
m_driveEncoder.getDistance(), new Rotation2d(m_turningEncoder.getDistance()));
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -106,7 +107,7 @@ public class SwerveModule {
|
||||
public void setDesiredState(SwerveModuleState desiredState) {
|
||||
// Optimize the reference state to avoid spinning further than 90 degrees
|
||||
SwerveModuleState state =
|
||||
SwerveModuleState.optimize(desiredState, new Rotation2d(m_turningEncoder.get()));
|
||||
SwerveModuleState.optimize(desiredState, new Rotation2d(m_turningEncoder.getDistance()));
|
||||
|
||||
// Calculate the drive output from the drive PID controller.
|
||||
final double driveOutput =
|
||||
@@ -114,7 +115,7 @@ public class SwerveModule {
|
||||
|
||||
// Calculate the turning motor output from the turning PID controller.
|
||||
final double turnOutput =
|
||||
m_turningPIDController.calculate(m_turningEncoder.get(), state.angle.getRadians());
|
||||
m_turningPIDController.calculate(m_turningEncoder.getDistance(), state.angle.getRadians());
|
||||
|
||||
// Calculate the turning motor output from the turning PID controller.
|
||||
m_driveMotor.set(driveOutput);
|
||||
|
||||
@@ -73,7 +73,7 @@ public class SwerveModule {
|
||||
// resolution.
|
||||
m_driveEncoder.setDistancePerPulse(2 * Math.PI * kWheelRadius / kEncoderResolution);
|
||||
|
||||
// Set the distance (in this case, angle) per pulse for the turning encoder.
|
||||
// Set the distance (in this case, angle) in radians per pulse for the turning encoder.
|
||||
// This is the the angle through an entire rotation (2 * pi) divided by the
|
||||
// encoder resolution.
|
||||
m_turningEncoder.setDistancePerPulse(2 * Math.PI / kEncoderResolution);
|
||||
@@ -89,7 +89,8 @@ public class SwerveModule {
|
||||
* @return The current state of the module.
|
||||
*/
|
||||
public SwerveModuleState getState() {
|
||||
return new SwerveModuleState(m_driveEncoder.getRate(), new Rotation2d(m_turningEncoder.get()));
|
||||
return new SwerveModuleState(
|
||||
m_driveEncoder.getRate(), new Rotation2d(m_turningEncoder.getDistance()));
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -99,7 +100,7 @@ public class SwerveModule {
|
||||
*/
|
||||
public SwerveModulePosition getPosition() {
|
||||
return new SwerveModulePosition(
|
||||
m_driveEncoder.getDistance(), new Rotation2d(m_turningEncoder.get()));
|
||||
m_driveEncoder.getDistance(), new Rotation2d(m_turningEncoder.getDistance()));
|
||||
}
|
||||
|
||||
/**
|
||||
@@ -110,7 +111,7 @@ public class SwerveModule {
|
||||
public void setDesiredState(SwerveModuleState desiredState) {
|
||||
// Optimize the reference state to avoid spinning further than 90 degrees
|
||||
SwerveModuleState state =
|
||||
SwerveModuleState.optimize(desiredState, new Rotation2d(m_turningEncoder.get()));
|
||||
SwerveModuleState.optimize(desiredState, new Rotation2d(m_turningEncoder.getDistance()));
|
||||
|
||||
// Calculate the drive output from the drive PID controller.
|
||||
final double driveOutput =
|
||||
@@ -120,7 +121,7 @@ public class SwerveModule {
|
||||
|
||||
// Calculate the turning motor output from the turning PID controller.
|
||||
final double turnOutput =
|
||||
m_turningPIDController.calculate(m_turningEncoder.get(), state.angle.getRadians());
|
||||
m_turningPIDController.calculate(m_turningEncoder.getDistance(), state.angle.getRadians());
|
||||
|
||||
final double turnFeedforward =
|
||||
m_turnFeedforward.calculate(m_turningPIDController.getSetpoint().velocity);
|
||||
|
||||
Reference in New Issue
Block a user