From 652708c45edbc27ec92b484fbd6f9adadc765992 Mon Sep 17 00:00:00 2001 From: TotalTaxAmount Date: Tue, 23 Jan 2024 13:38:38 -0700 Subject: [PATCH] Add javadoc to more classes --- .../frc/robot/commands/DriveCommands.java | 10 ++++ .../controllers/SwerveModuleControlller.java | 32 +++++++++++-- .../frc/robot/subsystems/SwerveSubsystem.java | 1 - .../frc/robot/utils/NetworkTableUtils.java | 47 +++++++++++++++++++ 4 files changed, 86 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/commands/DriveCommands.java b/src/main/java/frc/robot/commands/DriveCommands.java index cd46da2..39c9481 100644 --- a/src/main/java/frc/robot/commands/DriveCommands.java +++ b/src/main/java/frc/robot/commands/DriveCommands.java @@ -14,6 +14,15 @@ public class DriveCommands extends Command { private final DoubleSupplier radians; private final boolean fieldRelativeFromButton; + /** + * This class contains all the drive commands for swerve + * @param swerveSubsystem SwerveSubsystem instance for controlling the swerve drive + * @param forward The target forward meters/second + * @param sideways The target sideways meters/second + * @param radians The target radian for the rotation + * @param fieldRelative If the swerve should be relative to the robot or the field + * @param limited If we are limiting the motors + */ public DriveCommands(SwerveSubsystem swerveSubsystem, DoubleSupplier forward, DoubleSupplier sideways, DoubleSupplier radians, boolean fieldRelative, boolean limited) { this.swerveSubsystem = swerveSubsystem; this.forward = forward; @@ -23,6 +32,7 @@ public DriveCommands(SwerveSubsystem swerveSubsystem, DoubleSupplier forward, Do addRequirements(swerveSubsystem); } + // Don't write javadoc for wpilib functions @Override public void execute() { double forwardDesired = MathUtil.applyDeadband(forward.getAsDouble(), 0.06); diff --git a/src/main/java/frc/robot/controllers/SwerveModuleControlller.java b/src/main/java/frc/robot/controllers/SwerveModuleControlller.java index f6c2682..3592944 100644 --- a/src/main/java/frc/robot/controllers/SwerveModuleControlller.java +++ b/src/main/java/frc/robot/controllers/SwerveModuleControlller.java @@ -6,6 +6,7 @@ import edu.wpi.first.math.kinematics.SwerveModuleState; import frc.robot.constants.DrivetrainConstants; +// TODO: Lots of deprecated stuff here public class SwerveModuleControlller { private final CANSparkMax drivingMotor; private final CANSparkMax turningMotor; @@ -17,14 +18,20 @@ public class SwerveModuleControlller { private double chassisAngularOffset; + /** + * This class contains all the logic and code to control the swerve motors + * @param drivingPort the port for the drive motor + * @param turningPort the port for the turning motor + * @param chassisAngularOffset the angular offset of the motor to the chassis? + */ public SwerveModuleControlller(int drivingPort, int turningPort, double chassisAngularOffset) { this.chassisAngularOffset = chassisAngularOffset; - drivingMotor = new CANSparkMax(drivingPort, CANSparkMaxLowLevel.MotorType.kBrushless); - turningMotor = new CANSparkMax(turningPort, CANSparkMaxLowLevel.MotorType.kBrushless); + drivingMotor = new CANSparkMax(drivingPort, CANSparkLowLevel.MotorType.kBrushless); + turningMotor = new CANSparkMax(turningPort, CANSparkLowLevel.MotorType.kBrushless); // drivingEncoder = drivingMotor.getEncoder(); drivingEncoder = drivingMotor.getEncoder(); - turningEncoder = turningMotor.getAbsoluteEncoder(SparkMaxAbsoluteEncoder.Type.kDutyCycle); + turningEncoder = turningMotor.getAbsoluteEncoder(SparkAbsoluteEncoder.Type.kDutyCycle); drivingPID = drivingMotor.getPIDController(); turningPID = turningMotor.getPIDController(); m_desiredState = new SwerveModuleState(0.0, new Rotation2d()); @@ -71,14 +78,26 @@ public SwerveModuleControlller(int drivingPort, int turningPort, double chassisA turningMotor.burnFlash(); } + /** + * This function gets the state of the swerve module + * @return Returns a SwerveModuleState containing info about the velocity and rotation of the swerve module + */ public SwerveModuleState getState() { return new SwerveModuleState(drivingEncoder.getVelocity(), new Rotation2d(turningEncoder.getPosition() - chassisAngularOffset)); } + /** + * Gets the position of the swerve module + * @return Returns a SwerveModulePosition containing info about the velocity and rotation of the swerve module + */ public SwerveModulePosition getPosition() { return new SwerveModulePosition(drivingEncoder.getPosition(), new Rotation2d(turningEncoder.getPosition() - chassisAngularOffset)); } + /** + * This function sets the state of a swerve module + * @param desiredState the target state for the module + */ public void setDesiredState(SwerveModuleState desiredState) { SwerveModuleState correctedDesiredState = new SwerveModuleState(); correctedDesiredState.speedMetersPerSecond = desiredState.speedMetersPerSecond; @@ -96,10 +115,17 @@ public void setDesiredState(SwerveModuleState desiredState) { } + /** + * Gets the current desired state + * @return returns the desired state as a SwerveModuleState + */ public SwerveModuleState getDesiredState(){ return m_desiredState; } + /** + * This function resets all encoders for the swerve module + */ public void resetEncoders() { drivingEncoder.setPosition(0.0); } diff --git a/src/main/java/frc/robot/subsystems/SwerveSubsystem.java b/src/main/java/frc/robot/subsystems/SwerveSubsystem.java index 2f088eb..08f6cea 100644 --- a/src/main/java/frc/robot/subsystems/SwerveSubsystem.java +++ b/src/main/java/frc/robot/subsystems/SwerveSubsystem.java @@ -161,7 +161,6 @@ public void periodic() { /** * Get robot's pose. */ - private Pose2d getPose() { return odometry.getPoseMeters(); } diff --git a/src/main/java/frc/robot/utils/NetworkTableUtils.java b/src/main/java/frc/robot/utils/NetworkTableUtils.java index 964bea5..7f2a654 100644 --- a/src/main/java/frc/robot/utils/NetworkTableUtils.java +++ b/src/main/java/frc/robot/utils/NetworkTableUtils.java @@ -6,34 +6,76 @@ public class NetworkTableUtils { private NetworkTable table; + /** + * This class is a utility class for interfacing with network tables + * @param table The string ID for a network tables table + */ public NetworkTableUtils(String table) { this.table = NetworkTableInstance.getDefault().getTable(table); } + /** + * This function returns the table of this instance of NetworkTableUtils + * @return Returns the table as a NetworkTable + */ public NetworkTable getTable() { return this.table; } + /** + * This function gets a value from network tables as a double + * @param key The key in Network Tables for the value + * @param defaultValue If the entry is not found or null we will return this + * @return Returns the Network Table entry as a double + */ public double getDouble(String key, double defaultValue) { return this.table.getEntry(key).getDouble(defaultValue); } + /** + * This function gets a value from network tables as a String + * @param key The key in Network Tables for the value + * @param defaultValue If the entry is not found or null we will return this + * @return Returns the Network Table entry as a String + */ public String getString(String key, String defaultValue) { return this.table.getEntry(key).getString(defaultValue); } + /** + * This function gets a value from Network Tables as a double array + * @param key The key in Network Tables for the value + * @param doubles If the entry is not found or null we will return this + * @return Returns the Network Table entry as a double array (double[]) + */ public double[] getDoubleArray(String key, double[] doubles) { return this.table.getEntry(key).getDoubleArray(doubles); } + /** + * This function sets a double in network tables + * @param key The key in Network Tables for the value + * @param value What we are setting the entry to + */ public void setDouble(String key, double value) { this.table.getEntry(key).setDouble(value); } + /** + * This function sets a String in network tables + * @param key The key in Network Tables for the value + * @param value What we are setting the entry to + */ public void setString(String key, String value) { this.table.getEntry(key).setString(value); } + /** + * This function returns a entry as whatever it is + * @param key The key in Network Tables for the value + * @param value We will return this is the entry is invalid + * @return Returns the entry as whatever it is + */ public T getEntry(String key, T value) { if (this.table.getEntry(key).exists()) { if (value instanceof Double) { @@ -48,6 +90,11 @@ public T getEntry(String key, T value) { } } + /** + * Sets a entry in Network Tables to a value + * @param key The key in Network Tables for the value + * @param value The value we are setting the entry to. + */ public void setEntry(String key, T value) { if (this.table.getEntry(key).exists()) { if (value instanceof Double) {