Skip to content

Commit

Permalink
[docs] Add missing JavaDocs (#6146)
Browse files Browse the repository at this point in the history
  • Loading branch information
calcmogul authored Jan 4, 2024
1 parent 6e58db3 commit f29a7d2
Show file tree
Hide file tree
Showing 145 changed files with 1,106 additions and 94 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -57,8 +57,21 @@ public static class Config {
*/
public boolean debug;

/** Default constructor. */
public Config() {}

/**
* Constructs a detector configuration.
*
* @param numThreads How many threads should be used for computation.
* @param quadDecimate Quad decimation.
* @param quadSigma What Gaussian blur should be applied to the segmented image (used for quad
* detection).
* @param refineEdges When true, the edges of the each quad are adjusted to "snap to" strong
* gradients nearby.
* @param decodeSharpening How much sharpening should be done to decoded images.
* @param debug Debug mode.
*/
Config(
int numThreads,
float quadDecimate,
Expand Down Expand Up @@ -139,8 +152,21 @@ public static class QuadThresholdParameters {
*/
public boolean deglitch;

/** Default constructor. */
public QuadThresholdParameters() {}

/**
* Constructs quad threshold parameters.
*
* @param minClusterPixels Threshold used to reject quads containing too few pixels.
* @param maxNumMaxima How many corner candidates to consider when segmenting a group of pixels
* into a quad.
* @param criticalAngle Critical angle, in radians.
* @param maxLineFitMSE When fitting lines to the contours, the maximum mean squared error
* allowed.
* @param minWhiteBlackDiff Minimum brightness offset.
* @param deglitch Whether the thresholded image be should be deglitched.
*/
QuadThresholdParameters(
int minClusterPixels,
int maxNumMaxima,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,8 +44,11 @@
@JsonIgnoreProperties(ignoreUnknown = true)
@JsonAutoDetect(getterVisibility = JsonAutoDetect.Visibility.NONE)
public class AprilTagFieldLayout {
/** Common origin positions for the AprilTag coordinate system. */
public enum OriginPosition {
/** Blue alliance wall, right side. */
kBlueAllianceWallRightSide,
/** Red alliance wall, right side. */
kRedAllianceWallRightSide,
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,15 +7,20 @@
import java.io.IOException;
import java.io.UncheckedIOException;

/** Loadable AprilTag field layouts. */
public enum AprilTagFields {
/** 2022 Rapid React. */
k2022RapidReact("2022-rapidreact.json"),
/** 2023 Charged Up. */
k2023ChargedUp("2023-chargedup.json");

/** Base resource directory. */
public static final String kBaseResourceDir = "/edu/wpi/first/apriltag/";

/** Alias to the current game. */
public static final AprilTagFields kDefaultField = k2023ChargedUp;

/** Resource filename. */
public final String m_resourceFile;

AprilTagFields(String resourceFile) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,10 +29,19 @@ public Config(double tagSize, double fx, double fy, double cx, double cy) {
this.cy = cy;
}

/** Tag size, in meters. */
public double tagSize;

/** Camera horizontal focal length, in pixels. */
public double fx;

/** Camera vertical focal length, in pixels. */
public double fy;

/** Camera horizontal focal center, in pixels. */
public double cx;

/** Camera vertical focal center, in pixels. */
public double cy;

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -38,8 +38,13 @@ namespace frc {
* towards the opposing alliance). */
class WPILIB_DLLEXPORT AprilTagFieldLayout {
public:
/**
* Common origin positions for the AprilTag coordinate system.
*/
enum class OriginPosition {
/// Blue alliance wall, right side.
kBlueAllianceWallRightSide,
/// Red alliance wall, right side.
kRedAllianceWallRightSide,
};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,8 +12,13 @@

namespace frc {

/**
* Loadable AprilTag field layouts.
*/
enum class AprilTagField {
/// 2022 Rapid React.
k2022RapidReact,
/// 2023 Charged Up.
k2023ChargedUp,

// This is a placeholder for denoting the last supported field. This should
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -39,6 +39,7 @@
* NetworkTables.
*/
public final class CameraServer {
/** CameraServer base port. */
public static final int kBasePort = 1181;

private static final String kPublishName = "/CameraPublisher";
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

package edu.wpi.first.cameraserver;

/** CameraServer shared functions. */
public interface CameraServerShared {
/**
* get the main thread id func.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@

package edu.wpi.first.cameraserver;

/** Storage for CameraServerShared instance. */
public final class CameraServerSharedStore {
private static CameraServerShared cameraServerShared;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -22,10 +22,8 @@ namespace frc {
*/
class CameraServer {
public:
/// CameraServer base port.
static constexpr uint16_t kBasePort = 1181;
static constexpr int kSize640x480 = 0;
static constexpr int kSize320x240 = 1;
static constexpr int kSize160x120 = 2;

/**
* Start automatically capturing images to send to the dashboard.
Expand Down
2 changes: 1 addition & 1 deletion datalogtool/src/main/generate/WPILibVersion.cpp.in
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
/*
/**
* Autogenerated file! Do not manually edit this file. This version is regenerated
* any time the publish task is run, or when this file is deleted.
*/
Expand Down
2 changes: 1 addition & 1 deletion glass/src/app/generate/WPILibVersion.cpp.in
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
/*
/**
* Autogenerated file! Do not manually edit this file. This version is regenerated
* any time the publish task is run, or when this file is deleted.
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,14 @@

package edu.wpi.first.hal.simulation;

/** Interface for simulation buffer callbacks. */
public interface BufferCallback {
/**
* Simulation buffer callback function.
*
* @param name Buffer name.
* @param buffer Buffer.
* @param count Buffer size.
*/
void callback(String name, byte[] buffer, int count);
}
2 changes: 1 addition & 1 deletion outlineviewer/src/main/generate/WPILibVersion.cpp.in
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
/*
/**
* Autogenerated file! Do not manually edit this file. This version is regenerated
* any time the publish task is run, or when this file is deleted.
*/
Expand Down
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
/*
/**
* Autogenerated file! Do not manually edit this file. This version is regenerated
* any time the publish task is run, or when this file is deleted.
*/
Expand Down
2 changes: 1 addition & 1 deletion sysid/src/main/generate/WPILibVersion.cpp.in
Original file line number Diff line number Diff line change
@@ -1,4 +1,4 @@
/*
/**
* Autogenerated file! Do not manually edit this file. This version is regenerated
* any time the publish task is run, or when this file is deleted.
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -25,8 +25,10 @@
* <p>This class is provided by the NewCommands VendorDep
*/
public abstract class Command implements Sendable {
/** Requirements set. */
protected Set<Subsystem> m_requirements = new HashSet<>();

/** Default constructor. */
@SuppressWarnings("this-escape")
protected Command() {
String name = getClass().getName();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -16,4 +16,9 @@
*/
@Deprecated(since = "2024", forRemoval = true)
@SuppressWarnings("PMD.AbstractClassWithoutAnyMethod")
public abstract class CommandBase extends Command {}
public abstract class CommandBase extends Command {
/** Default constructor. */
public CommandBase() {
super();
}
}
Original file line number Diff line number Diff line change
Expand Up @@ -19,9 +19,16 @@
* <p>This class is provided by the NewCommands VendorDep
*/
public class PIDCommand extends Command {
/** PID controller. */
protected final PIDController m_controller;

/** Measurement getter. */
protected DoubleSupplier m_measurement;

/** Setpoint getter. */
protected DoubleSupplier m_setpoint;

/** PID controller output consumer. */
protected DoubleConsumer m_useOutput;

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,10 @@
* <p>This class is provided by the NewCommands VendorDep
*/
public abstract class PIDSubsystem extends SubsystemBase {
/** PID controller. */
protected final PIDController m_controller;

/** Whether PID controller output is enabled. */
protected boolean m_enabled;

/**
Expand Down Expand Up @@ -47,6 +50,11 @@ public void periodic() {
}
}

/**
* Returns the PIDController.
*
* @return The controller.
*/
public PIDController getController() {
return m_controller;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -21,9 +21,16 @@
* <p>This class is provided by the NewCommands VendorDep
*/
public class ProfiledPIDCommand extends Command {
/** Profiled PID controller. */
protected final ProfiledPIDController m_controller;

/** Measurement getter. */
protected DoubleSupplier m_measurement;

/** Goal getter. */
protected Supplier<State> m_goal;

/** Profiled PID controller output consumer. */
protected BiConsumer<Double, State> m_useOutput;

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,10 @@
* <p>This class is provided by the NewCommands VendorDep
*/
public abstract class ProfiledPIDSubsystem extends SubsystemBase {
/** Profiled PID controller. */
protected final ProfiledPIDController m_controller;

/** Whether the profiled PID controller output is enabled. */
protected boolean m_enabled;

/**
Expand Down Expand Up @@ -47,6 +50,11 @@ public void periodic() {
}
}

/**
* Returns the ProfiledPIDController.
*
* @return The controller.
*/
public ProfiledPIDController getController() {
return m_controller;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,9 @@
* <p>This class is provided by the NewCommands VendorDep
*/
public class WaitCommand extends Command {
/** The timer used for waiting. */
protected Timer m_timer = new Timer();

private final double m_duration;

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,10 +42,20 @@ private InternalButton(AtomicBoolean state, AtomicBoolean inverted) {
this.m_inverted = inverted;
}

/**
* Sets whether to invert button state.
*
* @param inverted Whether button state should be inverted.
*/
public void setInverted(boolean inverted) {
m_inverted.set(inverted);
}

/**
* Sets whether button is pressed.
*
* @param pressed Whether button is pressed.
*/
public void setPressed(boolean pressed) {
m_pressed.set(pressed);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -426,6 +426,7 @@ class Command : public wpi::Sendable, public wpi::SendableHelper<Command> {
protected:
Command();

/// Requirements set.
wpi::SmallSet<Subsystem*, 4> m_requirements;

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -74,9 +74,16 @@ class PIDCommand : public CommandHelper<Command, PIDCommand> {
frc::PIDController& GetController();

protected:
/// PID controller.
frc::PIDController m_controller;

/// Measurement getter.
std::function<double()> m_measurement;

/// Setpoint getter.
std::function<double()> m_setpoint;

/// PID controller output consumer.
std::function<void(double)> m_useOutput;
};
} // namespace frc2
Original file line number Diff line number Diff line change
Expand Up @@ -69,7 +69,10 @@ class PIDSubsystem : public SubsystemBase {
frc::PIDController& GetController();

protected:
/// PID controller.
frc::PIDController m_controller;

/// Whether PID controller output is enabled.
bool m_enabled{false};

/**
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -139,9 +139,16 @@ class ProfiledPIDCommand
frc::ProfiledPIDController<Distance>& GetController() { return m_controller; }

protected:
/// Profiled PID controller.
frc::ProfiledPIDController<Distance> m_controller;

/// Measurement getter.
std::function<Distance_t()> m_measurement;

/// Goal getter.
std::function<State()> m_goal;

/// Profiled PID controller output consumer.
std::function<void(double, State)> m_useOutput;
};
} // namespace frc2
Loading

0 comments on commit f29a7d2

Please sign in to comment.