Upgrade spotless and shadow (#385)

Fixes Log4J vulnerability
This commit is contained in:
Tyler Veness
2022-01-10 11:56:45 -08:00
committed by GitHub
parent 43c35286f3
commit 46fa17dfd8
62 changed files with 978 additions and 978 deletions

View File

@@ -40,10 +40,10 @@ public class PhotonCamera {
Packet packet = new Packet(1);
/**
* Constructs a PhotonCamera from a root table.
*
* @param rootTable The root table that the camera is broadcasting information over.
*/
* Constructs a PhotonCamera from a root table.
*
* @param rootTable The root table that the camera is broadcasting information over.
*/
public PhotonCamera(NetworkTable rootTable) {
path = rootTable.getPath();
rawBytesEntry = rootTable.getEntry("rawBytes");
@@ -56,19 +56,19 @@ public class PhotonCamera {
}
/**
* Constructs a PhotonCamera from the name of the camera.
*
* @param cameraName The nickname of the camera (found in the PhotonVision UI).
*/
* Constructs a PhotonCamera from the name of the camera.
*
* @param cameraName The nickname of the camera (found in the PhotonVision UI).
*/
public PhotonCamera(String cameraName) {
this(NetworkTableInstance.getDefault().getTable("photonvision").getSubTable(cameraName));
}
/**
* Returns the latest pipeline result.
*
* @return The latest pipeline result.
*/
* Returns the latest pipeline result.
*
* @return The latest pipeline result.
*/
public PhotonPipelineResult getLatestResult() {
verifyVersion();
@@ -88,66 +88,66 @@ public class PhotonCamera {
}
/**
* Returns whether the camera is in driver mode.
*
* @return Whether the camera is in driver mode.
*/
* Returns whether the camera is in driver mode.
*
* @return Whether the camera is in driver mode.
*/
public boolean getDriverMode() {
return driverModeEntry.getBoolean(false);
}
/**
* Toggles driver mode.
*
* @param driverMode Whether to set driver mode.
*/
* Toggles driver mode.
*
* @param driverMode Whether to set driver mode.
*/
public void setDriverMode(boolean driverMode) {
driverModeEntry.setBoolean(driverMode);
}
/**
* Request the camera to save a new image file from the input camera stream with overlays. Images
* take up space in the filesystem of the PhotonCamera. Calling it frequently will fill up disk
* space and eventually cause the system to stop working. Clear out images in
* /opt/photonvision/photonvision_config/imgSaves frequently to prevent issues.
*/
* Request the camera to save a new image file from the input camera stream with overlays. Images
* take up space in the filesystem of the PhotonCamera. Calling it frequently will fill up disk
* space and eventually cause the system to stop working. Clear out images in
* /opt/photonvision/photonvision_config/imgSaves frequently to prevent issues.
*/
public void takeInputSnapshot() {
inputSaveImgEntry.setBoolean(true);
}
/**
* Request the camera to save a new image file from the output stream with overlays. Images take
* up space in the filesystem of the PhotonCamera. Calling it frequently will fill up disk space
* and eventually cause the system to stop working. Clear out images in
* /opt/photonvision/photonvision_config/imgSaves frequently to prevent issues.
*/
* Request the camera to save a new image file from the output stream with overlays. Images take
* up space in the filesystem of the PhotonCamera. Calling it frequently will fill up disk space
* and eventually cause the system to stop working. Clear out images in
* /opt/photonvision/photonvision_config/imgSaves frequently to prevent issues.
*/
public void takeOutputSnapshot() {
outputSaveImgEntry.setBoolean(true);
}
/**
* Returns the active pipeline index.
*
* @return The active pipeline index.
*/
* Returns the active pipeline index.
*
* @return The active pipeline index.
*/
public int getPipelineIndex() {
return pipelineIndexEntry.getNumber(0).intValue();
}
/**
* Allows the user to select the active pipeline index.
*
* @param index The active pipeline index.
*/
* Allows the user to select the active pipeline index.
*
* @param index The active pipeline index.
*/
public void setPipelineIndex(int index) {
pipelineIndexEntry.setNumber(index);
}
/**
* Returns the current LED mode.
*
* @return The current LED mode.
*/
* Returns the current LED mode.
*
* @return The current LED mode.
*/
public VisionLEDMode getLEDMode() {
int value = ledModeEntry.getNumber(-1).intValue();
switch (value) {
@@ -164,22 +164,22 @@ public class PhotonCamera {
}
/**
* Sets the LED mode.
*
* @param led The mode to set to.
*/
* Sets the LED mode.
*
* @param led The mode to set to.
*/
public void setLED(VisionLEDMode led) {
ledModeEntry.setNumber(led.value);
}
/**
* Returns whether the latest target result has targets.
*
* <p>This method is deprecated; {@link PhotonPipelineResult#hasTargets()} should be used instead.
*
* @deprecated This method should be replaced with {@link PhotonPipelineResult#hasTargets()}
* @return Whether the latest target result has targets.
*/
* Returns whether the latest target result has targets.
*
* <p>This method is deprecated; {@link PhotonPipelineResult#hasTargets()} should be used instead.
*
* @deprecated This method should be replaced with {@link PhotonPipelineResult#hasTargets()}
* @return Whether the latest target result has targets.
*/
@Deprecated
public boolean hasTargets() {
return getLatestResult().hasTargets();

View File

@@ -27,25 +27,25 @@ public final class PhotonUtils {
}
/**
* Algorithm from https://docs.limelightvision.io/en/latest/cs_estimating_distance.html Estimates
* range to a target using the target's elevation. This method can produce more stable results
* than SolvePNP when well tuned, if the full 6d robot pose is not required. Note that this method
* requires the camera to have 0 roll (not be skewed clockwise or CCW relative to the floor), and
* for there to exist a height differential between goal and camera. The larger this differential,
* the more accurate the distance estimate will be.
*
* <p>Units can be converted using the {@link edu.wpi.first.math.util.Units} class.
*
* @param cameraHeightMeters The physical height of the camera off the floor in meters.
* @param targetHeightMeters The physical height of the target off the floor in meters. This
* should be the height of whatever is being targeted (i.e. if the targeting region is set to
* top, this should be the height of the top of the target).
* @param cameraPitchRadians The pitch of the camera from the horizontal plane in radians.
* Positive values up.
* @param targetPitchRadians The pitch of the target in the camera's lens in radians. Positive
* values up.
* @return The estimated distance to the target in meters.
*/
* Algorithm from https://docs.limelightvision.io/en/latest/cs_estimating_distance.html Estimates
* range to a target using the target's elevation. This method can produce more stable results
* than SolvePNP when well tuned, if the full 6d robot pose is not required. Note that this method
* requires the camera to have 0 roll (not be skewed clockwise or CCW relative to the floor), and
* for there to exist a height differential between goal and camera. The larger this differential,
* the more accurate the distance estimate will be.
*
* <p>Units can be converted using the {@link edu.wpi.first.math.util.Units} class.
*
* @param cameraHeightMeters The physical height of the camera off the floor in meters.
* @param targetHeightMeters The physical height of the target off the floor in meters. This
* should be the height of whatever is being targeted (i.e. if the targeting region is set to
* top, this should be the height of the top of the target).
* @param cameraPitchRadians The pitch of the camera from the horizontal plane in radians.
* Positive values up.
* @param targetPitchRadians The pitch of the target in the camera's lens in radians. Positive
* values up.
* @return The estimated distance to the target in meters.
*/
public static double calculateDistanceToTargetMeters(
double cameraHeightMeters,
double targetHeightMeters,
@@ -56,12 +56,12 @@ public final class PhotonUtils {
}
/**
* Estimate the {@link Translation2d} of the target relative to the camera.
*
* @param targetDistanceMeters The distance to the target in meters.
* @param yaw The observed yaw of the target.
* @return The target's camera-relative translation.
*/
* Estimate the {@link Translation2d} of the target relative to the camera.
*
* @param targetDistanceMeters The distance to the target in meters.
* @param yaw The observed yaw of the target.
* @return The target's camera-relative translation.
*/
public static Translation2d estimateCameraToTargetTranslation(
double targetDistanceMeters, Rotation2d yaw) {
return new Translation2d(
@@ -69,25 +69,25 @@ public final class PhotonUtils {
}
/**
* Estimate the position of the robot in the field.
*
* @param cameraHeightMeters The physical height of the camera off the floor in meters.
* @param targetHeightMeters The physical height of the target off the floor in meters. This
* should be the height of whatever is being targeted (i.e. if the targeting region is set to
* top, this should be the height of the top of the target).
* @param cameraPitchRadians The pitch of the camera from the horizontal plane in radians.
* Positive values up.
* @param targetPitchRadians The pitch of the target in the camera's lens in radians. Positive
* values up.
* @param targetYaw The observed yaw of the target. Note that this *must* be CCW-positive, and
* Photon returns CW-positive.
* @param gyroAngle The current robot gyro angle, likely from odometry.
* @param fieldToTarget A Pose2d representing the target position in the field coordinate system.
* @param cameraToRobot The position of the robot relative to the camera. If the camera was
* mounted 3 inches behind the "origin" (usually physical center) of the robot, this would be
* Transform2d(3 inches, 0 inches, 0 degrees).
* @return The position of the robot in the field.
*/
* Estimate the position of the robot in the field.
*
* @param cameraHeightMeters The physical height of the camera off the floor in meters.
* @param targetHeightMeters The physical height of the target off the floor in meters. This
* should be the height of whatever is being targeted (i.e. if the targeting region is set to
* top, this should be the height of the top of the target).
* @param cameraPitchRadians The pitch of the camera from the horizontal plane in radians.
* Positive values up.
* @param targetPitchRadians The pitch of the target in the camera's lens in radians. Positive
* values up.
* @param targetYaw The observed yaw of the target. Note that this *must* be CCW-positive, and
* Photon returns CW-positive.
* @param gyroAngle The current robot gyro angle, likely from odometry.
* @param fieldToTarget A Pose2d representing the target position in the field coordinate system.
* @param cameraToRobot The position of the robot relative to the camera. If the camera was
* mounted 3 inches behind the "origin" (usually physical center) of the robot, this would be
* Transform2d(3 inches, 0 inches, 0 degrees).
* @return The position of the robot in the field.
*/
public static Pose2d estimateFieldToRobot(
double cameraHeightMeters,
double targetHeightMeters,
@@ -110,17 +110,17 @@ public final class PhotonUtils {
}
/**
* Estimates a {@link Transform2d} that maps the camera position to the target position, using the
* robot's gyro. Note that the gyro angle provided *must* line up with the field coordinate system
* -- that is, it should read zero degrees when pointed towards the opposing alliance station, and
* increase as the robot rotates CCW.
*
* @param cameraToTargetTranslation A Translation2d that encodes the x/y position of the target
* relative to the camera.
* @param fieldToTarget A Pose2d representing the target position in the field coordinate system.
* @param gyroAngle The current robot gyro angle, likely from odometry.
* @return A Transform2d that takes us from the camera to the target.
*/
* Estimates a {@link Transform2d} that maps the camera position to the target position, using the
* robot's gyro. Note that the gyro angle provided *must* line up with the field coordinate system
* -- that is, it should read zero degrees when pointed towards the opposing alliance station, and
* increase as the robot rotates CCW.
*
* @param cameraToTargetTranslation A Translation2d that encodes the x/y position of the target
* relative to the camera.
* @param fieldToTarget A Pose2d representing the target position in the field coordinate system.
* @param gyroAngle The current robot gyro angle, likely from odometry.
* @return A Transform2d that takes us from the camera to the target.
*/
public static Transform2d estimateCameraToTarget(
Translation2d cameraToTargetTranslation, Pose2d fieldToTarget, Rotation2d gyroAngle) {
// This pose maps our camera at the origin out to our target, in the robot
@@ -133,31 +133,31 @@ public final class PhotonUtils {
}
/**
* Estimates the pose of the robot in the field coordinate system, given the position of the
* target relative to the camera, the target relative to the field, and the robot relative to the
* camera.
*
* @param cameraToTarget The position of the target relative to the camera.
* @param fieldToTarget The position of the target in the field.
* @param cameraToRobot The position of the robot relative to the camera. If the camera was
* mounted 3 inches behind the "origin" (usually physical center) of the robot, this would be
* Transform2d(3 inches, 0 inches, 0 degrees).
* @return The position of the robot in the field.
*/
* Estimates the pose of the robot in the field coordinate system, given the position of the
* target relative to the camera, the target relative to the field, and the robot relative to the
* camera.
*
* @param cameraToTarget The position of the target relative to the camera.
* @param fieldToTarget The position of the target in the field.
* @param cameraToRobot The position of the robot relative to the camera. If the camera was
* mounted 3 inches behind the "origin" (usually physical center) of the robot, this would be
* Transform2d(3 inches, 0 inches, 0 degrees).
* @return The position of the robot in the field.
*/
public static Pose2d estimateFieldToRobot(
Transform2d cameraToTarget, Pose2d fieldToTarget, Transform2d cameraToRobot) {
return estimateFieldToCamera(cameraToTarget, fieldToTarget).transformBy(cameraToRobot);
}
/**
* Estimates the pose of the camera in the field coordinate system, given the position of the
* target relative to the camera, and the target relative to the field. This *only* tracks the
* position of the camera, not the position of the robot itself.
*
* @param cameraToTarget The position of the target relative to the camera.
* @param fieldToTarget The position of the target in the field.
* @return The position of the camera in the field.
*/
* Estimates the pose of the camera in the field coordinate system, given the position of the
* target relative to the camera, and the target relative to the field. This *only* tracks the
* position of the camera, not the position of the robot itself.
*
* @param cameraToTarget The position of the target relative to the camera.
* @param fieldToTarget The position of the target in the field.
* @return The position of the camera in the field.
*/
public static Pose2d estimateFieldToCamera(Transform2d cameraToTarget, Pose2d fieldToTarget) {
var targetToCamera = cameraToTarget.inverse();
return fieldToTarget.transformBy(targetToCamera);

View File

@@ -36,10 +36,10 @@ public class SimPhotonCamera extends PhotonCamera {
private final NetworkTableEntry targetPoseEntry;
/**
* Constructs a Simulated PhotonCamera from a root table.
*
* @param rootTable The root table that the camera is broadcasting information over.
*/
* Constructs a Simulated PhotonCamera from a root table.
*
* @param rootTable The root table that the camera is broadcasting information over.
*/
public SimPhotonCamera(NetworkTable rootTable) {
super(rootTable);
@@ -53,53 +53,53 @@ public class SimPhotonCamera extends PhotonCamera {
}
/**
* Constructs a Simulated PhotonCamera from the name of the camera.
*
* @param cameraName The nickname of the camera (found in the PhotonVision UI).
*/
* Constructs a Simulated PhotonCamera from the name of the camera.
*
* @param cameraName The nickname of the camera (found in the PhotonVision UI).
*/
public SimPhotonCamera(String cameraName) {
this(NetworkTableInstance.getDefault().getTable("photonvision").getSubTable(cameraName));
}
/**
* Simulate one processed frame of vision data, putting one result to NT.
*
* @param latencyMillis Latency of the provided frame
* @param targets Each target detected
*/
* Simulate one processed frame of vision data, putting one result to NT.
*
* @param latencyMillis Latency of the provided frame
* @param targets Each target detected
*/
public void submitProcessedFrame(double latencyMillis, PhotonTrackedTarget... targets) {
submitProcessedFrame(latencyMillis, Arrays.asList(targets));
}
/**
* Simulate one processed frame of vision data, putting one result to NT.
*
* @param latencyMillis Latency of the provided frame
* @param sortMode Order in which to sort targets
* @param targets Each target detected
*/
* Simulate one processed frame of vision data, putting one result to NT.
*
* @param latencyMillis Latency of the provided frame
* @param sortMode Order in which to sort targets
* @param targets Each target detected
*/
public void submitProcessedFrame(
double latencyMillis, PhotonTargetSortMode sortMode, PhotonTrackedTarget... targets) {
submitProcessedFrame(latencyMillis, sortMode, Arrays.asList(targets));
}
/**
* Simulate one processed frame of vision data, putting one result to NT.
*
* @param latencyMillis Latency of the provided frame
* @param targetList List of targets detected
*/
* Simulate one processed frame of vision data, putting one result to NT.
*
* @param latencyMillis Latency of the provided frame
* @param targetList List of targets detected
*/
public void submitProcessedFrame(double latencyMillis, List<PhotonTrackedTarget> targetList) {
submitProcessedFrame(latencyMillis, null, targetList);
}
/**
* Simulate one processed frame of vision data, putting one result to NT.
*
* @param latencyMillis Latency of the provided frame
* @param sortMode Order in which to sort targets
* @param targetList List of targets detected
*/
* Simulate one processed frame of vision data, putting one result to NT.
*
* @param latencyMillis Latency of the provided frame
* @param sortMode Order in which to sort targets
* @param targetList List of targets detected
*/
public void submitProcessedFrame(
double latencyMillis, PhotonTargetSortMode sortMode, List<PhotonTrackedTarget> targetList) {
latencyMillisEntry.setDouble(latencyMillis);

View File

@@ -38,28 +38,28 @@ public class SimVisionSystem {
ArrayList<SimVisionTarget> tgtList;
/**
* Create a simulated vision system involving a camera and coprocessor mounted on a mobile robot
* running PhotonVision, detecting one or more targets scattered around the field. This assumes a
* fairly simple and distortion-less pinhole camera model.
*
* @param camName Name of the PhotonVision camera to create. Align it with the settings you use in
* the PhotonVision GUI.
* @param camDiagFOVDegrees Diagonal Field of View of the camera used. Align it with the
* manufacturer specifications, and/or whatever is configured in the PhotonVision Setting
* page.
* @param camPitchDegrees pitch of the camera's view axis back from horizontal. Make this the same
* as whatever is configured in the PhotonVision Setting page.
* @param cameraToRobot Pose Transform to move from the camera's mount position to the robot's
* position
* @param cameraHeightOffGroundMeters Height of the camera off the ground in meters
* @param maxLEDRangeMeters Maximum distance at which your camera can illuminate the target and
* make it visible. Set to 9000 or more if your vision system does not rely on LED's.
* @param cameraResWidth Width of your camera's image sensor in pixels
* @param cameraResHeight Height of your camera's image sensor in pixels
* @param minTargetArea Minimum area that that the target should be before it's recognized as a
* target by the camera. Match this with your contour filtering settings in the PhotonVision
* GUI.
*/
* Create a simulated vision system involving a camera and coprocessor mounted on a mobile robot
* running PhotonVision, detecting one or more targets scattered around the field. This assumes a
* fairly simple and distortion-less pinhole camera model.
*
* @param camName Name of the PhotonVision camera to create. Align it with the settings you use in
* the PhotonVision GUI.
* @param camDiagFOVDegrees Diagonal Field of View of the camera used. Align it with the
* manufacturer specifications, and/or whatever is configured in the PhotonVision Setting
* page.
* @param camPitchDegrees pitch of the camera's view axis back from horizontal. Make this the same
* as whatever is configured in the PhotonVision Setting page.
* @param cameraToRobot Pose Transform to move from the camera's mount position to the robot's
* position
* @param cameraHeightOffGroundMeters Height of the camera off the ground in meters
* @param maxLEDRangeMeters Maximum distance at which your camera can illuminate the target and
* make it visible. Set to 9000 or more if your vision system does not rely on LED's.
* @param cameraResWidth Width of your camera's image sensor in pixels
* @param cameraResHeight Height of your camera's image sensor in pixels
* @param minTargetArea Minimum area that that the target should be before it's recognized as a
* target by the camera. Match this with your contour filtering settings in the PhotonVision
* GUI.
*/
public SimVisionSystem(
String camName,
double camDiagFOVDegrees,
@@ -88,24 +88,24 @@ public class SimVisionSystem {
}
/**
* Add a target on the field which your vision system is designed to detect. The PhotonCamera from
* this system will report the location of the robot relative to the subset of these targets which
* are visible from the given robot position.
*
* @param target Target to add to the simulated field
*/
* Add a target on the field which your vision system is designed to detect. The PhotonCamera from
* this system will report the location of the robot relative to the subset of these targets which
* are visible from the given robot position.
*
* @param target Target to add to the simulated field
*/
public void addSimVisionTarget(SimVisionTarget target) {
tgtList.add(target);
}
/**
* Adjust the camera position relative to the robot. Use this if your camera is on a gimbal or
* turret or some other mobile platform.
*
* @param newCameraToRobot New Transform from the robot to the camera
* @param newCamHeightMeters New height of the camera off the floor
* @param newCamPitchDegrees New pitch of the camera axis back from horizontal
*/
* Adjust the camera position relative to the robot. Use this if your camera is on a gimbal or
* turret or some other mobile platform.
*
* @param newCameraToRobot New Transform from the robot to the camera
* @param newCamHeightMeters New height of the camera off the floor
* @param newCamPitchDegrees New pitch of the camera axis back from horizontal
*/
public void moveCamera(
Transform2d newCameraToRobot, double newCamHeightMeters, double newCamPitchDegrees) {
this.cameraToRobot = newCameraToRobot;
@@ -114,13 +114,13 @@ public class SimVisionSystem {
}
/**
* Periodic update. Call this once per frame of image data you wish to process and send to
* NetworkTables
*
* @param robotPoseMeters current pose of the robot on the field. Will be used to calculate which
* targets are actually in view, where they are at relative to the robot, and relevant
* PhotonVision parameters.
*/
* Periodic update. Call this once per frame of image data you wish to process and send to
* NetworkTables
*
* @param robotPoseMeters current pose of the robot on the field. Will be used to calculate which
* targets are actually in view, where they are at relative to the robot, and relevant
* PhotonVision parameters.
*/
public void processFrame(Pose2d robotPoseMeters) {
Pose2d cameraPos = robotPoseMeters.transformBy(cameraToRobot.inverse());

View File

@@ -26,15 +26,15 @@ public class SimVisionTarget {
double tgtAreaMeters2;
/**
* Describes a vision target located somewhere on the field that your SimVisionSystem can detect.
*
* @param targetPos Pose2d of the target on the field. Define it such that, if you are standing on
* the middle of the field facing the target, the Y axis points to your left, and the X axis
* points away from you.
* @param targetHeightAboveGroundMeters Height of the target above the field plane, in meters.
* @param targetWidthMeters Width of the outer bounding box of the target in meters.
* @param targetHeightMeters Pair Height of the outer bounding box of the target in meters.
*/
* Describes a vision target located somewhere on the field that your SimVisionSystem can detect.
*
* @param targetPos Pose2d of the target on the field. Define it such that, if you are standing on
* the middle of the field facing the target, the Y axis points to your left, and the X axis
* points away from you.
* @param targetHeightAboveGroundMeters Height of the target above the field plane, in meters.
* @param targetWidthMeters Width of the outer bounding box of the target in meters.
* @param targetHeightMeters Pair Height of the outer bounding box of the target in meters.
*/
public SimVisionTarget(
Pose2d targetPos,
double targetHeightAboveGroundMeters,