system testing code
This commit is contained in:
parent
ba548a447a
commit
570696fa7a
@ -133,14 +133,14 @@ public class RobotContainer {
|
||||
);
|
||||
|
||||
//intake.setDefaultCommand(intake.intakeUpCommand());
|
||||
intake.setDefaultCommand(intake.manualPivot(operator::getLeftY));
|
||||
intake.setDefaultCommand(intake.manualPivot(operator::getLeftY, driver::getLeftTriggerAxis));
|
||||
|
||||
// shooter.setDefaultCommand(shooter.angleSpeedsSetpoints(ShooterConstants.kShooterLoadAngle, 0.0, 0.0));
|
||||
shooter.setDefaultCommand(shooter.manualPivot(operator::getRightY);
|
||||
shooter.setDefaultCommand(shooter.manualPivot(operator::getRightY, operator::getLeftTriggerAxis));
|
||||
|
||||
climber.setDefaultCommand(climber.stop());
|
||||
|
||||
indexer.setDefaultCommand(indexer.autoIndexing());
|
||||
indexer.setDefaultCommand(indexer.shootNote(operator::getRightTriggerAxis));
|
||||
|
||||
driver.povCenter().onFalse(
|
||||
drivetrain.driveCardinal(
|
||||
@ -226,6 +226,10 @@ public class RobotContainer {
|
||||
.withPosition(0, 0)
|
||||
.withSize(2, 1)
|
||||
.withWidget(BuiltInWidgets.kBooleanBox);
|
||||
teleopTab.addBoolean("indexer beam break", indexer.getBeamBreak());
|
||||
teleopTab.addBoolean("shooter beam break", shooter.getBeamBreak());
|
||||
teleopTab.addDouble("shooter angle", shooter.getShooterAngle());
|
||||
teleopTab.addDouble("intake angle", intake.getIntakeAngle());
|
||||
}
|
||||
|
||||
public Command getAutonomousCommand() {
|
||||
|
@ -3,5 +3,5 @@ package frc.robot.constants;
|
||||
public class IndexerConstants {
|
||||
public static final int kIndexerID = 13;
|
||||
|
||||
public static final int kIndexerBeamBreakChannel = 3;
|
||||
public static final int kIndexerBeamBreakChannel = 2;
|
||||
}
|
||||
|
@ -31,5 +31,5 @@ public class ShooterConstants {
|
||||
|
||||
public static final int kShooterEncoderChannelA = 0;
|
||||
public static final int kShooterEncoderChannelB = 1;
|
||||
public static final int kShooterBeamBreakChannel = 4;
|
||||
public static final int kShooterBeamBreakChannel = 3;
|
||||
}
|
||||
|
@ -1,6 +1,10 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import com.revrobotics.CANSparkMax;
|
||||
|
||||
import java.util.function.BooleanSupplier;
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
import com.revrobotics.CANSparkBase.IdleMode;
|
||||
import com.revrobotics.CANSparkLowLevel.MotorType;
|
||||
|
||||
@ -35,9 +39,13 @@ public class Indexer extends SubsystemBase{
|
||||
});
|
||||
}
|
||||
|
||||
public Command shootNote(){
|
||||
public Command shootNote(DoubleSupplier indexerSpeed){
|
||||
return run(() -> {
|
||||
indexerMotor.set(1.0);
|
||||
indexerMotor.set(indexerSpeed.getAsDouble());
|
||||
});
|
||||
}
|
||||
|
||||
public BooleanSupplier getBeamBreak(){
|
||||
return indexerBeamBreak::get;
|
||||
}
|
||||
}
|
||||
|
@ -70,9 +70,10 @@ public class Intake extends SubsystemBase{
|
||||
});
|
||||
}
|
||||
|
||||
public Command manualPivot(DoubleSupplier pivotPower){
|
||||
public Command manualPivot(DoubleSupplier pivotPower, DoubleSupplier rollerSpinny){
|
||||
return run(() ->{
|
||||
intakePivot.set(pivotPower.getAsDouble());
|
||||
intakeRoller.set(rollerSpinny.getAsDouble());
|
||||
});
|
||||
}
|
||||
|
||||
@ -107,4 +108,8 @@ public class Intake extends SubsystemBase{
|
||||
);
|
||||
});
|
||||
}
|
||||
|
||||
public DoubleSupplier getIntakeAngle(){
|
||||
return intakeEncoder::getPosition;
|
||||
}
|
||||
}
|
||||
|
@ -1,5 +1,6 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import java.util.function.BooleanSupplier;
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
import com.revrobotics.CANSparkMax;
|
||||
@ -132,9 +133,15 @@ public class Shooter extends SubsystemBase{
|
||||
return () -> {return pivotEncoder.getDistance();};
|
||||
}
|
||||
|
||||
public Command manualPivot(DoubleSupplier pivotPower){
|
||||
public BooleanSupplier getBeamBreak(){
|
||||
return shooterBeamBreak::get;
|
||||
}
|
||||
|
||||
public Command manualPivot(DoubleSupplier pivotPower, DoubleSupplier spinny){
|
||||
return run(() ->{
|
||||
shooterPivot.set(pivotPower.getAsDouble());
|
||||
topShooter.set(spinny.getAsDouble());
|
||||
bottomShooter.set(spinny.getAsDouble());
|
||||
});
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user