001/*
002 * MIT License
003 *
004 * Copyright (c) PhotonVision
005 *
006 * Permission is hereby granted, free of charge, to any person obtaining a copy
007 * of this software and associated documentation files (the "Software"), to deal
008 * in the Software without restriction, including without limitation the rights
009 * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
010 * copies of the Software, and to permit persons to whom the Software is
011 * furnished to do so, subject to the following conditions:
012 *
013 * The above copyright notice and this permission notice shall be included in all
014 * copies or substantial portions of the Software.
015 *
016 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
017 * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
018 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
019 * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
020 * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
021 * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
022 * SOFTWARE.
023 */
024
025package org.photonvision.simulation;
026
027import edu.wpi.first.apriltag.AprilTag;
028import edu.wpi.first.apriltag.AprilTagFieldLayout;
029import edu.wpi.first.math.geometry.Pose2d;
030import edu.wpi.first.math.geometry.Pose3d;
031import edu.wpi.first.math.geometry.Transform3d;
032import edu.wpi.first.math.interpolation.TimeInterpolatableBuffer;
033import edu.wpi.first.wpilibj.Timer;
034import edu.wpi.first.wpilibj.smartdashboard.Field2d;
035import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
036import java.util.ArrayList;
037import java.util.Collection;
038import java.util.HashMap;
039import java.util.HashSet;
040import java.util.List;
041import java.util.Map;
042import java.util.Optional;
043import java.util.Set;
044import java.util.stream.Collectors;
045import org.photonvision.PhotonCamera;
046import org.photonvision.estimation.TargetModel;
047
048/**
049 * A simulated vision system involving a camera(s) and coprocessor(s) mounted on a mobile robot
050 * running PhotonVision, detecting targets placed on the field. {@link VisionTargetSim}s added to
051 * this class will be detected by the {@link PhotonCameraSim}s added to this class. This class
052 * should be updated periodically with the robot's current pose in order to publish the simulated
053 * camera target info.
054 */
055public class VisionSystemSim {
056    private final Map<String, PhotonCameraSim> camSimMap = new HashMap<>();
057    private static final double kBufferLengthSeconds = 1.5;
058    // save robot-to-camera for each camera over time (Pose3d is easily interpolatable)
059    private final Map<PhotonCameraSim, TimeInterpolatableBuffer<Pose3d>> camTrfMap = new HashMap<>();
060
061    // interpolate drivetrain with twists
062    private final TimeInterpolatableBuffer<Pose3d> robotPoseBuffer =
063            TimeInterpolatableBuffer.createBuffer(kBufferLengthSeconds);
064
065    private final Map<String, Set<VisionTargetSim>> targetSets = new HashMap<>();
066
067    private final Field2d dbgField;
068
069    private final Transform3d kEmptyTrf = new Transform3d();
070
071    /**
072     * A simulated vision system involving a camera(s) and coprocessor(s) mounted on a mobile robot
073     * running PhotonVision, detecting targets placed on the field. {@link VisionTargetSim}s added to
074     * this class will be detected by the {@link PhotonCameraSim}s added to this class. This class
075     * should be updated periodically with the robot's current pose in order to publish the simulated
076     * camera target info.
077     *
078     * @param visionSystemName The specific identifier for this vision system in NetworkTables.
079     */
080    public VisionSystemSim(String visionSystemName) {
081        dbgField = new Field2d();
082        String tableName = "VisionSystemSim-" + visionSystemName;
083        SmartDashboard.putData(tableName + "/Sim Field", dbgField);
084    }
085
086    /** Get one of the simulated cameras. */
087    public Optional<PhotonCameraSim> getCameraSim(String name) {
088        return Optional.ofNullable(camSimMap.get(name));
089    }
090
091    /** Get all the simulated cameras. */
092    public Collection<PhotonCameraSim> getCameraSims() {
093        return camSimMap.values();
094    }
095
096    /**
097     * Adds a simulated camera to this vision system with a specified robot-to-camera transformation.
098     * The vision targets registered with this vision system simulation will be observed by the
099     * simulated {@link PhotonCamera}.
100     *
101     * @param cameraSim The camera simulation
102     * @param robotToCamera The transform from the robot pose to the camera pose
103     */
104    public void addCamera(PhotonCameraSim cameraSim, Transform3d robotToCamera) {
105        var existing = camSimMap.putIfAbsent(cameraSim.getCamera().getName(), cameraSim);
106        if (existing == null) {
107            camTrfMap.put(cameraSim, TimeInterpolatableBuffer.createBuffer(kBufferLengthSeconds));
108            camTrfMap
109                    .get(cameraSim)
110                    .addSample(Timer.getFPGATimestamp(), new Pose3d().plus(robotToCamera));
111        }
112    }
113
114    /** Remove all simulated cameras from this vision system. */
115    public void clearCameras() {
116        camSimMap.clear();
117        camTrfMap.clear();
118    }
119
120    /**
121     * Remove a simulated camera from this vision system.
122     *
123     * @return If the camera was present and removed
124     */
125    public boolean removeCamera(PhotonCameraSim cameraSim) {
126        boolean success = camSimMap.remove(cameraSim.getCamera().getName()) != null;
127        camTrfMap.remove(cameraSim);
128        return success;
129    }
130
131    /**
132     * Get a simulated camera's position relative to the robot. If the requested camera is invalid, an
133     * empty optional is returned.
134     *
135     * @param cameraSim The specific camera to get the robot-to-camera transform of
136     * @return The transform of this camera, or an empty optional if it is invalid
137     */
138    public Optional<Transform3d> getRobotToCamera(PhotonCameraSim cameraSim) {
139        return getRobotToCamera(cameraSim, Timer.getFPGATimestamp());
140    }
141
142    /**
143     * Get a simulated camera's position relative to the robot. If the requested camera is invalid, an
144     * empty optional is returned.
145     *
146     * @param cameraSim The specific camera to get the robot-to-camera transform of
147     * @param timeSeconds Timestamp in seconds of when the transform should be observed
148     * @return The transform of this camera, or an empty optional if it is invalid
149     */
150    public Optional<Transform3d> getRobotToCamera(PhotonCameraSim cameraSim, double timeSeconds) {
151        var trfBuffer = camTrfMap.get(cameraSim);
152        if (trfBuffer == null) return Optional.empty();
153        var sample = trfBuffer.getSample(timeSeconds);
154        if (sample.isEmpty()) return Optional.empty();
155        return Optional.of(new Transform3d(new Pose3d(), sample.orElse(new Pose3d())));
156    }
157
158    /**
159     * Get a simulated camera's position on the field. If the requested camera is invalid, an empty
160     * optional is returned.
161     *
162     * @param cameraSim The specific camera to get the field pose of
163     * @return The pose of this camera, or an empty optional if it is invalid
164     */
165    public Optional<Pose3d> getCameraPose(PhotonCameraSim cameraSim) {
166        return getCameraPose(cameraSim, Timer.getFPGATimestamp());
167    }
168
169    /**
170     * Get a simulated camera's position on the field. If the requested camera is invalid, an empty
171     * optional is returned.
172     *
173     * @param cameraSim The specific camera to get the field pose of
174     * @param timeSeconds Timestamp in seconds of when the pose should be observed
175     * @return The pose of this camera, or an empty optional if it is invalid
176     */
177    public Optional<Pose3d> getCameraPose(PhotonCameraSim cameraSim, double timeSeconds) {
178        var robotToCamera = getRobotToCamera(cameraSim, timeSeconds);
179        return robotToCamera.map(transform3d -> getRobotPose(timeSeconds).plus(transform3d));
180    }
181
182    /**
183     * Adjust a camera's position relative to the robot. Use this if your camera is on a gimbal or
184     * turret or some other mobile platform.
185     *
186     * @param cameraSim The simulated camera to change the relative position of
187     * @param robotToCamera New transform from the robot to the camera
188     * @return If the cameraSim was valid and transform was adjusted
189     */
190    public boolean adjustCamera(PhotonCameraSim cameraSim, Transform3d robotToCamera) {
191        var trfBuffer = camTrfMap.get(cameraSim);
192        if (trfBuffer == null) return false;
193        trfBuffer.addSample(Timer.getFPGATimestamp(), new Pose3d().plus(robotToCamera));
194        return true;
195    }
196
197    /** Reset the previous transforms for all cameras to their current transform. */
198    public void resetCameraTransforms() {
199        for (var cam : camTrfMap.keySet()) resetCameraTransforms(cam);
200    }
201
202    /**
203     * Reset the transform history for this camera to just the current transform.
204     *
205     * @return If the cameraSim was valid and transforms were reset
206     */
207    public boolean resetCameraTransforms(PhotonCameraSim cameraSim) {
208        double now = Timer.getFPGATimestamp();
209        var trfBuffer = camTrfMap.get(cameraSim);
210        if (trfBuffer == null) return false;
211        var lastTrf = new Transform3d(new Pose3d(), trfBuffer.getSample(now).orElse(new Pose3d()));
212        trfBuffer.clear();
213        adjustCamera(cameraSim, lastTrf);
214        return true;
215    }
216
217    public Set<VisionTargetSim> getVisionTargets() {
218        var all = new HashSet<VisionTargetSim>();
219        for (var entry : targetSets.entrySet()) {
220            all.addAll(entry.getValue());
221        }
222        return all;
223    }
224
225    public Set<VisionTargetSim> getVisionTargets(String type) {
226        return targetSets.get(type);
227    }
228
229    /**
230     * Adds targets on the field which your vision system is designed to detect. The {@link
231     * PhotonCamera}s simulated from this system will report the location of the camera relative to
232     * the subset of these targets which are visible from the given camera position.
233     *
234     * <p>By default these are added under the type "targets".
235     *
236     * @param targets Targets to add to the simulated field
237     */
238    public void addVisionTargets(VisionTargetSim... targets) {
239        addVisionTargets("targets", targets);
240    }
241
242    /**
243     * Adds targets on the field which your vision system is designed to detect. The {@link
244     * PhotonCamera}s simulated from this system will report the location of the camera relative to
245     * the subset of these targets which are visible from the given camera position.
246     *
247     * <p>The AprilTags from this layout will be added as vision targets under the type "apriltag".
248     * The poses added preserve the tag layout's current alliance origin. If the tag layout's alliance
249     * origin is changed, these added tags will have to be cleared and re-added.
250     *
251     * @param tagLayout The field tag layout to get Apriltag poses and IDs from
252     */
253    public void addAprilTags(AprilTagFieldLayout tagLayout) {
254        for (AprilTag tag : tagLayout.getTags()) {
255            addVisionTargets(
256                    "apriltag",
257                    new VisionTargetSim(
258                            tagLayout.getTagPose(tag.ID).get(), // preserve alliance rotation
259                            TargetModel.kAprilTag36h11,
260                            tag.ID));
261        }
262    }
263
264    /**
265     * Adds targets on the field which your vision system is designed to detect. The {@link
266     * PhotonCamera}s simulated from this system will report the location of the camera relative to
267     * the subset of these targets which are visible from the given camera position.
268     *
269     * @param type Type of target (e.g. "cargo").
270     * @param targets Targets to add to the simulated field
271     */
272    public void addVisionTargets(String type, VisionTargetSim... targets) {
273        targetSets.computeIfAbsent(type, k -> new HashSet<>());
274        for (var tgt : targets) {
275            targetSets.get(type).add(tgt);
276        }
277    }
278
279    public void clearVisionTargets() {
280        targetSets.clear();
281    }
282
283    public void clearAprilTags() {
284        removeVisionTargets("apriltag");
285    }
286
287    public Set<VisionTargetSim> removeVisionTargets(String type) {
288        return targetSets.remove(type);
289    }
290
291    public Set<VisionTargetSim> removeVisionTargets(VisionTargetSim... targets) {
292        var removeList = List.of(targets);
293        var removedSet = new HashSet<VisionTargetSim>();
294        for (var entry : targetSets.entrySet()) {
295            entry
296                    .getValue()
297                    .removeIf(
298                            t -> {
299                                if (removeList.contains(t)) {
300                                    removedSet.add(t);
301                                    return true;
302                                } else return false;
303                            });
304        }
305        return removedSet;
306    }
307
308    /** Get the latest robot pose in meters saved by the vision system. */
309    public Pose3d getRobotPose() {
310        return getRobotPose(Timer.getFPGATimestamp());
311    }
312
313    /**
314     * Get the robot pose in meters saved by the vision system at this timestamp.
315     *
316     * @param timestamp Timestamp of the desired robot pose
317     */
318    public Pose3d getRobotPose(double timestamp) {
319        return robotPoseBuffer.getSample(timestamp).orElse(new Pose3d());
320    }
321
322    /** Clears all previous robot poses and sets robotPose at current time. */
323    public void resetRobotPose(Pose2d robotPose) {
324        resetRobotPose(new Pose3d(robotPose));
325    }
326
327    /** Clears all previous robot poses and sets robotPose at current time. */
328    public void resetRobotPose(Pose3d robotPose) {
329        robotPoseBuffer.clear();
330        robotPoseBuffer.addSample(Timer.getFPGATimestamp(), robotPose);
331    }
332
333    public Field2d getDebugField() {
334        return dbgField;
335    }
336
337    /**
338     * Periodic update. Ensure this is called repeatedly-- camera performance is used to automatically
339     * determine if a new frame should be submitted.
340     *
341     * @param robotPoseMeters The simulated robot pose in meters
342     */
343    public void update(Pose2d robotPoseMeters) {
344        update(new Pose3d(robotPoseMeters));
345    }
346
347    /**
348     * Periodic update. Ensure this is called repeatedly-- camera performance is used to automatically
349     * determine if a new frame should be submitted.
350     *
351     * @param robotPoseMeters The simulated robot pose in meters
352     */
353    public void update(Pose3d robotPoseMeters) {
354        var targetTypes = targetSets.entrySet();
355        // update vision targets on field
356        targetTypes.forEach(
357                entry ->
358                        dbgField
359                                .getObject(entry.getKey())
360                                .setPoses(
361                                        entry.getValue().stream()
362                                                .map(t -> t.getPose().toPose2d())
363                                                .collect(Collectors.toList())));
364
365        if (robotPoseMeters == null) return;
366
367        // save "real" robot poses over time
368        double now = Timer.getFPGATimestamp();
369        robotPoseBuffer.addSample(now, robotPoseMeters);
370        dbgField.setRobotPose(robotPoseMeters.toPose2d());
371
372        var allTargets = new ArrayList<VisionTargetSim>();
373        targetTypes.forEach((entry) -> allTargets.addAll(entry.getValue()));
374        var visTgtPoses2d = new ArrayList<Pose2d>();
375        var cameraPoses2d = new ArrayList<Pose2d>();
376        boolean processed = false;
377        // process each camera
378        for (var camSim : camSimMap.values()) {
379            // check if this camera is ready to process and get latency
380            var optTimestamp = camSim.consumeNextEntryTime();
381            if (optTimestamp.isEmpty()) continue;
382            else processed = true;
383            // when this result "was" read by NT
384            long timestampNT = optTimestamp.get();
385            // this result's processing latency in milliseconds
386            double latencyMillis = camSim.prop.estLatencyMs();
387            // the image capture timestamp in seconds of this result
388            double timestampCapture = timestampNT / 1e6 - latencyMillis / 1e3;
389
390            // use camera pose from the image capture timestamp
391            Pose3d lateRobotPose = getRobotPose(timestampCapture);
392            Pose3d lateCameraPose = lateRobotPose.plus(getRobotToCamera(camSim, timestampCapture).get());
393            cameraPoses2d.add(lateCameraPose.toPose2d());
394
395            // process a PhotonPipelineResult with visible targets
396            var camResult = camSim.process(latencyMillis, lateCameraPose, allTargets);
397            // publish this info to NT at estimated timestamp of receive
398            camSim.submitProcessedFrame(camResult, timestampNT);
399            // display debug results
400            for (var target : camResult.getTargets()) {
401                var trf = target.getBestCameraToTarget();
402                if (trf.equals(kEmptyTrf)) continue;
403                visTgtPoses2d.add(lateCameraPose.transformBy(trf).toPose2d());
404            }
405        }
406        if (processed) dbgField.getObject("visibleTargetPoses").setPoses(visTgtPoses2d);
407        if (!cameraPoses2d.isEmpty()) dbgField.getObject("cameras").setPoses(cameraPoses2d);
408    }
409}