Skip to content

Commit

Permalink
Merge pull request #152 from frc937/javadoc-cleanup
Browse files Browse the repository at this point in the history
Clean up JavaDoc post-Heartland
  • Loading branch information
willitcode authored Mar 19, 2024
2 parents 59bf5eb + d88890e commit 32cf230
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 4 deletions.
1 change: 1 addition & 0 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -162,6 +162,7 @@ public static class Intake {
/** Current limit (in amps) for the intake motor(s) */
public static final int INTAKE_MOTOR_CURRENT_LIMIT = 40;

/** Idle mode for the intake motors. (Either brake or coast) */
public static final IdleMode INTAKE_MOTOR_IDLE_MODE = IdleMode.kBrake;
}

Expand Down
2 changes: 1 addition & 1 deletion src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -93,7 +93,7 @@ public class RobotContainer {
/** Singleton instance of {@link PDP} for the whole robot. */
public static PDP pdp = new PDP();

/* TODO: JAVADOC */
/** Singleton instance of the intake {@link Camera} for the whole robot. */
public static Camera intakeCamera = new Camera(0);

/*
Expand Down
13 changes: 10 additions & 3 deletions src/main/java/frc/robot/subsystems/Camera.java
Original file line number Diff line number Diff line change
Expand Up @@ -17,21 +17,28 @@
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;

/** Subsystem for a USB camera. */
public class Camera extends SubsystemBase {
private int port;
private UsbCamera camera;

/** Creates a new Camera. */
/**
* Creates a new Camera.
*
* @param port The USB port number on the RoboRIO that the camera is plugged into. (This will
* determine which /dev/videoX device the CameraServer tries to find).
*/
public Camera(int port) {
this.port = port;
}

/**
* Starts the camera that this subsystem represents and adds it to the Driver tab on Shuffleboard.
*/
public void startCamera() {
camera = CameraServer.startAutomaticCapture(port);
camera.setConnectionStrategy(ConnectionStrategy.kKeepOpen);

System.out.println("Camera started");

Shuffleboard.getTab("Driver").add(camera).withSize(4, 4);
}

Expand Down

0 comments on commit 32cf230

Please sign in to comment.