Skip to content

Commit

Permalink
Browse files Browse the repository at this point in the history
  • Loading branch information
PGgit08 committed Mar 21, 2024
2 parents ab179e9 + 587faa1 commit a015a5a
Show file tree
Hide file tree
Showing 2 changed files with 16 additions and 4 deletions.
2 changes: 2 additions & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -153,6 +153,8 @@ public static class Ports {
public static final int DRIVER_CONTROLLER = 0;
public static final int OPERATOR_CONTROLLER = 1;
public static final int LEDS = 0; // pwm port

public static final int ANGLE_ENCODER = 0; // TODO: GET REAL VALUE
}

// static field constants
Expand Down
18 changes: 14 additions & 4 deletions src/main/java/frc/robot/subsystems/ShooterSubsystem.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,6 +13,7 @@
import edu.wpi.first.math.filter.Debouncer;
import edu.wpi.first.math.filter.Debouncer.DebounceType;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.wpilibj.DutyCycleEncoder;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;
Expand All @@ -36,6 +37,8 @@ public class ShooterSubsystem extends SubsystemBase {
private final CANSparkMax _rightMotor = new CANSparkMax(Constants.CAN.SHOOTER_RIGHT, MotorType.kBrushless);

private final TalonFX _angleMotor = new TalonFX(Constants.CAN.SHOOTER_ANGLE);

private final DutyCycleEncoder _angleEncoder = new DutyCycleEncoder(Constants.Ports.ANGLE_ENCODER);

private final RelativeEncoder _leftEncoder = _leftMotor.getEncoder();

Expand Down Expand Up @@ -69,12 +72,15 @@ public ShooterSubsystem() {
softLimits.ForwardSoftLimitThreshold = 69 * Constants.Physical.SHOOTER_ANGLE_GEAR_RATIO / 360;
softLimits.ReverseSoftLimitThreshold = -25 * Constants.Physical.SHOOTER_ANGLE_GEAR_RATIO / 360;

softLimits.ForwardSoftLimitEnable = true;
softLimits.ReverseSoftLimitEnable = true;
softLimits.ForwardSoftLimitEnable = false;
softLimits.ReverseSoftLimitEnable = false;

_angleMotor.getConfigurator().apply(softLimits);

_angleController.setTolerance(0.2);

_angleEncoder.setDistancePerRotation(360);
// _angleEncoder.reset();
}

@Override
Expand Down Expand Up @@ -143,7 +149,8 @@ public void setAngle(double angleDegrees) {

/** Get the angle of the shooter in degrees. */
public double getAngle() {
return _angleMotor.getPosition().getValueAsDouble() / Constants.Physical.SHOOTER_ANGLE_GEAR_RATIO * 360;
// return _angleMotor.getPosition().getValueAsDouble() / Constants.Physical.SHOOTER_ANGLE_GEAR_RATIO * 360;
return _angleEncoder.getDistance();
}

/** Returns the angular velocity of the motor. (deg/sec) */
Expand All @@ -161,6 +168,10 @@ public double getVelocity() {
* included).
*/
public void driveAngle(double speed) {
if ((getAngle() >= 65 && speed > 0) || (getAngle() <= -25 && speed < 0)) {
speed = 0;
}

_angleMotor.set(UtilFuncs.FromVolts(_angleFeed.calculate(Math.toRadians(getAngle()), 0)) + speed);
// _angleMotor.set(speed);
}
Expand Down Expand Up @@ -207,5 +218,4 @@ public void spinShooter(double speed) {
public void stopShooter() {
spinShooter(0);
}

}

0 comments on commit a015a5a

Please sign in to comment.