after portland changes
This commit is contained in:
@@ -12,6 +12,8 @@ import org.littletonrobotics.junction.Logger;
|
||||
|
||||
import com.pathplanner.lib.auto.AutoBuilder;
|
||||
import com.pathplanner.lib.auto.NamedCommands;
|
||||
import com.pathplanner.lib.events.EventTrigger;
|
||||
import com.pathplanner.lib.path.EventMarker;
|
||||
|
||||
import edu.wpi.first.math.geometry.Pose2d;
|
||||
import edu.wpi.first.math.util.Units;
|
||||
@@ -19,6 +21,7 @@ import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Commands;
|
||||
import edu.wpi.first.wpilibj2.command.InstantCommand;
|
||||
import edu.wpi.first.wpilibj2.command.PrintCommand;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||
@@ -71,7 +74,7 @@ public class RobotContainer {
|
||||
configureNamedCommands();
|
||||
|
||||
|
||||
vision.addPoseEstimateConsumer(drivetrain::consumeVisualPose);
|
||||
//vision.addPoseEstimateConsumer(drivetrain::consumeVisualPose);
|
||||
vision.addPoseEstimateConsumer((vp) -> {
|
||||
Logger.recordOutput(
|
||||
"Vision/" + vp.cameraName() + "/Pose",
|
||||
@@ -333,7 +336,7 @@ public class RobotContainer {
|
||||
|
||||
NamedCommands.registerCommand(
|
||||
"intake down",
|
||||
intakePivot.manualSpeed(()->-0.75)
|
||||
intakePivot.manualSpeed(()->0.75)
|
||||
.withTimeout(1)
|
||||
);
|
||||
|
||||
@@ -345,7 +348,33 @@ public class RobotContainer {
|
||||
spindexer.spinToShooter()
|
||||
.alongWith(shooter.maintainSpeed(ShooterSpeeds.kHubSpeed))
|
||||
.alongWith(hood.trackToAngle(() -> Units.degreesToRadians(10)))
|
||||
.withTimeout(3));
|
||||
.withTimeout(3).andThen(spindexer.instantaneousStop()));
|
||||
|
||||
// NamedCommands.registerCommand("Intake Start", intakeRoller.runIn());
|
||||
|
||||
new EventTrigger("Intake Start")
|
||||
.onTrue(intakeRoller.runIn());
|
||||
|
||||
NamedCommands.registerCommand("stop spindexer", spindexer.instantaneousStop());
|
||||
|
||||
NamedCommands.registerCommand("jimmy",
|
||||
Commands.repeatingSequence(
|
||||
intakePivot.manualSpeed(() -> -0.75).withTimeout(0.2)
|
||||
.andThen(intakePivot.manualSpeed(() -> 0.75).withTimeout(0.2))
|
||||
)
|
||||
);
|
||||
|
||||
NamedCommands.registerCommand("shoot N jimmy",
|
||||
Commands.parallel(
|
||||
Commands.repeatingSequence(
|
||||
intakePivot.manualSpeed(() -> -0.75).withTimeout(0.5),
|
||||
intakePivot.manualSpeed(() -> 0.75).withTimeout(0.5)
|
||||
),
|
||||
spindexer.spinToShooter()
|
||||
.alongWith(shooter.maintainSpeed(ShooterSpeeds.kHubSpeed),
|
||||
hood.trackToAngle(() -> Units.degreesToRadians(10)))
|
||||
|
||||
).withTimeout(3).andThen(spindexer.instantaneousStop()));
|
||||
}
|
||||
|
||||
public Command getAutonomousCommand() {
|
||||
|
||||
@@ -12,9 +12,9 @@ public class SpindexerConstants {
|
||||
public static final int kSpindexerMotorCANID = 0;
|
||||
public static final int kFeederMotorCANID = 4;
|
||||
|
||||
public static final int kSpindexerStatorCurrentLimit = 110;
|
||||
public static final int kSpindexerSupplyCurrentLimit = 60;
|
||||
public static final int kFeederCurrentLimit = 40;
|
||||
public static final int kSpindexerStatorCurrentLimit = 95;
|
||||
public static final int kSpindexerSupplyCurrentLimit = 50;
|
||||
public static final int kFeederCurrentLimit = 30;
|
||||
|
||||
public static final double kSpindexerSpeed = 1;
|
||||
public static final double kFeederSpeed = 1;
|
||||
|
||||
@@ -80,6 +80,13 @@ public class IntakePivot extends SubsystemBase {
|
||||
});
|
||||
}
|
||||
|
||||
// public Command jimmy(){
|
||||
// return run(() -> {
|
||||
// leftMotor.set(0.5 * IntakePivotConstants.kMaxManualSpeedMultiplier);
|
||||
// rightMotor.set(0.5 * IntakePivotConstants.kMaxManualSpeedMultiplier);
|
||||
// })
|
||||
// }
|
||||
|
||||
public Command stop() {
|
||||
return manualSpeed(() -> 0);
|
||||
}
|
||||
|
||||
@@ -59,5 +59,12 @@ public class Spindexer extends SubsystemBase {
|
||||
feederMotor.set(0);
|
||||
});
|
||||
}
|
||||
|
||||
public Command instantaneousStop() {
|
||||
return runOnce(() -> {
|
||||
spindexerMotor.setControl(spindexerMotorOutput.withOutput(0));
|
||||
feederMotor.set(0);
|
||||
});
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user