2021-01-16 20:41:47 -08:00
|
|
|
/*
|
2022-01-20 19:35:28 -08:00
|
|
|
* MIT License
|
2021-01-16 20:41:47 -08:00
|
|
|
*
|
2022-01-20 19:35:28 -08:00
|
|
|
* Copyright (c) 2022 PhotonVision
|
2021-01-16 20:41:47 -08:00
|
|
|
*
|
2022-01-20 19:35:28 -08:00
|
|
|
* Permission is hereby granted, free of charge, to any person obtaining a copy
|
|
|
|
|
* of this software and associated documentation files (the "Software"), to deal
|
|
|
|
|
* in the Software without restriction, including without limitation the rights
|
|
|
|
|
* to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
|
|
|
|
|
* copies of the Software, and to permit persons to whom the Software is
|
|
|
|
|
* furnished to do so, subject to the following conditions:
|
2021-01-16 20:41:47 -08:00
|
|
|
*
|
2022-01-20 19:35:28 -08:00
|
|
|
* The above copyright notice and this permission notice shall be included in all
|
|
|
|
|
* copies or substantial portions of the Software.
|
|
|
|
|
*
|
|
|
|
|
* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
|
|
|
|
|
* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
|
|
|
|
|
* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
|
|
|
|
|
* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
|
|
|
|
|
* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
|
|
|
|
|
* OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
|
|
|
|
|
* SOFTWARE.
|
2021-01-16 20:41:47 -08:00
|
|
|
*/
|
2022-01-20 19:35:28 -08:00
|
|
|
|
2021-01-16 20:41:47 -08:00
|
|
|
package org.photonvision;
|
|
|
|
|
|
2023-01-06 17:41:47 -05:00
|
|
|
import edu.wpi.first.apriltag.AprilTag;
|
|
|
|
|
import edu.wpi.first.apriltag.AprilTagFieldLayout;
|
2021-11-21 17:22:56 -08:00
|
|
|
import edu.wpi.first.math.geometry.Pose2d;
|
2022-11-03 15:05:37 -05:00
|
|
|
import edu.wpi.first.math.geometry.Pose3d;
|
2022-12-16 17:05:23 -08:00
|
|
|
import edu.wpi.first.math.geometry.Rotation2d;
|
2022-09-28 18:21:41 -07:00
|
|
|
import edu.wpi.first.math.geometry.Transform3d;
|
2022-12-16 17:05:23 -08:00
|
|
|
import edu.wpi.first.math.geometry.Translation2d;
|
2022-11-03 15:05:37 -05:00
|
|
|
import edu.wpi.first.math.geometry.Translation3d;
|
2021-11-21 17:22:56 -08:00
|
|
|
import edu.wpi.first.math.util.Units;
|
2022-11-03 15:05:37 -05:00
|
|
|
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
|
|
|
|
|
import edu.wpi.first.wpilibj.smartdashboard.FieldObject2d;
|
|
|
|
|
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
2021-01-16 20:41:47 -08:00
|
|
|
import java.util.ArrayList;
|
2022-01-10 20:31:36 -08:00
|
|
|
import java.util.List;
|
2021-01-16 20:41:47 -08:00
|
|
|
import org.photonvision.targeting.PhotonTrackedTarget;
|
2022-01-10 20:31:36 -08:00
|
|
|
import org.photonvision.targeting.TargetCorner;
|
2021-01-16 20:41:47 -08:00
|
|
|
|
|
|
|
|
public class SimVisionSystem {
|
|
|
|
|
SimPhotonCamera cam;
|
|
|
|
|
|
|
|
|
|
double camHorizFOVDegrees;
|
|
|
|
|
double camVertFOVDegrees;
|
|
|
|
|
double cameraHeightOffGroundMeters;
|
|
|
|
|
double maxLEDRangeMeters;
|
|
|
|
|
int cameraResWidth;
|
|
|
|
|
int cameraResHeight;
|
|
|
|
|
double minTargetArea;
|
2023-01-06 17:41:47 -05:00
|
|
|
Transform3d robotToCamera;
|
2022-11-03 15:05:37 -05:00
|
|
|
|
|
|
|
|
Field2d dbgField;
|
|
|
|
|
FieldObject2d dbgRobot;
|
|
|
|
|
FieldObject2d dbgCamera;
|
2021-01-16 20:41:47 -08:00
|
|
|
|
|
|
|
|
ArrayList<SimVisionTarget> tgtList;
|
|
|
|
|
|
|
|
|
|
/**
|
2022-01-10 11:56:45 -08:00
|
|
|
* 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.
|
2023-01-06 17:41:47 -05:00
|
|
|
* @param robotToCamera Transform to move from the center of the robot to the camera's mount
|
|
|
|
|
* position
|
2022-01-10 11:56:45 -08:00
|
|
|
* @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.
|
|
|
|
|
*/
|
2021-01-16 20:41:47 -08:00
|
|
|
public SimVisionSystem(
|
|
|
|
|
String camName,
|
|
|
|
|
double camDiagFOVDegrees,
|
2023-01-06 17:41:47 -05:00
|
|
|
Transform3d robotToCamera,
|
2021-01-16 20:41:47 -08:00
|
|
|
double maxLEDRangeMeters,
|
|
|
|
|
int cameraResWidth,
|
|
|
|
|
int cameraResHeight,
|
|
|
|
|
double minTargetArea) {
|
2023-01-06 17:41:47 -05:00
|
|
|
this.robotToCamera = robotToCamera;
|
2021-01-16 20:41:47 -08:00
|
|
|
this.maxLEDRangeMeters = maxLEDRangeMeters;
|
|
|
|
|
this.cameraResWidth = cameraResWidth;
|
|
|
|
|
this.cameraResHeight = cameraResHeight;
|
|
|
|
|
this.minTargetArea = minTargetArea;
|
|
|
|
|
|
|
|
|
|
// Calculate horizontal/vertical FOV by similar triangles
|
|
|
|
|
double hypotPixels = Math.hypot(cameraResWidth, cameraResHeight);
|
|
|
|
|
this.camHorizFOVDegrees = camDiagFOVDegrees * cameraResWidth / hypotPixels;
|
|
|
|
|
this.camVertFOVDegrees = camDiagFOVDegrees * cameraResHeight / hypotPixels;
|
|
|
|
|
|
|
|
|
|
cam = new SimPhotonCamera(camName);
|
2021-03-23 12:47:26 -04:00
|
|
|
tgtList = new ArrayList<>();
|
2022-11-03 15:05:37 -05:00
|
|
|
|
|
|
|
|
dbgField = new Field2d();
|
|
|
|
|
dbgRobot = dbgField.getRobotObject();
|
|
|
|
|
dbgCamera = dbgField.getObject(camName + " Camera");
|
|
|
|
|
SmartDashboard.putData(camName + " Sim Field", dbgField);
|
2021-01-16 20:41:47 -08:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
2022-01-10 11:56:45 -08:00
|
|
|
* 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
|
|
|
|
|
*/
|
2021-03-23 12:47:26 -04:00
|
|
|
public void addSimVisionTarget(SimVisionTarget target) {
|
|
|
|
|
tgtList.add(target);
|
2022-11-03 15:05:37 -05:00
|
|
|
dbgField
|
|
|
|
|
.getObject("Target " + Integer.toString(target.targetID))
|
|
|
|
|
.setPose(target.targetPose.toPose2d());
|
|
|
|
|
;
|
2021-01-16 20:41:47 -08:00
|
|
|
}
|
|
|
|
|
|
2023-01-06 17:41:47 -05:00
|
|
|
/**
|
|
|
|
|
* Adds all apriltags from the provided {@link AprilTagFieldLayout} as sim vision targets. The
|
|
|
|
|
* poses added will preserve the tag layout's alliance origin at the time of calling this method.
|
|
|
|
|
*
|
|
|
|
|
* @param tagLayout The field tag layout to get Apriltag poses and IDs from
|
|
|
|
|
*/
|
|
|
|
|
public void addVisionTargets(AprilTagFieldLayout tagLayout) {
|
|
|
|
|
for (AprilTag tag : tagLayout.getTags()) {
|
|
|
|
|
addSimVisionTarget(
|
|
|
|
|
new SimVisionTarget(
|
|
|
|
|
tagLayout.getTagPose(tag.ID).get(), // preserve alliance rotation
|
|
|
|
|
Units.inchesToMeters(6),
|
|
|
|
|
Units.inchesToMeters(6),
|
|
|
|
|
tag.ID));
|
|
|
|
|
}
|
|
|
|
|
}
|
|
|
|
|
|
2021-01-16 20:41:47 -08:00
|
|
|
/**
|
2022-01-10 11:56:45 -08:00
|
|
|
* Adjust the camera position relative to the robot. Use this if your camera is on a gimbal or
|
|
|
|
|
* turret or some other mobile platform.
|
|
|
|
|
*
|
2023-01-06 17:41:47 -05:00
|
|
|
* @param newRobotToCamera New Transform from the robot to the camera
|
2022-01-10 11:56:45 -08:00
|
|
|
*/
|
2023-01-06 17:41:47 -05:00
|
|
|
public void moveCamera(Transform3d newRobotToCamera) {
|
|
|
|
|
this.robotToCamera = newRobotToCamera;
|
2021-01-16 20:41:47 -08:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
2022-01-10 11:56:45 -08:00
|
|
|
* 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.
|
|
|
|
|
*/
|
2021-01-16 20:41:47 -08:00
|
|
|
public void processFrame(Pose2d robotPoseMeters) {
|
2023-01-02 19:22:39 -05:00
|
|
|
processFrame(new Pose3d(robotPoseMeters));
|
2022-11-03 15:05:37 -05:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
/**
|
|
|
|
|
* 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 in space. 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(Pose3d robotPoseMeters) {
|
2023-01-06 17:41:47 -05:00
|
|
|
Pose3d cameraPose = robotPoseMeters.transformBy(robotToCamera);
|
2022-11-03 15:05:37 -05:00
|
|
|
|
|
|
|
|
dbgRobot.setPose(robotPoseMeters.toPose2d());
|
|
|
|
|
dbgCamera.setPose(cameraPose.toPose2d());
|
2021-01-16 20:41:47 -08:00
|
|
|
|
|
|
|
|
ArrayList<PhotonTrackedTarget> visibleTgtList = new ArrayList<>(tgtList.size());
|
|
|
|
|
|
|
|
|
|
tgtList.forEach(
|
|
|
|
|
(tgt) -> {
|
2022-11-03 15:05:37 -05:00
|
|
|
var camToTargetTrans = new Transform3d(cameraPose, tgt.targetPose);
|
2022-12-16 17:05:23 -08:00
|
|
|
|
|
|
|
|
// Generate a transformation from camera to target,
|
|
|
|
|
// ignoring rotation.
|
2022-11-03 15:05:37 -05:00
|
|
|
var t = camToTargetTrans.getTranslation();
|
|
|
|
|
|
|
|
|
|
// Rough approximation of the alternate solution, which is (so far) always incorrect.
|
|
|
|
|
var altTrans =
|
|
|
|
|
new Translation3d(
|
|
|
|
|
t.getX(),
|
|
|
|
|
-1.0 * t.getY(),
|
|
|
|
|
t.getZ()); // mirrored across camera axis in Y direction
|
|
|
|
|
var altRot = camToTargetTrans.getRotation().times(-1.0); // flipped
|
|
|
|
|
var camToTargetTransAlt = new Transform3d(altTrans, altRot);
|
|
|
|
|
|
|
|
|
|
double distMeters = t.getNorm();
|
|
|
|
|
|
|
|
|
|
double area_px = tgt.tgtAreaMeters2 / getM2PerPx(distMeters);
|
|
|
|
|
|
2022-12-16 17:05:23 -08:00
|
|
|
var translationAlongGround =
|
|
|
|
|
new Translation2d(
|
|
|
|
|
tgt.targetPose.toPose2d().getX() - cameraPose.toPose2d().getX(),
|
|
|
|
|
tgt.targetPose.toPose2d().getY() - cameraPose.toPose2d().getY());
|
|
|
|
|
|
|
|
|
|
var camAngle = cameraPose.getRotation().toRotation2d();
|
|
|
|
|
var camToTgtRotation =
|
|
|
|
|
new Rotation2d(translationAlongGround.getX(), translationAlongGround.getY());
|
|
|
|
|
double yawDegrees = camToTgtRotation.minus(camAngle).getDegrees();
|
2022-11-03 15:05:37 -05:00
|
|
|
|
|
|
|
|
double camHeightAboveGround = cameraPose.getZ();
|
|
|
|
|
double tgtHeightAboveGround = tgt.targetPose.getZ();
|
|
|
|
|
double camPitchDegrees = Units.radiansToDegrees(cameraPose.getRotation().getY());
|
|
|
|
|
|
2022-12-16 17:05:23 -08:00
|
|
|
double distAlongGround = translationAlongGround.getNorm();
|
2022-11-03 15:05:37 -05:00
|
|
|
|
2021-01-16 20:41:47 -08:00
|
|
|
double pitchDegrees =
|
2022-11-03 15:05:37 -05:00
|
|
|
Units.radiansToDegrees(
|
|
|
|
|
Math.atan2((tgtHeightAboveGround - camHeightAboveGround), distAlongGround))
|
|
|
|
|
- camPitchDegrees;
|
2021-01-16 20:41:47 -08:00
|
|
|
|
2022-11-03 15:05:37 -05:00
|
|
|
if (camCanSeeTarget(distMeters, yawDegrees, pitchDegrees, area_px)) {
|
2022-01-10 20:31:36 -08:00
|
|
|
// TODO simulate target corners
|
2021-01-16 20:41:47 -08:00
|
|
|
visibleTgtList.add(
|
2022-01-10 20:31:36 -08:00
|
|
|
new PhotonTrackedTarget(
|
|
|
|
|
yawDegrees,
|
|
|
|
|
pitchDegrees,
|
2022-11-03 15:05:37 -05:00
|
|
|
area_px,
|
2022-01-10 20:31:36 -08:00
|
|
|
0.0,
|
2022-11-03 15:05:37 -05:00
|
|
|
tgt.targetID,
|
|
|
|
|
camToTargetTrans,
|
|
|
|
|
camToTargetTransAlt,
|
|
|
|
|
0.0, // TODO - simulate ambiguity when straight on?
|
2022-01-10 20:31:36 -08:00
|
|
|
List.of(
|
|
|
|
|
new TargetCorner(0, 0), new TargetCorner(0, 0),
|
2023-01-06 19:20:27 -08:00
|
|
|
new TargetCorner(0, 0), new TargetCorner(0, 0)),
|
|
|
|
|
List.of(
|
|
|
|
|
new TargetCorner(0, 0), new TargetCorner(0, 0),
|
2022-01-10 20:31:36 -08:00
|
|
|
new TargetCorner(0, 0), new TargetCorner(0, 0))));
|
2021-01-16 20:41:47 -08:00
|
|
|
}
|
|
|
|
|
});
|
|
|
|
|
|
|
|
|
|
cam.submitProcessedFrame(0.0, visibleTgtList);
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
double getM2PerPx(double dist) {
|
|
|
|
|
double widthMPerPx =
|
|
|
|
|
2 * dist * Math.tan(Units.degreesToRadians(this.camHorizFOVDegrees) / 2) / cameraResWidth;
|
|
|
|
|
double heightMPerPx =
|
|
|
|
|
2 * dist * Math.tan(Units.degreesToRadians(this.camVertFOVDegrees) / 2) / cameraResHeight;
|
|
|
|
|
return widthMPerPx * heightMPerPx;
|
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
boolean camCanSeeTarget(double distMeters, double yaw, double pitch, double area) {
|
|
|
|
|
boolean inRange = (distMeters < this.maxLEDRangeMeters);
|
|
|
|
|
boolean inHorizAngle = Math.abs(yaw) < (this.camHorizFOVDegrees / 2);
|
|
|
|
|
boolean inVertAngle = Math.abs(pitch) < (this.camVertFOVDegrees / 2);
|
|
|
|
|
boolean targetBigEnough = area > this.minTargetArea;
|
|
|
|
|
return (inRange && inHorizAngle && inVertAngle && targetBigEnough);
|
|
|
|
|
}
|
|
|
|
|
}
|