made intake jimmy a method and added a button for it
This commit is contained in:
@@ -310,6 +310,12 @@ public class RobotContainer {
|
|||||||
secondary.rightBumper().onTrue(hood.trackToAngle(() -> Units.degreesToRadians(10)));
|
secondary.rightBumper().onTrue(hood.trackToAngle(() -> Units.degreesToRadians(10)));
|
||||||
//10 degrees good for shooting ~33in away from hub
|
//10 degrees good for shooting ~33in away from hub
|
||||||
|
|
||||||
|
secondary.y().whileTrue(
|
||||||
|
intakePivot.jimmy(.2)
|
||||||
|
.andThen(
|
||||||
|
intakePivot.manualSpeed(() -> -0.5)
|
||||||
|
)
|
||||||
|
);
|
||||||
|
|
||||||
hood.setDefaultCommand(hood.trackToAngle(() -> {
|
hood.setDefaultCommand(hood.trackToAngle(() -> {
|
||||||
Pose2d drivetrainPose = drivetrain.getPose();
|
Pose2d drivetrainPose = drivetrain.getPose();
|
||||||
@@ -374,18 +380,12 @@ public class RobotContainer {
|
|||||||
NamedCommands.registerCommand("stop spindexer", spindexer.instantaneousStop());
|
NamedCommands.registerCommand("stop spindexer", spindexer.instantaneousStop());
|
||||||
|
|
||||||
NamedCommands.registerCommand("jimmy",
|
NamedCommands.registerCommand("jimmy",
|
||||||
Commands.repeatingSequence(
|
intakePivot.jimmy(0.2)
|
||||||
intakePivot.manualSpeed(() -> -0.75).withTimeout(0.2)
|
|
||||||
.andThen(intakePivot.manualSpeed(() -> 0.75).withTimeout(0.2))
|
|
||||||
)
|
|
||||||
);
|
);
|
||||||
|
|
||||||
NamedCommands.registerCommand("shoot N jimmy",
|
NamedCommands.registerCommand("shoot N jimmy",
|
||||||
Commands.parallel(
|
Commands.parallel(
|
||||||
Commands.repeatingSequence(
|
intakePivot.jimmy(0.5),
|
||||||
intakePivot.manualSpeed(() -> -0.75).withTimeout(0.5),
|
|
||||||
intakePivot.manualSpeed(() -> 0.75).withTimeout(0.5)
|
|
||||||
),
|
|
||||||
spindexer.spinToShooter()
|
spindexer.spinToShooter()
|
||||||
.alongWith(shooter.maintainSpeed(ShooterSpeeds.kHubSpeed),
|
.alongWith(shooter.maintainSpeed(ShooterSpeeds.kHubSpeed),
|
||||||
hood.trackToAngle(() -> Units.degreesToRadians(10)))
|
hood.trackToAngle(() -> Units.degreesToRadians(10)))
|
||||||
|
|||||||
@@ -14,6 +14,7 @@ import com.revrobotics.spark.SparkBase.ControlType;
|
|||||||
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
import com.revrobotics.spark.SparkLowLevel.MotorType;
|
||||||
|
|
||||||
import edu.wpi.first.wpilibj2.command.Command;
|
import edu.wpi.first.wpilibj2.command.Command;
|
||||||
|
import edu.wpi.first.wpilibj2.command.Commands;
|
||||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||||
import frc.robot.constants.IntakePivotConstants;
|
import frc.robot.constants.IntakePivotConstants;
|
||||||
import frc.robot.constants.IntakePivotConstants.IntakePivotPosition;
|
import frc.robot.constants.IntakePivotConstants.IntakePivotPosition;
|
||||||
@@ -80,12 +81,31 @@ public class IntakePivot extends SubsystemBase {
|
|||||||
});
|
});
|
||||||
}
|
}
|
||||||
|
|
||||||
// public Command jimmy(){
|
/**
|
||||||
// return run(() -> {
|
* Repeatedly moves the intake up and down. AKA "Jimmying" the intake
|
||||||
// leftMotor.set(0.5 * IntakePivotConstants.kMaxManualSpeedMultiplier);
|
*
|
||||||
// rightMotor.set(0.5 * IntakePivotConstants.kMaxManualSpeedMultiplier);
|
* @param time How long the intake will go both ways for (seconds)
|
||||||
// })
|
* @return Command that repeatedly Jimmys the intake
|
||||||
// }
|
*/
|
||||||
|
public Command jimmy(double time){
|
||||||
|
return Commands.repeatingSequence(
|
||||||
|
manualSpeed(() -> -0.75).withTimeout(time)
|
||||||
|
.andThen(manualSpeed(() -> 0.75).withTimeout(time))
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Repeatedly moves the intake up and down. AKA "Jimmying" the intake
|
||||||
|
*
|
||||||
|
* @param time How long the intake will go both ways for (seconds)
|
||||||
|
* @return Command that repeatedly Jimmys the intake
|
||||||
|
*/
|
||||||
|
public Command jimmy(DoubleSupplier time) {
|
||||||
|
return Commands.repeatingSequence(
|
||||||
|
manualSpeed(() -> -0.75).withTimeout(time.getAsDouble())
|
||||||
|
.andThen(manualSpeed(() -> 0.75).withTimeout(time.getAsDouble()))
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
public Command stop() {
|
public Command stop() {
|
||||||
return manualSpeed(() -> 0);
|
return manualSpeed(() -> 0);
|
||||||
|
|||||||
Reference in New Issue
Block a user