This commit is contained in:
NoahLacks63 2025-05-20 18:59:22 -04:00
parent f28a984bf3
commit 44f00f75e1
3 changed files with 35 additions and 14 deletions

View File

@ -31,11 +31,11 @@ public class RobotContainer {
private void configureBindings() { private void configureBindings() {
driver.x().onTrue( driver.x().onTrue(
closedLoopTest.incrementPosition(-360) closedLoopTest.setPosition(360)
); );
driver.b().onTrue( driver.b().onTrue(
closedLoopTest.incrementPosition(360) closedLoopTest.setPosition(0)
); );
driver.y().onTrue( driver.y().onTrue(

View File

@ -1,15 +1,21 @@
package frc.robot.constants; package frc.robot.constants;
import com.revrobotics.spark.ClosedLoopSlot;
import com.revrobotics.spark.config.SparkMaxConfig; import com.revrobotics.spark.config.SparkMaxConfig;
import com.revrobotics.spark.config.MAXMotionConfig.MAXMotionPositionMode;
public class ClosedLoopTestConstants { public class ClosedLoopTestConstants {
public static final double kPositionConversionFactor = 360.0/25.0; public static final double kPositionConversionFactor = 360.0/25.0;
public static final double kVelocityConversionFactor = kPositionConversionFactor / 60.0; public static final double kVelocityConversionFactor = kPositionConversionFactor / 60.0;
public static final double kP = 0.001; public static final double kVeloP = 0.001;
public static final double kI = 0; public static final double kVeloI = 0;
public static final double kD = 0; public static final double kVeloD = 0;
public static final double kF = 0; public static final double kVeloF = 0;
public static final double kPosP = 0.001;
public static final double kPosI = 0;
public static final double kPosD = 0;
public static final double kAllowedClosedLoopError = 4; public static final double kAllowedClosedLoopError = 4;
public static final double kMaxAcceleration = 180; public static final double kMaxAcceleration = 180;
@ -23,14 +29,20 @@ public class ClosedLoopTestConstants {
.velocityConversionFactor(kVelocityConversionFactor); .velocityConversionFactor(kVelocityConversionFactor);
motorConfig.closedLoop motorConfig.closedLoop
.pidf( .pidf(
kP, kVeloP,
kI, kVeloI,
kD, kVeloD,
kF kVeloF,
ClosedLoopSlot.kSlot0
).pid(
kPosP,
kPosI,
kPosD,
ClosedLoopSlot.kSlot1
); );
motorConfig.closedLoop.maxMotion motorConfig.closedLoop.maxMotion
.allowedClosedLoopError(kAllowedClosedLoopError) .allowedClosedLoopError(kAllowedClosedLoopError)
.maxAcceleration(kMaxAcceleration) .maxAcceleration(kMaxAcceleration)
.maxVelocity(kMaxVelocity); .maxVelocity(kMaxVelocity).positionMode(MAXMotionPositionMode.kMAXMotionTrapezoidal);
} }
} }

View File

@ -1,6 +1,7 @@
package frc.robot.subsystems; package frc.robot.subsystems;
import com.revrobotics.RelativeEncoder; import com.revrobotics.RelativeEncoder;
import com.revrobotics.spark.ClosedLoopSlot;
import com.revrobotics.spark.SparkClosedLoopController; import com.revrobotics.spark.SparkClosedLoopController;
import com.revrobotics.spark.SparkMax; import com.revrobotics.spark.SparkMax;
import com.revrobotics.spark.SparkBase.ControlType; import com.revrobotics.spark.SparkBase.ControlType;
@ -37,10 +38,17 @@ public class ClosedLoopTest extends SubsystemBase {
} }
public Command incrementPosition(double increment) { public Command incrementPosition(double increment) {
return runOnce(() -> {
setPosition(encoder.getPosition() + increment);
});
}
public Command setPosition(double position) {
return runOnce(() -> { return runOnce(() -> {
controller.setReference( controller.setReference(
encoder.getPosition() + increment, position,
ControlType.kMAXMotionPositionControl ControlType.kMAXMotionPositionControl,
ClosedLoopSlot.kSlot0
); );
}); });
} }
@ -49,7 +57,8 @@ public class ClosedLoopTest extends SubsystemBase {
return runOnce(() -> { return runOnce(() -> {
controller.setReference( controller.setReference(
velocity, velocity,
ControlType.kMAXMotionVelocityControl ControlType.kMAXMotionVelocityControl,
ClosedLoopSlot.kSlot0
); );
}); });
} }