Skip to content

Commit

Permalink
upload
Browse files Browse the repository at this point in the history
  • Loading branch information
Anhysteretic committed Oct 26, 2024
1 parent 3cc4d09 commit 25ede0e
Show file tree
Hide file tree
Showing 6 changed files with 25 additions and 30 deletions.
15 changes: 8 additions & 7 deletions src/main/java/com/team841/calliope/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -92,8 +92,6 @@ public static RobotContainer getInstance() {
}

public RobotContainer() {
registerNamedCommands();

switch (RC.robotType) {
default -> {
if (RC.robot == RC.Robot.CALLIOPE)
Expand All @@ -118,9 +116,12 @@ public RobotContainer() {
}
}

registerNamedCommands();


if (RC.robot == RC.Robot.NIKE){
this.sticksXbox = new CommandXboxController[1];
this.sticksPS5 = new CommandPS5Controller[1];
this.sticksPS5 = new CommandPS5Controller[0];
this.sticksXbox[0] = new CommandXboxController(RC.Controllers.soloStick);
} else {
this.sticksPS5 = new CommandPS5Controller[1];
Expand Down Expand Up @@ -153,9 +154,9 @@ public RobotContainer() {
this.drivetrain.setDefaultCommand(bioDrive);

if (RC.robot == RC.Robot.NIKE){
configureDuoStick();
} else {
configureSoloStick();
} else {
configureDuoStick();
}
}

Expand Down Expand Up @@ -205,8 +206,8 @@ private void configureSoloStick() {
new SequentialCommandGroup(
new InstantCommand(indexer::stopIndexer),
new InstantCommand(shooter::stopShooter)));
//sticksXbox[0].rightStick().whileTrue(new InstantCommand(hanger::ExtendHanger)).onFalse(new InstantCommand(hanger::StopHanger));
//sticksXbox[0].leftStick().whileTrue(new InstantCommand(hanger::RetractHanger)).onFalse(new InstantCommand(hanger::StopHanger));
sticksXbox[0].rightStick().whileTrue(new InstantCommand(hanger::ExtendHanger)).onFalse(new InstantCommand(hanger::StopHanger));
sticksXbox[0].leftStick().whileTrue(new InstantCommand(hanger::RetractHanger)).onFalse(new InstantCommand(hanger::StopHanger));
sticksXbox[0].povCenter().whileTrue(new InstantCommand(hanger::StopHanger));
sticksXbox[0].povLeft().whileTrue(new InstantCommand(hanger::toggleHanger));
sticksXbox[0]
Expand Down
26 changes: 5 additions & 21 deletions src/main/java/com/team841/calliope/drive/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -42,12 +42,6 @@ public class Drivetrain extends SwerveDrivetrain implements Subsystem {
StructPublisher<Pose2d> limelightPublisher = limelightTopic.publish();
StructPublisher<Pose2d> ctrePublisher = ctreTopic.publish();

LoggedTunableNumber kp = new LoggedTunableNumber("ki");
LoggedTunableNumber ki = new LoggedTunableNumber("ki");
LoggedTunableNumber kd = new LoggedTunableNumber("kd");

Double oldKP, oldKI, oldKD;

private static final double kSimLoopPeriod = 0.005; // 5 ms
private Notifier m_simNotifier = null;
private double m_lastSimTime;
Expand Down Expand Up @@ -116,13 +110,17 @@ private void ConfigureMotors() {
}
}

public void emtpyReturn(Pose2d input){
return;
}

public void configurePathplanner() {

double driveBaseRadius = 0;

AutoBuilder.configureHolonomic(
() -> this.getState().Pose, // Supplier of current robot pose
this::seedFieldRelative, // Consumer for seeding pose against auto
this::emtpyReturn, // Consumer for seeding pose against auto
this::getCurrentRobotChassisSpeeds,
(speeds) ->
this.setControl(
Expand Down Expand Up @@ -267,19 +265,5 @@ public void periodic() {
SmartDashboard.putBoolean("In Dinstance", inRangeToSpeaker());
SmartDashboard.putNumber("tune-target", 0.00);
SmartDashboard.putNumber("tune-angle", this.getState().Pose.getRotation().getDegrees());

if (Swerve.controller != null && oldKP == null){
this.oldKP = Swerve.controller.getP();
this.oldKI = Swerve.controller.getI();
this.oldKD = Swerve.controller.getD();
}

if (kp.hasChanged() || ki.hasChanged() || kd.hasChanged()){
if (Swerve.controller != null){
Swerve.controller.setP(kp.get());
Swerve.controller.setI(ki.get());
Swerve.controller.setD(kd.get());
}
}
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ public void periodic() {
}

public void ExtendHanger() {
io.setVelocity(1.00);
io.setVelocity(-1.00);
}

public void RetractHanger() {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,7 @@ public boolean isHighShot() {
}

public void stopShooter() {
io.setMotionMagicVelocityVoltageOutput(-0.015);
io.setDutyCycle(-0.05);
}

public Command runShooter(double velocity) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,11 +9,14 @@ public class ShooterIOInputs{
public double bottomVelocity;
public double topMotionMagicVoltageVelocity;
public double bottomMotionMagicVoltageVelocity;
public double dutyCycleOut;

}

public default void updateInputs(ShooterIOInputs inputs) { }

public default void setDutyCycle(double value) { }

public default void setMotionMagicVelocityVoltageOutput(double velocity) { }

public default void setMotionMagicVelocityVoltageOutput(double topVelocity, double bottomVelocity) { }
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,7 @@ public void updateInputs(ShooterIOInputs inputs) {
inputs.bottomVelocity = bottomShooter.getVelocity().getValue();
inputs.bottomMotionMagicVoltageVelocity = bottomControl.Velocity;
inputs.topMotionMagicVoltageVelocity = topControl.Velocity;
inputs.dutyCycleOut = topShooter.getDutyCycle().getValue();
}

@Override
Expand All @@ -43,6 +44,12 @@ public void setMotionMagicVelocityVoltageOutput(double topVelocity, double botto
topShooter.setControl(topControl.withVelocity(bottomVelocity));
}

@Override
public void setDutyCycle(double value){
topShooter.set(value);
bottomShooter.set(value);
}

@Override
public void stop() {
bottomShooter.stopMotor();
Expand Down

0 comments on commit 25ede0e

Please sign in to comment.