Skip to content

Commit

Permalink
refactor: change package from frc.robot to org.team1540.robot2024
Browse files Browse the repository at this point in the history
  • Loading branch information
mimizh2418 committed Jan 9, 2024
1 parent c88d0d9 commit 5e27186
Show file tree
Hide file tree
Showing 19 changed files with 51 additions and 64 deletions.
2 changes: 1 addition & 1 deletion .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -172,7 +172,7 @@ out/
simgui*.json

# Version file
src/main/java/frc/robot/BuildConstants.java
src/main/java/org/team1540/robot2024/BuildConstants.java

ctre_sim/
*.wpilog
Expand Down
4 changes: 2 additions & 2 deletions build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ java {
targetCompatibility = JavaVersion.VERSION_17
}

def ROBOT_MAIN_CLASS = "frc.robot.Main"
def ROBOT_MAIN_CLASS = "org.team1540.robot2024.Main"

// Define my targets (RoboRIO) and artifacts (deployable files)
// This is added by GradleRIO's backing project DeployUtils.
Expand Down Expand Up @@ -133,7 +133,7 @@ tasks.withType(JavaCompile) {
project.compileJava.dependsOn(createVersionFile)
gversion {
srcDir = "src/main/java/"
classPackage = "frc.robot"
classPackage = "org.team1540.robot2024"
className = "BuildConstants"
dateFormat = "yyyy-MM-dd HH:mm:ss z"
timeZone = "America/New_York"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package frc.robot;
package org.team1540.robot2024;

import edu.wpi.first.math.util.Units;

Expand All @@ -24,7 +24,7 @@
* constants are needed, to reduce verbosity.
*/
public final class Constants {
public static final Mode currentMode = Mode.REAL;
public static final Mode currentMode = Mode.SIM;

public static enum Mode {
/** Running on a real robot. */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package frc.robot;
package org.team1540.robot2024;

import edu.wpi.first.wpilibj.RobotBase;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package frc.robot;
package org.team1540.robot2024;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package frc.robot;
package org.team1540.robot2024;

import com.pathplanner.lib.auto.AutoBuilder;
import edu.wpi.first.math.geometry.Pose2d;
Expand All @@ -21,10 +21,10 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import frc.robot.commands.DriveCommands;
import frc.robot.commands.FeedForwardCharacterization;
import frc.robot.subsystems.drive.*;
import frc.robot.util.swerve.SwerveFactory;
import org.team1540.robot2024.commands.DriveCommands;
import org.team1540.robot2024.commands.FeedForwardCharacterization;
import org.team1540.robot2024.subsystems.drive.*;
import org.team1540.robot2024.util.swerve.SwerveFactory;
import org.littletonrobotics.junction.networktables.LoggedDashboardChooser;


Expand Down Expand Up @@ -115,7 +115,7 @@ private void configureButtonBindings() {
drive,
() -> -controller.getLeftY(),
() -> -controller.getLeftX(),
() -> controller.getRightX()));
() -> -controller.getRightX()));
controller.x().onTrue(Commands.runOnce(drive::stopWithX, drive));
controller
.b()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package frc.robot.commands;
package org.team1540.robot2024.commands;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Pose2d;
Expand All @@ -21,7 +21,7 @@
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.robot.subsystems.drive.Drive;
import org.team1540.robot2024.subsystems.drive.Drive;

import java.util.function.DoubleSupplier;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,12 +11,12 @@
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package frc.robot.commands;
package org.team1540.robot2024.commands;

import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Subsystem;
import frc.robot.util.PolynomialRegression;
import org.team1540.robot2024.util.PolynomialRegression;
import java.util.LinkedList;
import java.util.List;
import java.util.function.Consumer;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package frc.robot.subsystems.drive;
package org.team1540.robot2024.subsystems.drive;

import com.pathplanner.lib.auto.AutoBuilder;
import com.pathplanner.lib.pathfinding.Pathfinding;
Expand All @@ -28,12 +28,10 @@
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.util.LocalADStarAK;
import org.team1540.robot2024.util.LocalADStarAK;
import org.littletonrobotics.junction.AutoLogOutput;
import org.littletonrobotics.junction.Logger;


import static frc.robot.Constants.Drivetrain.*;
import org.team1540.robot2024.Constants;

public class Drive extends SubsystemBase {

Expand Down Expand Up @@ -65,7 +63,7 @@ public Drive(
this::setPose,
() -> kinematics.toChassisSpeeds(getModuleStates()),
this::runVelocity,
new HolonomicPathFollowerConfig(MAX_LINEAR_SPEED, DRIVE_BASE_RADIUS, new ReplanningConfig()),
new HolonomicPathFollowerConfig(Constants.Drivetrain.MAX_LINEAR_SPEED, Constants.Drivetrain.DRIVE_BASE_RADIUS, new ReplanningConfig()),
() -> DriverStation.getAlliance().isPresent() && DriverStation.getAlliance().get() == DriverStation.Alliance.Red,
this);
Pathfinding.setPathfinder(new LocalADStarAK());
Expand Down Expand Up @@ -129,7 +127,7 @@ public void runVelocity(ChassisSpeeds speeds) {
// Calculate module setpoints
ChassisSpeeds discreteSpeeds = ChassisSpeeds.discretize(speeds, 0.02);
SwerveModuleState[] setpointStates = kinematics.toSwerveModuleStates(discreteSpeeds);
SwerveDriveKinematics.desaturateWheelSpeeds(setpointStates, MAX_LINEAR_SPEED);
SwerveDriveKinematics.desaturateWheelSpeeds(setpointStates, Constants.Drivetrain.MAX_LINEAR_SPEED);

// Send setpoints to modules
SwerveModuleState[] optimizedSetpointStates = new SwerveModuleState[4];
Expand Down Expand Up @@ -222,25 +220,25 @@ public void setPose(Pose2d pose) {
* Returns the maximum linear speed in meters per sec.
*/
public double getMaxLinearSpeedMetersPerSec() {
return MAX_LINEAR_SPEED;
return Constants.Drivetrain.MAX_LINEAR_SPEED;
}

/**
* Returns the maximum angular speed in radians per sec.
*/
public double getMaxAngularSpeedRadPerSec() {
return MAX_ANGULAR_SPEED;
return Constants.Drivetrain.MAX_ANGULAR_SPEED;
}

/**
* Returns an array of module translations.
*/
public static Translation2d[] getModuleTranslations() {
return new Translation2d[]{
new Translation2d(TRACK_WIDTH_X / 2.0, TRACK_WIDTH_Y / 2.0),
new Translation2d(TRACK_WIDTH_X / 2.0, -TRACK_WIDTH_Y / 2.0),
new Translation2d(-TRACK_WIDTH_X / 2.0, TRACK_WIDTH_Y / 2.0),
new Translation2d(-TRACK_WIDTH_X / 2.0, -TRACK_WIDTH_Y / 2.0)
new Translation2d(Constants.Drivetrain.TRACK_WIDTH_X / 2.0, Constants.Drivetrain.TRACK_WIDTH_Y / 2.0),
new Translation2d(Constants.Drivetrain.TRACK_WIDTH_X / 2.0, -Constants.Drivetrain.TRACK_WIDTH_Y / 2.0),
new Translation2d(-Constants.Drivetrain.TRACK_WIDTH_X / 2.0, Constants.Drivetrain.TRACK_WIDTH_Y / 2.0),
new Translation2d(-Constants.Drivetrain.TRACK_WIDTH_X / 2.0, -Constants.Drivetrain.TRACK_WIDTH_Y / 2.0)
};
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package frc.robot.subsystems.drive;
package org.team1540.robot2024.subsystems.drive;

import edu.wpi.first.math.geometry.Rotation2d;
import org.littletonrobotics.junction.AutoLog;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,12 +1,10 @@
package frc.robot.subsystems.drive;
package org.team1540.robot2024.subsystems.drive;

import com.kauailabs.navx.frc.AHRS;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.SPI;
import edu.wpi.first.wpilibj.Timer;

import java.util.logging.Logger;

public class GyroIONavx implements GyroIO{
private final AHRS navx = new AHRS(SPI.Port.kMXP);
private Rotation2d lastAngle;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package frc.robot.subsystems.drive;
package org.team1540.robot2024.subsystems.drive;

import com.ctre.phoenix6.BaseStatusSignal;
import com.ctre.phoenix6.StatusCode;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,19 +11,16 @@
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package frc.robot.subsystems.drive;
package org.team1540.robot2024.subsystems.drive;

import edu.wpi.first.math.controller.PIDController;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
import edu.wpi.first.math.kinematics.SwerveModuleState;
import edu.wpi.first.math.util.Units;
import frc.robot.Constants;
import org.team1540.robot2024.Constants;
import org.littletonrobotics.junction.Logger;

import static frc.robot.Constants.Drivetrain.WHEEL_RADIUS;

public class Module {


Expand Down Expand Up @@ -96,7 +93,7 @@ public void periodic() {
double adjustSpeedSetpoint = speedSetpoint * Math.cos(turnFeedback.getPositionError());

// Run drive controller
double velocityRadPerSec = adjustSpeedSetpoint / WHEEL_RADIUS;
double velocityRadPerSec = adjustSpeedSetpoint / Constants.Drivetrain.WHEEL_RADIUS;
io.setDriveVoltage(
driveFeedforward.calculate(velocityRadPerSec)
+ driveFeedback.calculate(inputs.driveVelocityRadPerSec, velocityRadPerSec));
Expand Down Expand Up @@ -157,12 +154,12 @@ public Rotation2d getAngle() {

/** Returns the current drive position of the module in meters. */
public double getPositionMeters() {
return inputs.drivePositionRad * WHEEL_RADIUS;
return inputs.drivePositionRad * Constants.Drivetrain.WHEEL_RADIUS;
}

/** Returns the current drive velocity of the module in meters per second. */
public double getVelocityMetersPerSec() {
return inputs.driveVelocityRadPerSec * WHEEL_RADIUS;
return inputs.driveVelocityRadPerSec * Constants.Drivetrain.WHEEL_RADIUS;
}

/** Returns the module position (turn angle and drive position). */
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package frc.robot.subsystems.drive;
package org.team1540.robot2024.subsystems.drive;

import edu.wpi.first.math.geometry.Rotation2d;
import org.littletonrobotics.junction.AutoLog;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package frc.robot.subsystems.drive;
package org.team1540.robot2024.subsystems.drive;

import edu.wpi.first.math.MathUtil;
import edu.wpi.first.math.geometry.Rotation2d;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
// GNU General Public License for more details.

package frc.robot.subsystems.drive;
package org.team1540.robot2024.subsystems.drive;

import com.ctre.phoenix6.BaseStatusSignal;
import com.ctre.phoenix6.StatusSignal;
Expand All @@ -23,9 +23,8 @@
import com.ctre.phoenix6.signals.NeutralModeValue;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.util.Units;
import frc.robot.util.swerve.SwerveFactory;

import static frc.robot.Constants.Drivetrain.*;
import org.team1540.robot2024.util.swerve.SwerveFactory;
import org.team1540.robot2024.Constants;

/**
* Module IO implementation for Talon FX drive motor controller, Talon FX turn motor controller, and
Expand Down Expand Up @@ -93,14 +92,14 @@ public ModuleIOTalonFX(SwerveFactory.SwerveModuleHW hw) {
public void updateInputs(ModuleIOInputs inputs) {
BaseStatusSignal.refreshAll(drivePosition, driveVelocity, driveAppliedVolts, driveCurrent, turnAbsolutePosition, turnPosition, turnVelocity, turnAppliedVolts, turnCurrent);

inputs.drivePositionRad = Units.rotationsToRadians(drivePosition.getValueAsDouble()) / DRIVE_GEAR_RATIO;
inputs.driveVelocityRadPerSec = Units.rotationsToRadians(driveVelocity.getValueAsDouble()) / DRIVE_GEAR_RATIO;
inputs.drivePositionRad = Units.rotationsToRadians(drivePosition.getValueAsDouble()) / Constants.Drivetrain.DRIVE_GEAR_RATIO;
inputs.driveVelocityRadPerSec = Units.rotationsToRadians(driveVelocity.getValueAsDouble()) / Constants.Drivetrain.DRIVE_GEAR_RATIO;
inputs.driveAppliedVolts = driveAppliedVolts.getValueAsDouble();
inputs.driveCurrentAmps = new double[]{driveCurrent.getValueAsDouble()};

inputs.turnAbsolutePosition = Rotation2d.fromRotations(turnAbsolutePosition.getValueAsDouble()).minus(absoluteEncoderOffset);
inputs.turnPosition = Rotation2d.fromRotations(turnPosition.getValueAsDouble() / TURN_GEAR_RATIO);
inputs.turnVelocityRadPerSec = Units.rotationsToRadians(turnVelocity.getValueAsDouble()) / TURN_GEAR_RATIO;
inputs.turnPosition = Rotation2d.fromRotations(turnPosition.getValueAsDouble() / Constants.Drivetrain.TURN_GEAR_RATIO);
inputs.turnVelocityRadPerSec = Units.rotationsToRadians(turnVelocity.getValueAsDouble()) / Constants.Drivetrain.TURN_GEAR_RATIO;
inputs.turnAppliedVolts = turnAppliedVolts.getValueAsDouble();
inputs.turnCurrentAmps = new double[]{turnCurrent.getValueAsDouble()};
}
Expand All @@ -126,7 +125,7 @@ public void setDriveBrakeMode(boolean enable) {
@Override
public void setTurnBrakeMode(boolean enable) {
var config = new MotorOutputConfigs();
config.Inverted = IS_TURN_MOTOR_INVERTED ? InvertedValue.Clockwise_Positive : InvertedValue.CounterClockwise_Positive;
config.Inverted = Constants.Drivetrain.IS_TURN_MOTOR_INVERTED ? InvertedValue.Clockwise_Positive : InvertedValue.CounterClockwise_Positive;
config.NeutralMode = enable ? NeutralModeValue.Brake : NeutralModeValue.Coast;
turnTalon.getConfigurator().apply(config);
}
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.robot.util;
package org.team1540.robot2024.util;

import com.pathplanner.lib.path.GoalEndState;
import com.pathplanner.lib.path.PathConstraints;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.robot.util;
package org.team1540.robot2024.util;

import Jama.Matrix;
import Jama.QRDecomposition;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,19 +1,14 @@
package frc.robot.util.swerve;
package org.team1540.robot2024.util.swerve;

import com.ctre.phoenix6.configs.CANcoderConfiguration;
import com.ctre.phoenix6.configs.MagnetSensorConfigs;
import com.ctre.phoenix6.configs.TalonFXConfiguration;
import com.ctre.phoenix6.hardware.CANcoder;
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.AbsoluteSensorRangeValue;
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.SensorDirectionValue;
import edu.wpi.first.math.geometry.Rotation2d;

import java.util.ArrayList;
import java.util.List;

import static frc.robot.Constants.Drivetrain.CAN_BUS;
import org.team1540.robot2024.Constants;

public class SwerveFactory {
private static final double[] moduleOffsetsRots = new double[]{
Expand All @@ -28,7 +23,7 @@ public class SwerveFactory {
};

public static SwerveModuleHW getModuleMotors(int id, SwerveCorner corner) {
return new SwerveModuleHW(id, corner, CAN_BUS);
return new SwerveModuleHW(id, corner, Constants.Drivetrain.CAN_BUS);
}

public enum SwerveCorner {
Expand Down

0 comments on commit 5e27186

Please sign in to comment.