Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add json #83

Open
wants to merge 5 commits into
base: main
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
3 changes: 3 additions & 0 deletions DriverConstants.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
{
"joystickDeadband": 0.16
}
3 changes: 3 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
import edu.wpi.first.wpilibj.PowerDistribution.ModuleType;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import frc.robot.constants.ConstantsLoader;
import frc.robot.constants.ModeConstants;
import frc.robot.constants.ModeConstants.Mode;
import org.littletonrobotics.junction.LoggedRobot;
Expand Down Expand Up @@ -49,6 +50,8 @@ public void robotInit() {
// new
// log
}*/

ConstantsLoader.loadDriverConstants();
Logger.start();
}

Expand Down
118 changes: 59 additions & 59 deletions src/main/java/frc/robot/RobotContainer.java

Large diffs are not rendered by default.

13 changes: 6 additions & 7 deletions src/main/java/frc/robot/commands/DriveWithJoysticks.java
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,7 @@
import edu.wpi.first.networktables.NetworkTableInstance;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.button.CommandJoystick;
import frc.robot.constants.DriverConstants;
import frc.robot.constants.PhoenixDriveConstants;
import frc.robot.constants.ConstantsLoader;
import frc.robot.subsystems.drive.PhoenixDrive;

public class DriveWithJoysticks extends Command {
Expand Down Expand Up @@ -51,15 +50,15 @@ public void execute() {
Deadband.twoAxisDeadband(
leftJoystick.getX(),
leftJoystick.getY(),
DriverConstants.leftJoystickDeadband);
double filteredVY = -leftJoystickDeadbanded[1] * PhoenixDriveConstants.maxSpeedMetPerSec;
double filteredVX = -leftJoystickDeadbanded[0] * PhoenixDriveConstants.maxSpeedMetPerSec;
ConstantsLoader.DriverConstants.joystickDeadband);
double filteredVY = -leftJoystickDeadbanded[1] * ConstantsLoader.PhoenixDriveConstants.maxSpeedMetPerSec;
double filteredVX = -leftJoystickDeadbanded[0] * ConstantsLoader.PhoenixDriveConstants.maxSpeedMetPerSec;

double rightJoystickDeadbanded =
Deadband.oneAxisDeadband(
rightJoystick.getX(), DriverConstants.rightJoystickDeadband);
rightJoystick.getX(), ConstantsLoader.DriverConstants.joystickDeadband);
double filteredOmega =
-rightJoystickDeadbanded * PhoenixDriveConstants.MaxAngularRateRadPerSec;
-rightJoystickDeadbanded * ConstantsLoader.PhoenixDriveConstants.MaxAngularRateRadPerSec;

chassisSpeeds = new ChassisSpeeds(filteredVY, filteredVX, filteredOmega);
drivetrain.setGoalSpeeds(chassisSpeeds, true);
Expand Down
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/commands/ShootWithGamepad.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,8 @@

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.constants.PhoenixDriveConstants.AlignTarget;
import frc.robot.constants.ConstantsLoader;
import frc.robot.constants.PhoenixDriveConstantsSchema.AlignTarget;
import frc.robot.subsystems.scoring.ScoringSubsystem;
import frc.robot.subsystems.scoring.ScoringSubsystem.ScoringAction;
import java.util.function.BooleanSupplier;
Expand Down
180 changes: 180 additions & 0 deletions src/main/java/frc/robot/constants/ConstantsLoader.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,180 @@
package frc.robot.constants;

import java.util.HashMap;

import com.ctre.phoenix6.configs.Slot0Configs;
import com.ctre.phoenix6.mechanisms.swerve.SwerveDrivetrainConstants;
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstants.SteerFeedbackType;
import com.ctre.phoenix6.mechanisms.swerve.SwerveModuleConstantsFactory;

import coppercore.parameter_tools.JSONSync;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.util.Units;

public class ConstantsLoader {
/*
* NOTE: Each json constants file needs a schema matching its structure
*
* -> that schema is then put into a new JSON Sync class,
* class' load method is called,
* and then object is retrieved for holding in corresponding static variable
*
* IMPORTANT: file paths are from base folder (High-Key-2024)
*/
public static DriverConstantsSchema DriverConstants;
public static FeatureFlagsSchema FeatureFlags;
public static ScoringConstantsSchema ScoringConstants;
public static PhoenixDriveConstantsSchema PhoenixDriveConstants;

public static void loadDriverConstants() {
JSONSync<DriverConstantsSchema> synced =
new JSONSync<DriverConstantsSchema>(
new DriverConstantsSchema(),
"./DriverConstants.json",
new JSONSync.JSONSyncConfigBuilder().build());
synced.loadData();
DriverConstants = synced.getObject();
}

public static void loadFeatureFlags() {
JSONSync<FeatureFlagsSchema> synced =
new JSONSync<FeatureFlagsSchema>(
new FeatureFlagsSchema(),
"./DriverConstants.json",
new JSONSync.JSONSyncConfigBuilder().build());
synced.loadData();
FeatureFlags = synced.getObject();
}

public static void loadScoringConstants() {
JSONSync<ScoringConstantsSchema> synced =
new JSONSync<ScoringConstantsSchema>(
new ScoringConstantsSchema(),
"./DriverConstants.json",
new JSONSync.JSONSyncConfigBuilder().build());
synced.loadData();
ScoringConstants = synced.getObject();
ScoringConstants.aimerMap = new HashMap<Double, Double>();
ScoringConstants.shooterMap = new HashMap<Double, Double>();
ScoringConstants.timeToGoalMap = new HashMap<Double, Double>();
ScoringConstants.aimerToleranceMap = new HashMap<Double, Double>();

for (int i = 0; i < ScoringConstants.aimerDistance.length; i++) {
ScoringConstants.aimerMap.put(ScoringConstants.aimerDistance[i], ScoringConstants.aimerPosition[i]);
}

for (int i = 0; i < ScoringConstants.shooterDistance.length; i++) {
ScoringConstants.shooterMap.put(ScoringConstants.shooterDistance[i], ScoringConstants.shooterRPM[i]);
}

for (int i = 0; i < ScoringConstants.timeToGoalDistance.length; i++) {
ScoringConstants.timeToGoalMap.put(ScoringConstants.timeToGoalDistance[i], ScoringConstants.timeToGoal[i]);
}

for (int i = 0; i < ScoringConstants.aimerToleranceDistance.length; i++) {
ScoringConstants.aimerToleranceMap.put(ScoringConstants.aimerToleranceDistance[i], ScoringConstants.aimerTolerance[i]);
}
}

public static void loadPhoenixDriveConstants() {
JSONSync<PhoenixDriveConstantsSchema> synced =
new JSONSync<PhoenixDriveConstantsSchema>(
new PhoenixDriveConstantsSchema(),
"./DriverConstants.json",
new JSONSync.JSONSyncConfigBuilder().build());
synced.loadData();
PhoenixDriveConstants = synced.getObject();

PhoenixDriveConstants.steerGains =
new Slot0Configs()
.withKP(PhoenixDriveConstants.steerKP)
.withKI(PhoenixDriveConstants.steerKI)
.withKD(PhoenixDriveConstants.steerKD)
.withKS(PhoenixDriveConstants.steerKS)
.withKV(PhoenixDriveConstants.steerKV)
.withKA(PhoenixDriveConstants.steerKA);

PhoenixDriveConstants.driveGains =
new Slot0Configs()
.withKP(PhoenixDriveConstants.driveKP)
.withKI(PhoenixDriveConstants.driveKI)
.withKD(PhoenixDriveConstants.driveKD)
.withKS(PhoenixDriveConstants.driveKS)
.withKV(PhoenixDriveConstants.driveKV)
.withKA(PhoenixDriveConstants.driveKA);

PhoenixDriveConstants.DrivetrainConstants =
new SwerveDrivetrainConstants().withPigeon2Id(PhoenixDriveConstants.kPigeonId).withCANbusName(PhoenixDriveConstants.kCANbusName);

PhoenixDriveConstants.ConstantCreator =
new SwerveModuleConstantsFactory()
.withDriveMotorGearRatio(PhoenixDriveConstants.kDriveGearRatio)
.withSteerMotorGearRatio(PhoenixDriveConstants.kSteerGearRatio)
.withWheelRadius(PhoenixDriveConstants.kWheelRadiusInches)
.withSlipCurrent(PhoenixDriveConstants.kSlipCurrentA)
.withSteerMotorGains(PhoenixDriveConstants.steerGains)
.withDriveMotorGains(PhoenixDriveConstants.driveGains)
.withSteerMotorClosedLoopOutput(PhoenixDriveConstants.steerClosedLoopOutput)
.withDriveMotorClosedLoopOutput(PhoenixDriveConstants.driveClosedLoopOutput)
.withSpeedAt12VoltsMps(PhoenixDriveConstants.kSpeedAt12VoltsMps)
.withSteerInertia(PhoenixDriveConstants.kSteerInertia)
.withDriveInertia(PhoenixDriveConstants.kDriveInertia)
.withSteerFrictionVoltage(PhoenixDriveConstants.kSteerFrictionVoltage)
.withDriveFrictionVoltage(PhoenixDriveConstants.kDriveFrictionVoltage)
.withFeedbackSource(SteerFeedbackType.FusedCANcoder)
.withCouplingGearRatio(PhoenixDriveConstants.kCoupleRatio);

PhoenixDriveConstants.FrontLeft =
PhoenixDriveConstants.ConstantCreator.createModuleConstants(
PhoenixDriveConstants.kFrontLeftSteerMotorId,
PhoenixDriveConstants.kFrontLeftDriveMotorId,
PhoenixDriveConstants.kFrontLeftEncoderId,
PhoenixDriveConstants.kFrontLeftEncoderOffset,
Units.inchesToMeters(PhoenixDriveConstants.kFrontLeftXPosInches),
Units.inchesToMeters(PhoenixDriveConstants.kFrontLeftYPosInches),
PhoenixDriveConstants.kInvertLeftSide)
.withSteerMotorInverted(PhoenixDriveConstants.kFrontLeftSteerInvert);

PhoenixDriveConstants.FrontRight =
PhoenixDriveConstants.ConstantCreator.createModuleConstants(
PhoenixDriveConstants.kFrontRightSteerMotorId,
PhoenixDriveConstants.kFrontRightDriveMotorId,
PhoenixDriveConstants.kFrontRightEncoderId,
PhoenixDriveConstants.kFrontRightEncoderOffset,
Units.inchesToMeters(PhoenixDriveConstants.kFrontRightXPosInches),
Units.inchesToMeters(PhoenixDriveConstants.kFrontRightYPosInches),
PhoenixDriveConstants.kInvertRightSide)
.withSteerMotorInverted(PhoenixDriveConstants.kFrontRightSteerInvert);

PhoenixDriveConstants.BackLeft =
PhoenixDriveConstants.ConstantCreator.createModuleConstants(
PhoenixDriveConstants.kBackLeftSteerMotorId,
PhoenixDriveConstants.kBackLeftDriveMotorId,
PhoenixDriveConstants.kBackLeftEncoderId,
PhoenixDriveConstants.kBackLeftEncoderOffset,
Units.inchesToMeters(PhoenixDriveConstants.kBackLeftXPosInches),
Units.inchesToMeters(PhoenixDriveConstants.kBackLeftYPosInches),
PhoenixDriveConstants.kInvertLeftSide)
.withSteerMotorInverted(PhoenixDriveConstants.kBackLeftSteerInvert)
.withDriveMotorInverted(PhoenixDriveConstants.kBackLeftDriveInvert);

PhoenixDriveConstants.BackRight =
PhoenixDriveConstants.ConstantCreator.createModuleConstants(
PhoenixDriveConstants.kBackRightSteerMotorId,
PhoenixDriveConstants.kBackRightDriveMotorId,
PhoenixDriveConstants.kBackRightEncoderId,
PhoenixDriveConstants.kBackRightEncoderOffset,
Units.inchesToMeters(PhoenixDriveConstants.kBackRightXPosInches),
Units.inchesToMeters(PhoenixDriveConstants.kBackRightYPosInches),
PhoenixDriveConstants.kInvertRightSide)
.withSteerMotorInverted(PhoenixDriveConstants.kBackRightSteerInvert);

PhoenixDriveConstants.kinematics =
new SwerveDriveKinematics(
new Translation2d(PhoenixDriveConstants.FrontLeft.LocationX, PhoenixDriveConstants.FrontLeft.LocationY),
new Translation2d(PhoenixDriveConstants.FrontLeft.LocationX, PhoenixDriveConstants.FrontRight.LocationY),
new Translation2d(PhoenixDriveConstants.BackLeft.LocationX, PhoenixDriveConstants.BackLeft.LocationY),
new Translation2d(PhoenixDriveConstants.BackRight.LocationX, PhoenixDriveConstants.BackRight.LocationY));
}
}
14 changes: 7 additions & 7 deletions src/main/java/frc/robot/constants/ConversionConstants.java
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
package frc.robot.constants;

public final class ConversionConstants {
public static final double kRadiansPerSecondToRPM = 60.0 / (2.0 * Math.PI);
public static final double kRPMToRadiansPerSecond = 1.0 / kRadiansPerSecondToRPM;
public class ConversionConstants {
public static double kRadiansPerSecondToRPM = 60.0 / (2.0 * Math.PI);
public static double kRPMToRadiansPerSecond = 1.0 / kRadiansPerSecondToRPM;

public static final double kSecondsToMinutes = 1.0 / 60.0;
public static final double kMinutesToSeconds = 60.0;
public static double kSecondsToMinutes = 1.0 / 60.0;
public static double kMinutesToSeconds = 60.0;

public static final double kDegreesToRadians = Math.PI / 180.0;
public static final double kRadiansToDegrees = 180.0 / Math.PI;
public static double kDegreesToRadians = Math.PI / 180.0;
public static double kRadiansToDegrees = 180.0 / Math.PI;
}
6 changes: 0 additions & 6 deletions src/main/java/frc/robot/constants/DriverConstants.java

This file was deleted.

5 changes: 5 additions & 0 deletions src/main/java/frc/robot/constants/DriverConstantsSchema.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
package frc.robot.constants;

public class DriverConstantsSchema {
public double joystickDeadband = 0.16;
}
13 changes: 0 additions & 13 deletions src/main/java/frc/robot/constants/FeatureFlags.java

This file was deleted.

13 changes: 13 additions & 0 deletions src/main/java/frc/robot/constants/FeatureFlagsSchema.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
package frc.robot.constants;

public class FeatureFlagsSchema {
public boolean runDrive = true;
public boolean runVision = false;
// NOTE: A featureflag "runLocalizer" was removed from here recently.
// TODO: Figure out if we need this and add it back if necessary.
public boolean runLocalizer = false;
public boolean runIntake = true;
public boolean runScoring = true;
public boolean runLEDS = true;
public boolean runOrchestra = true;
}
Loading
Loading