mirror of
https://github.com/PhotonVision/photonvision
synced 2026-06-20 00:51:41 +00:00
@@ -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);
|
||||
|
||||
Reference in New Issue
Block a user