Skip to content

Commit

Permalink
Added Javadocs for all of vision.
Browse files Browse the repository at this point in the history
  • Loading branch information
sleepyghost-zzz committed Dec 7, 2024
1 parent ae92bd0 commit 28bf63c
Show file tree
Hide file tree
Showing 11 changed files with 260 additions and 44 deletions.
44 changes: 43 additions & 1 deletion vision/src/main/java/coppercore/vision/Camera.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,37 +6,79 @@
import edu.wpi.first.math.numbers.N3;
import org.littletonrobotics.junction.Logger;

/**
* Represents a PhotonVision camera by wrapping a {@link CameraIO} interface. This class is
* responsible for managing the camera's IO, logging camera data, calculating standard deviations,
* assembling {@link CameraMeasurement} objects, and updating the camera's state.
*/
public class Camera {
/** The name of the camera, typically defined in {@link CameraParams}. */
public final String name;

private final CameraIO io;
private final CameraIOInputsAutoLogged inputs;

/**
* Constructs a new {@code Camera} instance.
*
* @param params The parameters used to configure the camera, such as its name.
* @param io The {@link CameraIO} instance that provides the camera's input/output
* functionality.
*/
public Camera(CameraParams params, CameraIO io) {
name = params.name();

this.io = io;
inputs = new CameraIOInputsAutoLogged();
}

/**
* Updates the camera's inputs by polling the {@link CameraIO} and processes the data for
* logging using the {@link Logger}.
*/
public void update() {
io.updateInputs(inputs);
Logger.processInputs("Vision/" + name, inputs);
}

/**
* Checks if the camera has new measurements available.
*
* @return {@code true} if new measurements are available, as indicated by {@link
* coppercore.vision.CameraIO.CameraIOInputs#wasAccepted}.
*/
public boolean hasNewMeasurement() {
return inputs.wasAccepted;
}

/**
* Checks if the camera is currently connected.
*
* @return {@code true} if the camera is connected, as indicated by {@link
* coppercore.vision.CameraIO.CameraIOInputs#connected}.
*/
public boolean isConnected() {
return inputs.connected;
}

/**
* Retrieves the latest measurement from the camera, including the field-to-robot
* transformation, timestamp, and variance.
*
* @return A {@link CameraMeasurement} object containing the latest data.
*/
public CameraMeasurement getLatestMeasurement() {
return new CameraMeasurement(
inputs.latestFieldToRobot, inputs.latestTimestampSeconds, getLatestVariance());
}

/**
* Calculates the variance of the latest measurement based on the distance to the target and the
* number of detected tags.
*
* @return A {@link Matrix} representing the variance of the latest measurement, with dimensions
* {@code N3 x N1}.
*/
public Matrix<N3, N1> getLatestVariance() {
Matrix<N3, N1> stdDev = CoreVisionConstants.singleTagStdDev;
// TODO: Actually calculate variances!
Expand All @@ -52,7 +94,7 @@ public Matrix<N3, N1> getLatestVariance() {
return CoreVisionConstants.rejectionStdDev;
}

// distance based variance
// Distance-based variance
stdDev =
stdDev.times(
1
Expand Down
14 changes: 13 additions & 1 deletion vision/src/main/java/coppercore/vision/CameraContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,22 @@

import java.util.List;

/** This is not an AdvantageKit IO interface, but a class to hold cameras and associated data */
/**
* Represents a container for managing multiple {@link Camera} objects and their associated data.
* This interface provides methods to retrieve the cameras and update their state.
*
* <p>Note: This is not an AdvantageKit IO interface but rather a utility for grouping and managing
* cameras.
*/
public interface CameraContainer {

/**
* Retrieves the list of {@link Camera} objects managed by this container.
*
* @return A {@link List} of {@link Camera} objects.
*/
public List<Camera> getCameras();

/** Updates the state of all {@link Camera} objects in the container. */
public void update();
}
22 changes: 22 additions & 0 deletions vision/src/main/java/coppercore/vision/CameraContainerReal.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,20 +4,42 @@
import java.util.ArrayList;
import java.util.List;

/**
* A implementation of {@link CameraContainer} that manages a list of {@link Camera} objects for
* real-life matches. This class initializes cameras based on a list of {@link CameraParams} and an
* {@link AprilTagFieldLayout}, and provides methods to retrieve and update them.
*/
public class CameraContainerReal implements CameraContainer {

private List<Camera> cameras = new ArrayList<>();

/**
* Constructs a {@code CameraContainerReal} with a list of camera parameters and an AprilTag
* field layout. Each {@link Camera} is initialized with the given parameters and a
* corresponding {@link CameraIOPhoton}.
*
* @param params the list of {@link CameraParams} used to configure the cameras
* @param layout the {@link AprilTagFieldLayout} associated with the cameras
*/
public CameraContainerReal(List<CameraParams> params, AprilTagFieldLayout layout) {
for (CameraParams param : params) {
cameras.add(new Camera(param, CameraIOPhoton.fromRealCameraParams(param, layout)));
}
}

/**
* Retrieves the list of cameras managed by this container.
*
* @return a {@link List} of {@link Camera} objects
*/
public List<Camera> getCameras() {
return cameras;
}

/**
* Updates all cameras in the container by invoking their {@link Camera#update()} method. This
* ensures the cameras are synchronized with the latest data.
*/
public void update() {
for (Camera camera : cameras) {
camera.update();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,19 +3,39 @@
import java.util.ArrayList;
import java.util.List;

/**
* CameraContainerReplay simulates a container for cameras in a replay system. It does not interact
* with a real camera or simulation, and instead it updates the cameras based on replayed data.
*/
public class CameraContainerReplay implements CameraContainer {
private List<Camera> cameras = new ArrayList<>();

/**
* Initializes the CameraContainerReplay with the specified camera parameters.
*
* @param params A list of camera parameters for the replay.
*/
public CameraContainerReplay(List<CameraParams> params) {
for (CameraParams param : params) {
cameras.add(new Camera(param, new CameraIO() {}));
cameras.add(new Camera(param, new CameraIO() {})); // Use a no-op CameraIO for replay
}
}

/**
* Gets the list of cameras in the replay system.
*
* @return A list of cameras.
*/
@Override
public List<Camera> getCameras() {
return cameras;
}

/**
* Updates the cameras by calling the update method on each camera. This does not interact with
* a real vision system but updates based on replayed data.
*/
@Override
public void update() {
for (Camera camera : cameras) {
camera.update();
Expand Down
50 changes: 30 additions & 20 deletions vision/src/main/java/coppercore/vision/CameraContainerSim.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,6 @@

import edu.wpi.first.apriltag.AprilTagFieldLayout;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Twist2d;
import edu.wpi.first.math.kinematics.SwerveDriveKinematics;
import edu.wpi.first.math.kinematics.SwerveModulePosition;
Expand All @@ -15,12 +14,14 @@
import org.littletonrobotics.junction.Logger;
import org.photonvision.simulation.VisionSystemSim;

/**
* CameraContainerSim is used for handling cameras in a sim. It simulates the camera's interactions
* with the robot's state and the field's layout.
*/
public class CameraContainerSim implements CameraContainer {

private VisionSystemSim visionSim = new VisionSystemSim("main");

private List<Camera> cameras = new ArrayList<>();

private Supplier<SwerveModuleState[]> getModuleStates;
private Pose2d latestOdometryPose;
private SwerveModulePosition[] lastModulePositions =
Expand All @@ -31,26 +32,28 @@ public class CameraContainerSim implements CameraContainer {
new SwerveModulePosition()
};
private Timer dtTimer = new Timer();

SwerveDriveKinematics kinematics;

private SwerveDriveKinematics kinematics;

/**
* Initializes a CameraContainerSim with camera parameters and field layout.
*
* @param params A list of camera parameters for the simulation.
* @param layout The layout of the AprilTags in the simulation.
* @param initialPose The initial pose of the robot.
* @param kinematics The kinematics for the robot's swerve drive.
* @param getModuleStates A supplier for the current swerve module states.
*/
public CameraContainerSim(
List<CameraParams> params,
AprilTagFieldLayout layout,
Pose2d initialPose,
SwerveDriveKinematics kinematics,
Supplier<SwerveModuleState[]> getModuleStates) {
this.getModuleStates = getModuleStates;

visionSim.addAprilTags(layout);

this.kinematics = kinematics;

latestOdometryPose =
new Pose2d(
initialPose.getX(),
initialPose.getY(),
Rotation2d.fromRadians(initialPose.getRotation().getRadians()));
new Pose2d(initialPose.getX(), initialPose.getY(), initialPose.getRotation());

for (CameraParams param : params) {
cameras.add(
Expand All @@ -60,10 +63,21 @@ public CameraContainerSim(
}
}

/**
* Gets the list of cameras in the simulation.
*
* @return A list of cameras.
*/
@Override
public List<Camera> getCameras() {
return cameras;
}

/**
* Updates the odometry and camera states for the simulation. Updates both the simulated robot
* pose and camera measurements.
*/
@Override
public void update() {
updateOdometry();
visionSim.update(latestOdometryPose);
Expand All @@ -74,24 +88,20 @@ public void update() {
}
}

/** Updates the robot's odometry based on the latest swerve module states. */
private void updateOdometry() {
SwerveModulePosition[] deltas = new SwerveModulePosition[4];
SwerveModuleState[] states = getModuleStates.get();

double dt = dtTimer.get();
dtTimer.reset();
dtTimer.start();

SwerveModulePosition[] deltas = new SwerveModulePosition[4];
for (int i = 0; i < states.length; i++) {
deltas[i] =
new SwerveModulePosition(
states[i].speedMetersPerSecond * dt
- lastModulePositions[i].distanceMeters,
Rotation2d.fromRadians(
states[i]
.angle
.minus(lastModulePositions[i].angle)
.getRadians()));
states[i].angle.minus(lastModulePositions[i].angle));
}

Twist2d twist = kinematics.toTwist2d(deltas);
Expand Down
31 changes: 29 additions & 2 deletions vision/src/main/java/coppercore/vision/CameraIO.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,25 +4,52 @@
import edu.wpi.first.math.geometry.Rotation2d;
import org.littletonrobotics.junction.AutoLog;

/**
* Interface representing the input/output (IO) functionality for a camera in the vision system.
* This interface provides a method to update camera inputs and includes an inner class for
* encapsulating camera-related data.
*/
public interface CameraIO {

/**
* Class representing the inputs from a camera, including pose, tag information, and connection
* status.
*/
@AutoLog
public static class CameraIOInputs {
/** The most recent pose of the robot relative to the field, as calculated by the camera. */
public Pose3d latestFieldToRobot = new Pose3d();

/** The average distance to detected tags in meters. */
public double averageTagDistanceM = 0.0;

/** The average yaw (rotation) of detected tags, represented as a {@link Rotation2d}. */
public Rotation2d averageTagYaw = new Rotation2d();

/** The number of tags currently detected by the camera. */
public int nTags = 0;

/** The timestamp of the latest measurement in seconds. */
public double latestTimestampSeconds = 0.0;

/** Whether the camera is currently connected. */
public boolean connected = false;

/** Indicates if a new measurement has been received from the camera. */
public boolean isNewMeasurement = false;

/**
* Whether the new camera measurement was accepted by the initial filters. Always false if
* `isNewMeasurement` is false.
* Indicates whether the new camera measurement was accepted by the initial filters. This is
* always {@code false} if {@code isNewMeasurement} is {@code false}.
*/
public boolean wasAccepted = false;
}

/**
* Updates the provided {@link CameraIOInputs} object with the latest camera data. This default
* implementation does nothing and should be overridden by implementing classes.
*
* @param inputs The {@link CameraIOInputs} object to update with the latest camera data.
*/
public default void updateInputs(CameraIOInputs inputs) {}
}
Loading

0 comments on commit 28bf63c

Please sign in to comment.