granite state day 1 code
This commit is contained in:
parent
662c31702f
commit
b9eb688584
@ -262,8 +262,8 @@ public class RobotContainer {
|
||||
driver.a().whileTrue(indexer.shootNote(() -> 1.0));
|
||||
|
||||
operator.back().toggleOnTrue(shooter.manualPivot(
|
||||
() -> operator.getLeftY(),
|
||||
() -> operator.getRightTriggerAxis()-operator.getLeftTriggerAxis()
|
||||
() -> MathUtil.clamp(-operator.getLeftY(), -0.75, 0.75),
|
||||
() -> MathUtil.clamp(operator.getRightTriggerAxis()-operator.getLeftTriggerAxis(), -0.75, 0.75)
|
||||
));
|
||||
|
||||
operator.start().onTrue(shooter.zeroEncoder());
|
||||
|
@ -24,7 +24,7 @@ public final class AutoConstants {
|
||||
new PIDConstants(kPXController),
|
||||
new PIDConstants(kPThetaController),
|
||||
kMaxSpeedMetersPerSecond,
|
||||
Units.inchesToMeters(34.65),
|
||||
Units.inchesToMeters(Math.sqrt(Math.pow(28-17.5, 2)+ Math.pow(28-1.75, 2))),
|
||||
new ReplanningConfig()
|
||||
);
|
||||
|
||||
|
@ -8,6 +8,7 @@ import com.ctre.phoenix.motorcontrol.can.VictorSPX;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.constants.ClimberConstants;
|
||||
import frc.robot.constants.ShooterConstants;
|
||||
|
||||
public class Climber extends SubsystemBase {
|
||||
private VictorSPX motor1;
|
||||
@ -29,11 +30,8 @@ public class Climber extends SubsystemBase {
|
||||
public Command setSpeedWithSupplier(DoubleSupplier speed) {
|
||||
return run(() -> {
|
||||
|
||||
if(shooterAngle.getAsDouble() > Math.toRadians(-5.0)){
|
||||
motor1.set(VictorSPXControlMode.PercentOutput, speed.getAsDouble());
|
||||
}else{
|
||||
motor1.set(VictorSPXControlMode.PercentOutput, 0);
|
||||
}
|
||||
motor1.set(VictorSPXControlMode.PercentOutput, speed.getAsDouble());
|
||||
|
||||
});
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user