|
| 1 | +// Copyright (c) FIRST and other WPILib contributors. |
| 2 | +// Open Source Software; you can modify and/or share it under the terms of |
| 3 | +// the WPILib BSD license file in the root directory of this project. |
| 4 | + |
| 5 | +package frc.robot.subsystems; |
| 6 | + |
| 7 | +import com.ctre.phoenix6.hardware.CANrange; |
| 8 | +import com.revrobotics.spark.SparkFlex; |
| 9 | +import com.revrobotics.spark.SparkBase.PersistMode; |
| 10 | +import com.revrobotics.spark.SparkBase.ResetMode; |
| 11 | +import com.revrobotics.spark.SparkLowLevel.MotorType; |
| 12 | +import com.revrobotics.spark.config.SparkFlexConfig; |
| 13 | + |
| 14 | +import edu.wpi.first.math.MathUtil; |
| 15 | +import edu.wpi.first.math.controller.PIDController; |
| 16 | +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; |
| 17 | +import edu.wpi.first.wpilibj2.command.SubsystemBase; |
| 18 | +import frc.robot.Constants; |
| 19 | +import frc.robot.Robot; |
| 20 | +import frc.robot.Constants.ElevatorConstants; |
| 21 | + |
| 22 | +public class ElevatorSubsystem extends SubsystemBase { |
| 23 | + private final SparkFlex m_elevatorMotor; |
| 24 | + private final CANrange m_elevatorRange = new CANrange(ElevatorConstants.kElevatorCANrangePort); |
| 25 | + |
| 26 | + private final PIDController m_PIDController = new PIDController(ElevatorConstants.kPElevator, 0, 0, Constants.kFastPeriodicPeriod); |
| 27 | + |
| 28 | + private double m_targetPosition = 0; |
| 29 | + private double m_motorOffset = 0; |
| 30 | + |
| 31 | + /** Creates a new ElevatorSubsystem. */ |
| 32 | + public ElevatorSubsystem() { |
| 33 | + SparkFlexConfig motorConfig = new SparkFlexConfig(); |
| 34 | + motorConfig.encoder.positionConversionFactor(ElevatorConstants.kElevatorGearing); |
| 35 | + |
| 36 | + m_elevatorMotor = new SparkFlex(ElevatorConstants.kElevatorMotorPort, MotorType.kBrushless); |
| 37 | + // TODO: set to reset and persist after testing |
| 38 | + m_elevatorMotor.configure(motorConfig, ResetMode.kNoResetSafeParameters, PersistMode.kNoPersistParameters); |
| 39 | + } |
| 40 | + |
| 41 | + @Override |
| 42 | + public void periodic() { |
| 43 | + // This method will be called once per scheduler run |
| 44 | + if (m_elevatorRange.getDistance().getValueAsDouble() < ElevatorConstants.kElevatorDistanceThreshold) { |
| 45 | + // This offset is set when the distance sensor detects that the elevator is at the bottom |
| 46 | + // At the bottom, the motor's position + offset should equal 0 |
| 47 | + m_motorOffset = -m_elevatorMotor.getEncoder().getPosition(); |
| 48 | + } |
| 49 | + } |
| 50 | + |
| 51 | + public void fastPeriodic() { |
| 52 | + double output = m_PIDController.calculate( |
| 53 | + m_elevatorMotor.getEncoder().getPosition() + m_motorOffset, |
| 54 | + m_targetPosition) + ElevatorConstants.kElevatorFeedForward; |
| 55 | + output = MathUtil.clamp(output, -ElevatorConstants.kElevatorMaxSpeed, ElevatorConstants.kElevatorMaxSpeed); |
| 56 | + m_elevatorMotor.set(output); |
| 57 | + |
| 58 | + SmartDashboard.putNumber("elevator motor output", output); |
| 59 | + } |
| 60 | + |
| 61 | + public void trackPosition(double leftY) { |
| 62 | + // Moves the target position by leftY multiplied by the constant kSpeed, clamped between the top and bottom heights |
| 63 | + m_targetPosition += leftY * ElevatorConstants.kElevatorSpeedScalar * Robot.kDefaultPeriod; |
| 64 | + m_targetPosition = MathUtil.clamp(m_targetPosition, ElevatorConstants.kElevatorBottom, ElevatorConstants.kElevatorTop); |
| 65 | + // Display this number for now so we can see it |
| 66 | + SmartDashboard.putNumber("elevator targetPosition", m_targetPosition); |
| 67 | + } |
| 68 | + |
| 69 | + public void setHeight(double level) { |
| 70 | + // Set the elevator target height to the corresponding level (L1, L2, L3, L4) |
| 71 | + m_targetPosition = level; |
| 72 | + } |
| 73 | +} |
0 commit comments