Skip to content

Commit

Permalink
chore: do the cool package name thing
Browse files Browse the repository at this point in the history
  • Loading branch information
amb2127 committed Feb 12, 2024
1 parent 85e0461 commit b61a203
Show file tree
Hide file tree
Showing 64 changed files with 169 additions and 169 deletions.
2 changes: 1 addition & 1 deletion .gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -328,6 +328,6 @@ bin/

# End entries from WPI Lib team

src/main/java/frc/robot/BuildConstants.java
src/main/java/org.codeorange/robot/BuildConstants.java

ctre_sim/
4 changes: 2 additions & 2 deletions build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@ java {
targetCompatibility = javaVersion
}

def ROBOT_MAIN_CLASS = "frc.robot.Main"
def ROBOT_MAIN_CLASS = "org.codeorange.robot.Main"

// Define my targets (RoboRIO) and artifacts (deployable files)
// This is added by GradleRIO's backing project DeployUtils.
Expand Down Expand Up @@ -118,7 +118,7 @@ test{
project.compileJava.dependsOn(createVersionFile)
gversion {
srcDir = "src/main/java/"
classPackage = "frc.robot"
classPackage = "org.codeorange.robot"
className = "BuildConstants"
dateFormat = "yyyy-MM-dd HH:mm:ss z"
timeZone = "America/Los_Angeles" // Use preferred time zone
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
package frc.auto;
package org.codeorange.auto;

import frc.auto.routines.BaseRoutine;
import frc.auto.routines.DoNothing;
import frc.auto.routines.TestRoutine;
import org.codeorange.auto.routines.BaseRoutine;
import org.codeorange.auto.routines.DoNothing;
import org.codeorange.auto.routines.TestRoutine;

public class AutoManager {
private BaseRoutine selectedRoutine;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.auto.actions;
package org.codeorange.auto.actions;

public interface BaseAction {
default void start() {};
Expand Down
Original file line number Diff line number Diff line change
@@ -1,14 +1,14 @@
package frc.auto.actions;
package org.codeorange.auto.actions;

import com.choreo.lib.Choreo;
import com.choreo.lib.ChoreoControlFunction;
import com.choreo.lib.ChoreoTrajectory;
import com.choreo.lib.ChoreoTrajectoryState;
import edu.wpi.first.math.kinematics.ChassisSpeeds;
import edu.wpi.first.wpilibj.Timer;
import frc.robot.Robot;
import frc.subsystem.drive.Drive;
import frc.utility.wpimodified.PIDController;
import org.codeorange.robot.Robot;
import org.codeorange.subsystem.drive.Drive;
import org.codeorange.utility.wpimodified.PIDController;

public class DrivePath implements BaseAction {
private static Drive drive = Robot.getDrive();
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.auto.actions;
package org.codeorange.auto.actions;

import java.util.Arrays;
import java.util.List;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.auto.actions;
package org.codeorange.auto.actions;

import java.util.Arrays;
import java.util.List;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
package frc.auto.actions;
package org.codeorange.auto.actions;

import frc.subsystem.Superstructure;
import org.codeorange.subsystem.Superstructure;

public class SetSuperstructureState implements BaseAction {
private final Superstructure superstructure;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.auto.actions;
package org.codeorange.auto.actions;

public class Shoot implements BaseAction {
@Override
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.auto.actions;
package org.codeorange.auto.actions;

import edu.wpi.first.wpilibj.Timer;
import org.littletonrobotics.junction.Logger;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
package frc.auto.routines;
package org.codeorange.auto.routines;

import com.choreo.lib.Choreo;
import frc.auto.actions.BaseAction;
import frc.robot.Robot;
import frc.subsystem.drive.Drive;
import org.codeorange.auto.actions.BaseAction;
import org.codeorange.robot.Robot;
import org.codeorange.subsystem.drive.Drive;

public abstract class BaseRoutine {
protected boolean isActive = false;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.auto.routines;
package org.codeorange.auto.routines;

public class DoNothing extends BaseRoutine {
@Override
Expand Down
Original file line number Diff line number Diff line change
@@ -1,11 +1,11 @@
package frc.auto.routines;
package org.codeorange.auto.routines;

import com.choreo.lib.Choreo;
import com.choreo.lib.ChoreoTrajectory;
import frc.auto.actions.*;
import frc.robot.Robot;
import frc.subsystem.Superstructure;
import frc.subsystem.drive.Drive;
import org.codeorange.auto.actions.*;
import org.codeorange.robot.Robot;
import org.codeorange.subsystem.Superstructure;
import org.codeorange.subsystem.drive.Drive;

import java.util.List;

Expand Down
Original file line number Diff line number Diff line change
@@ -1,13 +1,13 @@
package frc.robot;
package org.codeorange.robot;

import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.controller.SimpleMotorFeedforward;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.util.Units;
import frc.utility.MacAddressUtil;
import frc.utility.MacAddressUtil.RobotIdentity;
import frc.utility.swerve.SwerveSetpointGenerator;
import frc.utility.swerve.SecondOrderKinematics;
import org.codeorange.utility.MacAddressUtil;
import org.codeorange.utility.MacAddressUtil.RobotIdentity;
import org.codeorange.utility.swerve.SwerveSetpointGenerator;
import org.codeorange.utility.swerve.SecondOrderKinematics;
import org.jetbrains.annotations.NotNull;
import org.joml.Vector3d;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot;
package org.codeorange.robot;

import edu.wpi.first.wpilibj.RobotBase;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,34 +3,34 @@
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.

package frc.robot;
package org.codeorange.robot;

import com.choreo.lib.ChoreoTrajectory;
import edu.wpi.first.wpilibj.PowerDistribution;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import frc.auto.AutoManager;
import frc.subsystem.AbstractSubsystem;
import frc.subsystem.arm.Arm;
import frc.subsystem.arm.ArmIO;
import frc.subsystem.arm.ArmIOTalonFX;
import frc.subsystem.Superstructure;
import frc.subsystem.drive.*;
import frc.subsystem.intake.IntakeIO;
import frc.subsystem.vision.Vision;
import frc.subsystem.wrist.Wrist;
import frc.subsystem.wrist.WristIO;
import frc.subsystem.wrist.WristIOTalonFX;
import frc.subsystem.elevator.Elevator;
import frc.subsystem.elevator.ElevatorIO;
import frc.subsystem.elevator.ElevatorIOTalonFX;
import frc.subsystem.shooter.*;
import frc.subsystem.intake.Intake;
import frc.subsystem.intake.IntakeIOTalonFX;
import frc.utility.Controller;
import frc.utility.Controller.XboxButtons;
import frc.utility.ControllerDriveInputs;
import frc.utility.MacAddressUtil;
import frc.utility.net.editing.LiveEditableValue;
import org.codeorange.auto.AutoManager;
import org.codeorange.subsystem.AbstractSubsystem;
import org.codeorange.subsystem.arm.Arm;
import org.codeorange.subsystem.arm.ArmIO;
import org.codeorange.subsystem.arm.ArmIOTalonFX;
import org.codeorange.subsystem.Superstructure;
import org.codeorange.subsystem.drive.*;
import org.codeorange.subsystem.intake.IntakeIO;
import org.codeorange.subsystem.vision.Vision;
import org.codeorange.subsystem.wrist.Wrist;
import org.codeorange.subsystem.wrist.WristIO;
import org.codeorange.subsystem.wrist.WristIOTalonFX;
import org.codeorange.subsystem.elevator.Elevator;
import org.codeorange.subsystem.elevator.ElevatorIO;
import org.codeorange.subsystem.elevator.ElevatorIOTalonFX;
import org.codeorange.subsystem.shooter.*;
import org.codeorange.subsystem.intake.Intake;
import org.codeorange.subsystem.intake.IntakeIOTalonFX;
import org.codeorange.utility.Controller;
import org.codeorange.utility.Controller.XboxButtons;
import org.codeorange.utility.ControllerDriveInputs;
import org.codeorange.utility.MacAddressUtil;
import org.codeorange.utility.net.editing.LiveEditableValue;
import org.littletonrobotics.junction.AutoLogOutputManager;
import org.littletonrobotics.junction.LogFileUtil;
import org.littletonrobotics.junction.LoggedRobot;
Expand All @@ -49,7 +49,7 @@
import java.util.Objects;
import java.util.concurrent.ConcurrentLinkedDeque;

import static frc.robot.Constants.*;
import static org.codeorange.robot.Constants.*;


/**
Expand Down Expand Up @@ -207,7 +207,7 @@ public void robotInit() {
superstructure.setCurrentState(Superstructure.States.STOW);

AutoManager.getInstance();
AutoLogOutputManager.addPackage("frc.subsystem");
AutoLogOutputManager.addPackage("org.codeorange.subsystem");
}

/** This function is called periodically during all modes. */
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
package frc.subsystem;
package org.codeorange.subsystem;

import edu.wpi.first.networktables.NetworkTable;
import edu.wpi.first.networktables.NetworkTableInstance;
import frc.robot.Constants;
import org.codeorange.robot.Constants;
import org.jetbrains.annotations.NotNull;
import org.jetbrains.annotations.Nullable;
import org.littletonrobotics.junction.Logger;
Expand Down
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
package frc.subsystem;
package org.codeorange.subsystem;

import edu.wpi.first.wpilibj.Filesystem;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import frc.subsystem.shooter.Shooter;
import org.codeorange.subsystem.shooter.Shooter;

import java.io.BufferedReader;
import java.io.FileReader;
Expand All @@ -11,16 +11,16 @@
import java.util.Map;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.wpilibj.DriverStation;
import frc.robot.Constants;
import frc.robot.Robot;
import frc.subsystem.arm.Arm;
import frc.subsystem.drive.Drive;
import frc.subsystem.elevator.Elevator;
import frc.subsystem.shooter.Shooter;
import frc.subsystem.intake.Intake;
import frc.subsystem.wrist.Wrist;
import frc.utility.MathUtil;
import frc.utility.net.editing.LiveEditableValue;
import org.codeorange.robot.Constants;
import org.codeorange.robot.Robot;
import org.codeorange.subsystem.arm.Arm;
import org.codeorange.subsystem.drive.Drive;
import org.codeorange.subsystem.elevator.Elevator;
import org.codeorange.subsystem.shooter.Shooter;
import org.codeorange.subsystem.intake.Intake;
import org.codeorange.subsystem.wrist.Wrist;
import org.codeorange.utility.MathUtil;
import org.codeorange.utility.net.editing.LiveEditableValue;
import org.littletonrobotics.junction.Logger;

public class Superstructure extends AbstractSubsystem {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
package frc.subsystem.arm;
package org.codeorange.subsystem.arm;

import frc.subsystem.AbstractSubsystem;
import org.codeorange.subsystem.AbstractSubsystem;
import org.littletonrobotics.junction.Logger;

public class Arm extends AbstractSubsystem {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
package frc.subsystem.arm;
package org.codeorange.subsystem.arm;

import frc.robot.Constants;
import org.codeorange.robot.Constants;
import org.littletonrobotics.junction.AutoLog;

public interface ArmIO {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.subsystem.arm;
package org.codeorange.subsystem.arm;

import com.ctre.phoenix6.BaseStatusSignal;
import com.ctre.phoenix6.StatusCode;
Expand All @@ -12,7 +12,7 @@
import com.ctre.phoenix6.hardware.TalonFX;
import com.ctre.phoenix6.signals.*;

import static frc.robot.Constants.Ports.*;
import static org.codeorange.robot.Constants.Ports.*;


public class ArmIOTalonFX implements ArmIO {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,9 +1,9 @@
package frc.subsystem.climber;
package org.codeorange.subsystem.climber;
import edu.wpi.first.math.MathUtil;
import frc.subsystem.AbstractSubsystem;
import org.codeorange.subsystem.AbstractSubsystem;
import org.littletonrobotics.junction.Logger;

import static frc.robot.Constants.*;
import static org.codeorange.robot.Constants.*;
/*
The climber works by engaging and disengaging a ratchet through the Spike H-Bridge Relay. When the relay is set to the
off position, the ratchet is engaged because of a spring-loaded pawl. When it is engaged, the climber can move back
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.subsystem.climber;
package org.codeorange.subsystem.climber;
import org.littletonrobotics.junction.AutoLog;

public interface ClimberIO {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
package frc.subsystem.climber;
package org.codeorange.subsystem.climber;

import com.ctre.phoenix6.BaseStatusSignal;
import com.ctre.phoenix6.StatusSignal;
Expand All @@ -9,12 +9,12 @@
import com.ctre.phoenix6.signals.InvertedValue;
import com.ctre.phoenix6.signals.NeutralModeValue;
import edu.wpi.first.wpilibj.Relay;
import frc.robot.Constants;
import org.codeorange.robot.Constants;

import static edu.wpi.first.wpilibj.Relay.Value.*;
import static frc.robot.Constants.ELEVATOR_STALLING_CURRENT;
import static frc.robot.Constants.Ports.WRIST_ENCODER;
import static frc.robot.Constants.Ports.WRIST_MOTOR;
import static org.codeorange.robot.Constants.ELEVATOR_STALLING_CURRENT;
import static org.codeorange.robot.Constants.Ports.WRIST_ENCODER;
import static org.codeorange.robot.Constants.Ports.WRIST_MOTOR;

public class ClimberIOTalonFX implements ClimberIO {
private final StatusSignal<Double> climberPosition;
Expand Down
Loading

0 comments on commit b61a203

Please sign in to comment.