Skip to content
This repository has been archived by the owner on Jan 2, 2025. It is now read-only.

Commit

Permalink
fix arm trying to kill us
Browse files Browse the repository at this point in the history
  • Loading branch information
jack60612 committed Feb 22, 2024
1 parent 842973f commit ba0afc6
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 10 deletions.
1 change: 1 addition & 0 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -193,6 +193,7 @@ private void bindArmSysIDCommands() {
m_controller1.x().whileTrue(m_armSubsystem.sysIdDynamic(SysIdRoutine.Direction.kForward));
m_controller1.y().whileTrue(m_armSubsystem.sysIdDynamic(SysIdRoutine.Direction.kReverse));
m_controller1.leftTrigger().whileTrue(new InstantCommand(() -> DataLogManager.stop()));
m_armSubsystem.disablePID();
}

private void bindShooterSysIDCommands() {
Expand Down
25 changes: 15 additions & 10 deletions src/main/java/frc/robot/subsystems/ArmSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,7 @@ public class ArmSubsystem extends SubsystemBase {
Units.degreesToRadians(45); // angle to be when shooting into amp
private final double karmMaxVelocity = 2; // m/s
private final double karmMaxAcceleration = 1; // m/s^2
private boolean kPIDEnabled = true;
// general drive constants
// https://www.chiefdelphi.com/t/encoders-velocity-to-m-s/390332/2
// https://sciencing.com/convert-rpm-linear-speed-8232280.html
Expand Down Expand Up @@ -178,19 +179,23 @@ public void zeroEncoders() {
m_MainEncoder.setPosition(0);
}

public void disablePID() {
kPIDEnabled = false;
}

@Override
public void periodic() {
// This method will be called once per scheduler run

// update the setpoint
m_setpoint = m_armTrapezoidProfile.calculate(kDt, m_setpoint, m_goal);

// Call the controller and feedforward with the target position and velocity
m_armMainPIDController.setReference(
m_setpoint.position,
CANSparkBase.ControlType.kPosition,
0,
m_armFeedforward.calculate(m_setpoint.position, m_setpoint.velocity));
if (kPIDEnabled) {
// update the setpoint
m_setpoint = m_armTrapezoidProfile.calculate(kDt, m_setpoint, m_goal);
// Call the controller and feedforward with the target position and velocity
m_armMainPIDController.setReference(
m_setpoint.position,
CANSparkBase.ControlType.kPosition,
0,
m_armFeedforward.calculate(m_setpoint.position, m_setpoint.velocity));
}
m_shooterState.updateDash();
}

Expand Down

0 comments on commit ba0afc6

Please sign in to comment.