mirror of
https://github.com/Team4388/2022NoWayHome.git
synced 2026-06-09 08:48:07 -06:00
Merge branch 'testRoboReveal' of https://github.com/Team4388/2022NoWayHome into testRoboReveal
This commit is contained in:
@@ -12,6 +12,7 @@ import com.revrobotics.CANSparkMax.ControlType;
|
||||
import com.revrobotics.CANSparkMax.SoftLimitDirection;
|
||||
import com.revrobotics.SparkMaxRelativeEncoder.Type;
|
||||
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
import frc4388.robot.Constants.ShooterConstants;
|
||||
@@ -49,7 +50,7 @@ public class Hood extends SubsystemBase {
|
||||
|
||||
m_angleAdjusterMotor.setSoftLimit(SoftLimitDirection.kForward, (float) ShooterConstants.HOOD_FORWARD_LIMIT);
|
||||
m_angleAdjusterMotor.setSoftLimit(SoftLimitDirection.kReverse, (float) ShooterConstants.HOOD_REVERSE_LIMIT);
|
||||
setHoodSoftLimits(true);
|
||||
setHoodSoftLimits(false);
|
||||
}
|
||||
|
||||
|
||||
@@ -86,6 +87,7 @@ public class Hood extends SubsystemBase {
|
||||
*/
|
||||
public void runHood(double input) {
|
||||
m_angleAdjusterMotor.set(input);
|
||||
SmartDashboard.putNumber("Hood Angle", m_angleAdjusterMotor.getAlternateEncoder(1024).getPosition());
|
||||
}
|
||||
|
||||
public void resetGyroAngleAdj(){
|
||||
|
||||
Reference in New Issue
Block a user