Skip to content

Commit

Permalink
upload
Browse files Browse the repository at this point in the history
  • Loading branch information
Anhysteretic committed Sep 24, 2024
1 parent 0c99ec8 commit af9d2b9
Show file tree
Hide file tree
Showing 5 changed files with 201 additions and 169 deletions.
5 changes: 5 additions & 0 deletions src/main/java/com/team841/calliope/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

package com.team841.calliope;

import com.ctre.phoenix6.SignalLogger;
import com.team841.calliope.constants.RC;
import edu.wpi.first.wpilibj.PowerDistribution;
import edu.wpi.first.wpilibj.RobotController;
Expand Down Expand Up @@ -63,6 +64,7 @@ public void robotInit() {
break;
}

SignalLogger.setPath("/media/sda1/");
Logger.start();
}

Expand Down Expand Up @@ -105,6 +107,8 @@ public void teleopInit() {
if (m_autonomousCommand != null) {
m_autonomousCommand.cancel();
}

SignalLogger.start();
}

@Override
Expand All @@ -113,6 +117,7 @@ public void teleopPeriodic() {

@Override
public void teleopExit() {
SignalLogger.stop();
}

@Override
Expand Down
23 changes: 15 additions & 8 deletions src/main/java/com/team841/calliope/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -29,9 +29,11 @@
import edu.wpi.first.wpilibj2.command.button.CommandPS5Controller;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;

import static com.team841.calliope.constants.Swerve.DrivetrainConstants;

public class RobotContainer {

public final Drivetrain drivetrain = Swerve.DriveTrain;
public final Drivetrain drivetrain;

public final ShooterIO shooterIO;
public final Shooter shooter;
Expand All @@ -50,8 +52,8 @@ public class RobotContainer {

public final CommandXboxController soloStick = new CommandXboxController(RC.Controllers.soloStick);

public final CommandPS5Controller duoStickDrive = new CommandPS5Controller(RC.Controllers.duoStickDrive);
public final CommandXboxController duoStickCoDrive = new CommandXboxController(RC.Controllers.duoStickCoDrive);
//public final CommandPS5Controller duoStickDrive = new CommandPS5Controller(RC.Controllers.duoStickDrive);
//public final CommandXboxController duoStickCoDrive = new CommandXboxController(RC.Controllers.duoStickCoDrive);

private final SwerveRequest.FieldCentric drive =
new SwerveRequest.FieldCentric()
Expand Down Expand Up @@ -81,6 +83,8 @@ public static RobotContainer getInstance() {
public RobotContainer() {
switch (RC.robotType) {
default -> {
this.drivetrain = new Drivetrain(Swerve.DrivetrainConstants, Swerve.FrontLeft, Swerve.FrontRight, Swerve.BackLeft, Swerve.BackRight);

this.shooterIO = new ShooterIOTalonFX();
this.shooter = new Shooter(this.shooterIO);

Expand All @@ -99,11 +103,11 @@ public RobotContainer() {
}

configureSoloStick();
configureDuoStick();
//configureDuoStick();
}

private void configureSoloStick() {
drivetrain.setDefaultCommand( // Drivetrain will execute this command periodically
this.drivetrain.setDefaultCommand( // Drivetrain will execute this command periodically
drivetrain.applyRequest(
() ->
drive
Expand Down Expand Up @@ -145,8 +149,8 @@ private void configureSoloStick() {
new SequentialCommandGroup(
new InstantCommand(indexer::stopIndexer),
new InstantCommand(shooter::stopShooter)));
soloStick.rightStick().whileTrue(new InstantCommand(hanger::ExtendHanger)).onFalse(new InstantCommand(hanger::StopHanger));
soloStick.leftStick().whileTrue(new InstantCommand(hanger::RetractHanger)).onFalse(new InstantCommand(hanger::StopHanger));
//soloStick.rightStick().whileTrue(new InstantCommand(hanger::ExtendHanger)).onFalse(new InstantCommand(hanger::StopHanger));
//soloStick.leftStick().whileTrue(new InstantCommand(hanger::RetractHanger)).onFalse(new InstantCommand(hanger::StopHanger));
soloStick.povCenter().whileTrue(new InstantCommand(hanger::StopHanger));
soloStick.povLeft().whileTrue(new InstantCommand(hanger::toggleHanger));
soloStick
Expand All @@ -168,7 +172,7 @@ private void configureSoloStick() {
.onFalse(new InstantCommand(shooter::stopShooter));
}

private void configureDuoStick() {
/*private void configureDuoStick() {
drivetrain.setDefaultCommand( // Drivetrain will execute this command periodically
drivetrain.applyRequest(
() ->
Expand Down Expand Up @@ -252,6 +256,9 @@ private void configureDuoStick() {
.onFalse(new InstantCommand(shooter::stopShooter));
}
*/


public Command getAutonomousCommand() {
return Commands.print("No autonomous command configured");
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/com/team841/calliope/constants/RC.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ public class RC {

public static boolean rumbleNeedsPing = false;

public static final RunType robotType = RunType.SIM;
public static final RunType robotType = RunType.COMP;

public static class Controllers {
public static final int soloStick = 3;
Expand Down
16 changes: 7 additions & 9 deletions src/main/java/com/team841/calliope/constants/Swerve.java
Original file line number Diff line number Diff line change
Expand Up @@ -61,10 +61,10 @@ public class Swerve {
private static final double kSteerFrictionVoltage = 0.25;
private static final double kDriveFrictionVoltage = 0.25;

private static final SwerveDrivetrainConstants DrivetrainConstants =
public static final SwerveDrivetrainConstants DrivetrainConstants =
new SwerveDrivetrainConstants().withPigeon2Id(kPigeonId).withCANbusName(kCANbusName);

private static final SwerveModuleConstantsFactory ConstantCreator =
public static final SwerveModuleConstantsFactory ConstantCreator =
new SwerveModuleConstantsFactory()
.withDriveMotorGearRatio(kDriveGearRatio)
.withSteerMotorGearRatio(kSteerGearRatio)
Expand Down Expand Up @@ -119,7 +119,7 @@ public class Swerve {
private static final double kBackRightXPosInches = -10.375;
private static final double kBackRightYPosInches = -10.375;

private static final SwerveModuleConstants FrontLeft =
public static final SwerveModuleConstants FrontLeft =
ConstantCreator.createModuleConstants(
kFrontLeftSteerMotorId,
kFrontLeftDriveMotorId,
Expand All @@ -128,7 +128,7 @@ public class Swerve {
Units.inchesToMeters(kFrontLeftXPosInches),
Units.inchesToMeters(kFrontLeftYPosInches),
kInvertLeftSide);
private static final SwerveModuleConstants FrontRight =
public static final SwerveModuleConstants FrontRight =
ConstantCreator.createModuleConstants(
kFrontRightSteerMotorId,
kFrontRightDriveMotorId,
Expand All @@ -137,7 +137,7 @@ public class Swerve {
Units.inchesToMeters(kFrontRightXPosInches),
Units.inchesToMeters(kFrontRightYPosInches),
kInvertRightSide);
private static final SwerveModuleConstants BackLeft =
public static final SwerveModuleConstants BackLeft =
ConstantCreator.createModuleConstants(
kBackLeftSteerMotorId,
kBackLeftDriveMotorId,
Expand All @@ -146,7 +146,7 @@ public class Swerve {
Units.inchesToMeters(kBackLeftXPosInches),
Units.inchesToMeters(kBackLeftYPosInches),
kInvertLeftSide);
private static final SwerveModuleConstants BackRight =
public static final SwerveModuleConstants BackRight =
ConstantCreator.createModuleConstants(
kBackRightSteerMotorId,
kBackRightDriveMotorId,
Expand All @@ -156,10 +156,8 @@ public class Swerve {
Units.inchesToMeters(kBackRightYPosInches),
kInvertRightSide);

public static double MaxAngularRate =
4 * Math.PI; // 1.5 * Math.PI; // 3/4 of a rotation per second max angular velocity
public static double MaxAngularRate = 4 * Math.PI; // 1.5 * Math.PI; // 3/4 of a rotation per second max angular velocity
public static double MaxSpeed = kSpeedAt12VoltsMps;
public static final Drivetrain DriveTrain = new Drivetrain(DrivetrainConstants, FrontLeft, FrontRight, BackLeft, BackRight);

public static final ProfiledPIDController TurnController =
new ProfiledPIDController(7, 0.0, 0.0, new TrapezoidProfile.Constraints(0, 0));
Expand Down
Loading

0 comments on commit af9d2b9

Please sign in to comment.