Skip to content

Commit

Permalink
upload
Browse files Browse the repository at this point in the history
  • Loading branch information
Anhysteretic committed Sep 21, 2024
1 parent 17fbff5 commit d81eb07
Show file tree
Hide file tree
Showing 28 changed files with 2,560 additions and 4 deletions.
4 changes: 3 additions & 1 deletion .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -177,4 +177,6 @@ logs/
# Folder that has CTRE Phoenix Sim device config storage
ctre_sim/

.idea
.idea

src/main/java/com/team841/calliope/BuildConstants.java
10 changes: 10 additions & 0 deletions build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -127,3 +127,13 @@ wpi.java.configureTestTasks(test)
tasks.withType(JavaCompile) {
options.compilerArgs.add '-XDstringConcat=inline'
}

project.compileJava.dependsOn(createVersionFile)
gversion {
srcDir = "src/main/java/"
classPackage = "com.team841.calliope"
className = "BuildConstants"
dateFormat = "yyyy-MM-dd HH:mm:ss z"
timeZone = "America/Los_Angeles" // Use preferred time zone
indent = " "
}
54 changes: 51 additions & 3 deletions src/main/java/com/team841/calliope/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,17 +4,65 @@

package com.team841.calliope;

import edu.wpi.first.wpilibj.TimedRobot;
import com.team841.calliope.constants.RC;
import edu.wpi.first.wpilibj.PowerDistribution;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;

public class Robot extends TimedRobot {
import org.littletonrobotics.junction.LogFileUtil;
import org.littletonrobotics.junction.LoggedRobot;
import org.littletonrobotics.junction.Logger;
import org.littletonrobotics.junction.networktables.NT4Publisher;
import org.littletonrobotics.junction.wpilog.WPILOGReader;
import org.littletonrobotics.junction.wpilog.WPILOGWriter;

public class Robot extends LoggedRobot {
private Command m_autonomousCommand;

private RobotContainer m_robotContainer;

@Override
public void robotInit() {

Logger.recordMetadata("ProjectName", "Calliope-software");
Logger.recordMetadata("TuningMode", Boolean.toString(RC.robotType == RC.RunType.DEV));
Logger.recordMetadata("ProjectName", BuildConstants.MAVEN_NAME);
Logger.recordMetadata("BuildDate", BuildConstants.BUILD_DATE);
Logger.recordMetadata("GitSHA", BuildConstants.GIT_SHA);
Logger.recordMetadata("GitDate", BuildConstants.GIT_DATE);
Logger.recordMetadata("GitBranch", BuildConstants.GIT_BRANCH);

switch (BuildConstants.DIRTY) {
case 0:
Logger.recordMetadata("GitDirty", "All changes committed");
break;
case 1:
Logger.recordMetadata("GitDirty", "Uncomitted changes");
break;
default:
Logger.recordMetadata("GitDirty", "Unknown");
break;
}

switch (RC.robotType){
case COMP:
Logger.addDataReceiver(new WPILOGWriter()); // Log to a USB stick ("/U/logs")
Logger.addDataReceiver(new NT4Publisher()); // Publish data to NetworkTables
new PowerDistribution(1, PowerDistribution.ModuleType.kRev); // Enables power distribution logging
break;
case SIM:
Logger.addDataReceiver(new NT4Publisher()); // Save outputs to a new log
break;
case REPLAY:
setUseTiming(false);
String logPath = LogFileUtil.findReplayLog(); // Pull the replay log from AdvantageScope (or prompt the user)
Logger.setReplaySource(new WPILOGReader(logPath));
Logger.addDataReceiver(new WPILOGWriter(LogFileUtil.addPathSuffix(logPath, "_sim"), 0.01));
break;
}

Logger.start();

m_robotContainer = new RobotContainer();
}

Expand Down
18 changes: 18 additions & 0 deletions src/main/java/com/team841/calliope/constants/Field.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
package com.team841.calliope.constants;

import com.team841.lib.util.FieldGeometry;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Rotation3d;

public class Field {
public static Pose3d kBlueSpeakerPose3d = new Pose3d(0.0, 5.549, 2.002, new Rotation3d());
public static Pose2d kBlueSpeakerPose2d =
new Pose2d(kBlueSpeakerPose3d.getX(), kBlueSpeakerPose3d.getY(), new Rotation2d(0.0));

public static Pose2d kRedSpeakerPose2d = FieldGeometry.flipFieldPose(kBlueSpeakerPose2d);

public static Pose2d S_OSpeakerC =
new Pose2d(1.3865381479263306, 4.631037712097168, new Rotation2d(3.14159));
}
13 changes: 13 additions & 0 deletions src/main/java/com/team841/calliope/constants/Manifest.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
package com.team841.calliope.constants;

import edu.wpi.first.wpilibj2.command.button.CommandXboxController;

public class Manifest {
public class SubsystemManifest {

}

public class JoystickManifest {

}
}
51 changes: 51 additions & 0 deletions src/main/java/com/team841/calliope/constants/RC.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
package com.team841.calliope.constants;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.RobotBase;

import java.util.function.Supplier;

public class RC {

public static Supplier<Boolean> isRedAlliance =
() -> {
var alliance = DriverStation.getAlliance();
return alliance.filter(value -> value == DriverStation.Alliance.Red).isPresent();
};

public static boolean rumbleNeedsPing = false;

public static final RunType robotType = RunType.SIM;

public static class Controllers {
public static final int driverPortLeft = 0; // controller USB port 0
public static final int driverPortRight = 1; // controller USB port 1
public static final int codriverPort = 2; // controller USB port 2

public static final int SysIDCommandPort = 4; // for sysID
}

public static final class SC_CAN_ID {

public static final int kIntake = 17;

public static final int kIndexerTalon = 10;

public static final int kHangerMotorLeft = 15;
public static final int kHangerMotorRight = 3;

public static final int kLeftArmJoint = 13;
public static final int kRightArmJoint = 14;

public static final int bottomShooter = 12;

public static final int topShooter = 11;
}

public enum RunType{
SIM, // Simulation
DEV, // Developer-tuning mode
COMP, // Comp code, real robot code
REPLAY
}
}
180 changes: 180 additions & 0 deletions src/main/java/com/team841/calliope/constants/SC.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,180 @@
package com.team841.calliope.constants;

import com.ctre.phoenix6.configs.*;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;

public class SC {

public static class Shooter {
private static AudioConfigs k_audio =
new AudioConfigs()
.withAllowMusicDurDisable(true)
.withBeepOnBoot(true)
.withBeepOnConfig(true);

private static ClosedLoopRampsConfigs k_closedLoopRampConfig =
new ClosedLoopRampsConfigs()
.withDutyCycleClosedLoopRampPeriod(0.1)
.withTorqueClosedLoopRampPeriod(0.1)
.withVoltageClosedLoopRampPeriod(0.1);

private static CurrentLimitsConfigs k_currentLimitsConfig =
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(60.0)
.withSupplyCurrentLimitEnable(true)
.withSupplyCurrentThreshold(60.0)
.withSupplyTimeThreshold(0);

private static CustomParamsConfigs k_customParamConfigs =
new CustomParamsConfigs().withCustomParam0(841).withCustomParam1(841);

private static MotionMagicConfigs k_shooterMotionMagicConfig =
new MotionMagicConfigs()
.withMotionMagicAcceleration(200.0)
.withMotionMagicCruiseVelocity(0.0)
.withMotionMagicExpo_kA(0.0)
.withMotionMagicExpo_kV(0.0)
.withMotionMagicJerk(0.0);
private static MotorOutputConfigs k_MotorOutputConfig =
new MotorOutputConfigs().withInverted(InvertedValue.Clockwise_Positive);

private static Slot0Configs k_slot0 =
new Slot0Configs().withKP(0.6).withKI(0).withKD(0).withKV(0).withKS(0);

public static TalonFXConfiguration k_BottomConfiguration =
new TalonFXConfiguration()
.withAudio(k_audio)
.withClosedLoopRamps(k_closedLoopRampConfig)
.withCurrentLimits(k_currentLimitsConfig)
.withCustomParams(k_customParamConfigs)
.withMotionMagic(k_shooterMotionMagicConfig)
.withMotorOutput(k_MotorOutputConfig)
.withSlot0(k_slot0);

public static TalonFXConfiguration k_TopConfiguration =
new TalonFXConfiguration()
.withAudio(k_audio)
.withClosedLoopRamps(k_closedLoopRampConfig)
.withCurrentLimits(k_currentLimitsConfig)
.withCustomParams(k_customParamConfigs)
.withMotionMagic(k_shooterMotionMagicConfig)
.withMotorOutput(k_MotorOutputConfig)
.withSlot0(k_slot0);
}

public static class Indexer {

private static AudioConfigs k_audio =
new AudioConfigs()
.withAllowMusicDurDisable(true)
.withBeepOnBoot(true)
.withBeepOnConfig(true);

private static ClosedLoopRampsConfigs k_closedLoopRampConfig =
new ClosedLoopRampsConfigs()
.withDutyCycleClosedLoopRampPeriod(0.1)
.withTorqueClosedLoopRampPeriod(0.1)
.withVoltageClosedLoopRampPeriod(0.1);

private static CurrentLimitsConfigs k_currentLimitsConfig =
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(60.0)
.withSupplyCurrentLimitEnable(true)
.withSupplyCurrentThreshold(60.0)
.withSupplyTimeThreshold(0);

private static CustomParamsConfigs k_customParamConfigs =
new CustomParamsConfigs().withCustomParam0(841).withCustomParam1(841);

private static MotionMagicConfigs k_IndexerMotionMagicConfig =
new MotionMagicConfigs()
.withMotionMagicAcceleration(0.0)
.withMotionMagicCruiseVelocity(0.0)
.withMotionMagicExpo_kA(0.0)
.withMotionMagicExpo_kV(0.12)
.withMotionMagicJerk(0.0);
private static MotorOutputConfigs k_IndexerMotorOutputConfig =
new MotorOutputConfigs().withInverted(InvertedValue.CounterClockwise_Positive);

// with note
private static Slot0Configs k_slot0 =
new Slot0Configs().withKP(60).withKI(0).withKD(0.1).withKV(0.12).withKS(0.5);

// No Note
private static Slot1Configs k_slot1 =
new Slot1Configs().withKP(60).withKI(0).withKD(0.1).withKV(0.12).withKS(0.5);
public static TalonFXConfiguration k_IndexerConfiguration =
new TalonFXConfiguration()
.withAudio(k_audio)
.withClosedLoopRamps(k_closedLoopRampConfig)
.withCurrentLimits(k_currentLimitsConfig)
.withCustomParams(k_customParamConfigs)
.withMotionMagic(k_IndexerMotionMagicConfig)
.withMotorOutput(k_IndexerMotorOutputConfig)
.withSlot0(k_slot0)
.withSlot1(k_slot1);

public static int k_RightSensorChannel = 1;
public static int k_LeftSensorChannel = 3;
}

public static class Intake {
public static final int kCurrentLimit = 60; // in amps

public static final int kBlinkingID = 1;

public static final TalonFXConfiguration k_MotorOutputConfig = null;
}

public static class Arm {
private static AudioConfigs k_audio =
new AudioConfigs()
.withAllowMusicDurDisable(true)
.withBeepOnBoot(true)
.withBeepOnConfig(true);

private static ClosedLoopRampsConfigs k_closedLoopRampConfig =
new ClosedLoopRampsConfigs()
.withDutyCycleClosedLoopRampPeriod(0.05)
.withTorqueClosedLoopRampPeriod(0.05)
.withVoltageClosedLoopRampPeriod(0.1);

private static CurrentLimitsConfigs k_currentLimitsConfig =
new CurrentLimitsConfigs()
.withSupplyCurrentLimit(10)
.withSupplyCurrentLimitEnable(true)
.withSupplyCurrentThreshold(10)
.withSupplyTimeThreshold(0);

private static CustomParamsConfigs k_customParamConfigs =
new CustomParamsConfigs().withCustomParam0(841).withCustomParam1(841);

private static MotionMagicConfigs k_ArmMotionMagicConfig =
new MotionMagicConfigs()
.withMotionMagicAcceleration(200.0)
.withMotionMagicCruiseVelocity(0.0)
.withMotionMagicExpo_kA(0.0)
.withMotionMagicExpo_kV(0.0)
.withMotionMagicJerk(0.0);

private static Slot0Configs k_slot0 =
new Slot0Configs().withKP(0.6).withKI(0).withKD(0).withKV(0).withKS(0);

private static MotorOutputConfigs k_motorOutput =
new MotorOutputConfigs().withNeutralMode(NeutralModeValue.Brake);

public static TalonFXConfiguration k_ArmConfiguration =
new TalonFXConfiguration()
.withAudio(k_audio)
.withClosedLoopRamps(k_closedLoopRampConfig)
.withCurrentLimits(k_currentLimitsConfig)
.withCustomParams(k_customParamConfigs)
.withMotionMagic(k_ArmMotionMagicConfig)
.withSlot0(k_slot0)
.withMotorOutput(k_motorOutput);
}

public static class Hanger {
}
}
Loading

0 comments on commit d81eb07

Please sign in to comment.