PhotonVision C++ v2026.2.2
Loading...
Searching...
No Matches
VisionSystemSim.h
Go to the documentation of this file.
1/*
2 * MIT License
3 *
4 * Copyright (c) PhotonVision
5 *
6 * Permission is hereby granted, free of charge, to any person obtaining a copy
7 * of this software and associated documentation files (the "Software"), to deal
8 * in the Software without restriction, including without limitation the rights
9 * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
10 * copies of the Software, and to permit persons to whom the Software is
11 * furnished to do so, subject to the following conditions:
12 *
13 * The above copyright notice and this permission notice shall be included in
14 * all copies or substantial portions of the Software.
15 *
16 * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
17 * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
18 * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
19 * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
20 * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
21 * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
22 * SOFTWARE.
23 */
24
25#pragma once
26
27#include <string>
28#include <unordered_map>
29#include <utility>
30#include <vector>
31
32#include <frc/Timer.h>
33#include <frc/interpolation/TimeInterpolatableBuffer.h>
34#include <frc/smartdashboard/Field2d.h>
35#include <frc/smartdashboard/FieldObject2d.h>
36#include <frc/smartdashboard/SmartDashboard.h>
37
39
40namespace photon {
41/**
42 * A simulated vision system involving a camera(s) and coprocessor(s) mounted on
43 * a mobile robot running PhotonVision, detecting targets placed on the field.
44 * VisionTargetSims added to this class will be detected by the PhotonCameraSim
45 * added to this class. This class should be updated periodically with the
46 * robot's current pose in order to publish the simulated camera target info.
47 */
49 public:
50 /**
51 * A simulated vision system involving a camera(s) and coprocessor(s) mounted
52 * on a mobile robot running PhotonVision, detecting targets placed on the
53 * field. VisionTargetSims added to this class will be detected by the
54 * PhotonCameraSims added to this class. This class should be updated
55 * periodically with the robot's current pose in order to publish the
56 * simulated camera target info.
57 *
58 * @param visionSystemName The specific identifier for this vision system in
59 * NetworkTables.
60 */
61 explicit VisionSystemSim(std::string visionSystemName) {
62 std::string tableName = "VisionSystemSim-" + visionSystemName;
63 frc::SmartDashboard::PutData(tableName + "/Sim Field", &dbgField);
64 }
65
66 /** Get one of the simulated cameras. */
67 std::optional<PhotonCameraSim*> GetCameraSim(std::string name) {
68 auto it = camSimMap.find(name);
69 if (it != camSimMap.end()) {
70 return std::make_optional(it->second);
71 } else {
72 return std::nullopt;
73 }
74 }
75
76 /** Get all the simulated cameras. */
77 std::vector<PhotonCameraSim*> GetCameraSims() {
78 std::vector<PhotonCameraSim*> retVal;
79 for (auto const& cam : camSimMap) {
80 retVal.emplace_back(cam.second);
81 }
82 return retVal;
83 }
84
85 /**
86 * Adds a simulated camera to this vision system with a specified
87 * robot-to-camera transformation. The vision targets registered with this
88 * vision system simulation will be observed by the simulated PhotonCamera.
89 *
90 * @param cameraSim The camera simulation
91 * @param robotToCamera The transform from the robot pose to the camera pose
92 */
93 void AddCamera(PhotonCameraSim* cameraSim,
94 const frc::Transform3d& robotToCamera) {
95 auto found =
96 camSimMap.find(std::string{cameraSim->GetCamera()->GetCameraName()});
97 if (found == camSimMap.end()) {
98 camSimMap[std::string{cameraSim->GetCamera()->GetCameraName()}] =
99 cameraSim;
100 camTrfMap.insert(std::make_pair(
101 std::move(cameraSim),
102 frc::TimeInterpolatableBuffer<frc::Pose3d>{bufferLength}));
103 camTrfMap.at(cameraSim).AddSample(frc::Timer::GetFPGATimestamp(),
104 frc::Pose3d{} + robotToCamera);
105 }
106 }
107
108 /** Remove all simulated cameras from this vision system. */
110 camSimMap.clear();
111 camTrfMap.clear();
112 }
113
114 /**
115 * Remove a simulated camera from this vision system.
116 *
117 * @param cameraSim The camera to remove
118 * @return If the camera was present and removed
119 */
120 bool RemoveCamera(PhotonCameraSim* cameraSim) {
121 int numOfElementsRemoved =
122 camSimMap.erase(std::string{cameraSim->GetCamera()->GetCameraName()});
123 if (numOfElementsRemoved == 1) {
124 return true;
125 } else {
126 return false;
127 }
128 }
129
130 /**
131 * Get a simulated camera's position relative to the robot. If the requested
132 * camera is invalid, an empty optional is returned.
133 *
134 * @param cameraSim The specific camera to get the robot-to-camera transform
135 * of
136 * @return The transform of this camera, or an empty optional if it is invalid
137 */
138 std::optional<frc::Transform3d> GetRobotToCamera(PhotonCameraSim* cameraSim) {
139 return GetRobotToCamera(cameraSim, frc::Timer::GetFPGATimestamp());
140 }
141
142 /**
143 * Get a simulated camera's position relative to the robot. If the requested
144 * camera is invalid, an empty optional is returned.
145 *
146 * @param cameraSim The specific camera to get the robot-to-camera transform
147 * of
148 * @param time Timestamp of when the transform should be observed
149 * @return The transform of this camera, or an empty optional if it is invalid
150 */
151 std::optional<frc::Transform3d> GetRobotToCamera(PhotonCameraSim* cameraSim,
152 units::second_t time) {
153 if (camTrfMap.find(cameraSim) != camTrfMap.end()) {
154 frc::TimeInterpolatableBuffer<frc::Pose3d> trfBuffer =
155 camTrfMap.at(cameraSim);
156 std::optional<frc::Pose3d> sample = trfBuffer.Sample(time);
157 if (!sample) {
158 return std::nullopt;
159 } else {
160 return std::make_optional(
161 frc::Transform3d{frc::Pose3d{}, sample.value_or(frc::Pose3d{})});
162 }
163 } else {
164 return std::nullopt;
165 }
166 }
167
168 /**
169 * Get a simulated camera's position on the field. If the requested camera is
170 * invalid, an empty optional is returned.
171 *
172 * @param cameraSim The specific camera to get the field pose of
173 * @return The pose of this camera, or an empty optional if it is invalid
174 */
175 std::optional<frc::Pose3d> GetCameraPose(PhotonCameraSim* cameraSim) {
176 return GetCameraPose(cameraSim, frc::Timer::GetFPGATimestamp());
177 }
178
179 /**
180 * Get a simulated camera's position on the field. If the requested camera is
181 * invalid, an empty optional is returned.
182 *
183 * @param cameraSim The specific camera to get the field pose of
184 * @param time Timestamp of when the pose should be observed
185 * @return The pose of this camera, or an empty optional if it is invalid
186 */
187 std::optional<frc::Pose3d> GetCameraPose(PhotonCameraSim* cameraSim,
188 units::second_t time) {
189 auto robotToCamera = GetRobotToCamera(cameraSim, time);
190 if (!robotToCamera) {
191 return std::nullopt;
192 } else {
193 return std::make_optional(GetRobotPose(time) + robotToCamera.value());
194 }
195 }
196
197 /**
198 * Adjust a camera's position relative to the robot. Use this if your camera
199 * is on a gimbal or turret or some other mobile platform.
200 *
201 * @param cameraSim The simulated camera to change the relative position of
202 * @param robotToCamera New transform from the robot to the camera
203 * @return If the cameraSim was valid and transform was adjusted
204 */
206 const frc::Transform3d& robotToCamera) {
207 if (camTrfMap.find(cameraSim) != camTrfMap.end()) {
208 camTrfMap.at(cameraSim).AddSample(frc::Timer::GetFPGATimestamp(),
209 frc::Pose3d{} + robotToCamera);
210 return true;
211 } else {
212 return false;
213 }
214 }
215
216 /** Reset the previous transforms for all cameras to their current transform.
217 */
219 for (const auto& pair : camTrfMap) {
220 ResetCameraTransforms(pair.first);
221 }
222 }
223
224 /**
225 * Reset the transform history for this camera to just the current transform.
226 *
227 * @param cameraSim The camera to reset
228 * @return If the cameraSim was valid and transforms were reset
229 */
231 units::second_t now = frc::Timer::GetFPGATimestamp();
232 if (camTrfMap.find(cameraSim) != camTrfMap.end()) {
233 auto trfBuffer = camTrfMap.at(cameraSim);
234 frc::Transform3d lastTrf{frc::Pose3d{},
235 trfBuffer.Sample(now).value_or(frc::Pose3d{})};
236 trfBuffer.Clear();
237 AdjustCamera(cameraSim, lastTrf);
238 return true;
239 } else {
240 return false;
241 }
242 }
243
244 /**
245 * Returns all the vision targets on the field.
246 *
247 * @return The vision targets
248 */
249 std::vector<VisionTargetSim> GetVisionTargets() {
250 std::vector<VisionTargetSim> all{};
251 for (const auto& entry : targetSets) {
252 for (const auto& target : entry.second) {
253 all.emplace_back(target);
254 }
255 }
256 return all;
257 }
258
259 /**
260 * Returns all the vision targets of the specified type on the field.
261 *
262 * @param type The type of vision targets to return
263 * @return The vision targets
264 */
265 std::vector<VisionTargetSim> GetVisionTargets(std::string type) {
266 return targetSets[type];
267 }
268
269 /**
270 * Adds targets on the field which your vision system is designed to detect.
271 * The PhotonCameras simulated from this system will report the location of
272 * the camera relative to the subset of these targets which are visible from
273 * the given camera position.
274 *
275 * By default these are added under the type "targets".
276 *
277 * @param targets Targets to add to the simulated field
278 */
279 void AddVisionTargets(const std::vector<VisionTargetSim>& targets) {
280 AddVisionTargets("targets", targets);
281 }
282
283 /**
284 * Adds targets on the field which your vision system is designed to detect.
285 * The PhotonCameras simulated from this system will report the location of
286 * the camera relative to the subset of these targets which are visible from
287 * the given camera position.
288 *
289 * @param type Type of target (e.g. "cargo").
290 * @param targets Targets to add to the simulated field
291 */
292 void AddVisionTargets(std::string type,
293 const std::vector<VisionTargetSim>& targets) {
294 if (!targetSets.contains(type)) {
295 targetSets[type] = std::vector<VisionTargetSim>{};
296 }
297 for (const auto& tgt : targets) {
298 targetSets[type].emplace_back(tgt);
299 }
300 }
301
302 /**
303 * Adds targets on the field which your vision system is designed to detect.
304 * The PhotonCameras simulated from this system will report the location of
305 * the camera relative to the subset of these targets which are visible from
306 * the given camera position.
307 *
308 * The AprilTags from this layout will be added as vision targets under the
309 * type "apriltag". The poses added preserve the tag layout's current alliance
310 * origin. If the tag layout's alliance origin is changed, these added tags
311 * will have to be cleared and re-added.
312 *
313 * @param layout The field tag layout to get Apriltag poses and IDs from
314 */
315 void AddAprilTags(const frc::AprilTagFieldLayout& layout) {
316 std::vector<VisionTargetSim> targets;
317 for (const frc::AprilTag& tag : layout.GetTags()) {
318 targets.emplace_back(VisionTargetSim{layout.GetTagPose(tag.ID).value(),
319 photon::kAprilTag36h11, tag.ID});
320 }
321 AddVisionTargets("apriltag", targets);
322 }
323 /** Removes every VisionTargetSim from the simulated field. */
324 void ClearVisionTargets() { targetSets.clear(); }
325 /** Removes all simulated AprilTag targets from the simulated field. */
326 void ClearAprilTags() { RemoveVisionTargets("apriltag"); }
327
328 /**
329 * Removes every VisionTargetSim of the specified type from the simulated
330 * field.
331 *
332 * @param type Type of target (e.g. "cargo"). Same as the type passed into
333 * #addVisionTargets(String, VisionTargetSim...)
334 * @return The removed targets, or null if no targets of the specified type
335 * exist
336 */
337 void RemoveVisionTargets(std::string type) { targetSets.erase(type); }
338
339 /**
340 * Removes the specified VisionTargetSims from the simulated field.
341 *
342 * @param targets The targets to remove
343 * @return The targets that were actually removed
344 */
345 std::vector<VisionTargetSim> RemoveVisionTargets(
346 const std::vector<VisionTargetSim>& targets) {
347 std::vector<VisionTargetSim> removedList;
348 for (auto& entry : targetSets) {
349 for (auto target : entry.second) {
350 auto it = std::find(targets.begin(), targets.end(), target);
351 if (it != targets.end()) {
352 removedList.emplace_back(target);
353 entry.second.erase(it);
354 }
355 }
356 }
357 return removedList;
358 }
359
360 /**
361 * Get the latest robot pose in meters saved by the vision system.
362 *
363 * @return The latest robot pose
364 */
365 frc::Pose3d GetRobotPose() {
366 return GetRobotPose(frc::Timer::GetFPGATimestamp());
367 }
368
369 /**
370 * Get the robot pose in meters saved by the vision system at this timestamp.
371 *
372 * @param timestamp Timestamp of the desired robot pose
373 * @return The robot pose
374 */
375 frc::Pose3d GetRobotPose(units::second_t timestamp) {
376 return robotPoseBuffer.Sample(timestamp).value_or(frc::Pose3d{});
377 }
378
379 /**
380 * Clears all previous robot poses and sets robotPose at current time.
381 *
382 * @param robotPose The robot pose
383 */
384 void ResetRobotPose(const frc::Pose2d& robotPose) {
385 ResetRobotPose(frc::Pose3d{robotPose});
386 }
387
388 /**
389 * Clears all previous robot poses and sets robotPose at current time.
390 *
391 * @param robotPose The robot pose
392 */
393 void ResetRobotPose(const frc::Pose3d& robotPose) {
394 robotPoseBuffer.Clear();
395 robotPoseBuffer.AddSample(frc::Timer::GetFPGATimestamp(), robotPose);
396 }
397 frc::Field2d& GetDebugField() { return dbgField; }
398
399 /**
400 * Periodic update. Ensure this is called repeatedly-- camera performance is
401 * used to automatically determine if a new frame should be submitted.
402 *
403 * @param robotPoseMeters The simulated robot pose in meters
404 */
405 void Update(const frc::Pose2d& robotPose) { Update(frc::Pose3d{robotPose}); }
406
407 /**
408 * Periodic update. Ensure this is called repeatedly-- camera performance is
409 * used to automatically determine if a new frame should be submitted.
410 *
411 * @param robotPoseMeters The simulated robot pose in meters
412 */
413 void Update(const frc::Pose3d& robotPose) {
414 for (auto& set : targetSets) {
415 std::vector<frc::Pose2d> posesToAdd{};
416 for (auto& target : set.second) {
417 posesToAdd.emplace_back(target.GetPose().ToPose2d());
418 }
419 dbgField.GetObject(set.first)->SetPoses(posesToAdd);
420 }
421
422 units::second_t now = frc::Timer::GetFPGATimestamp();
423 robotPoseBuffer.AddSample(now, robotPose);
424 dbgField.SetRobotPose(robotPose.ToPose2d());
425
426 std::vector<VisionTargetSim> allTargets{};
427 for (const auto& set : targetSets) {
428 for (const auto& target : set.second) {
429 allTargets.emplace_back(target);
430 }
431 }
432
433 std::vector<frc::Pose2d> visTgtPoses2d{};
434 std::vector<frc::Pose2d> cameraPoses2d{};
435 bool processed{false};
436 for (const auto& entry : camSimMap) {
437 auto camSim = entry.second;
438 auto optTimestamp = camSim->ConsumeNextEntryTime();
439 if (!optTimestamp) {
440 continue;
441 } else {
442 processed = true;
443 }
444 uint64_t timestampNt = optTimestamp.value();
445 units::second_t latency = camSim->prop.EstLatency();
446 units::second_t timestampCapture =
447 units::microsecond_t{static_cast<double>(timestampNt)} - latency;
448
449 frc::Pose3d lateRobotPose = GetRobotPose(timestampCapture);
450 frc::Pose3d lateCameraPose =
451 lateRobotPose + GetRobotToCamera(camSim, timestampCapture).value();
452 cameraPoses2d.push_back(lateCameraPose.ToPose2d());
453
454 auto camResult = camSim->Process(latency, lateCameraPose, allTargets);
455 camSim->SubmitProcessedFrame(camResult, timestampNt);
456 for (const auto& target : camResult.GetTargets()) {
457 auto trf = target.GetBestCameraToTarget();
458 if (trf == kEmptyTrf) {
459 continue;
460 }
461 visTgtPoses2d.push_back(lateCameraPose.TransformBy(trf).ToPose2d());
462 }
463 }
464 if (processed) {
465 dbgField.GetObject("visibleTargetPoses")->SetPoses(visTgtPoses2d);
466 }
467 if (cameraPoses2d.size() != 0) {
468 dbgField.GetObject("cameras")->SetPoses(cameraPoses2d);
469 }
470 }
471
472 private:
473 std::unordered_map<std::string, PhotonCameraSim*> camSimMap{};
474 static constexpr units::second_t bufferLength{1.5_s};
475 std::unordered_map<PhotonCameraSim*,
476 frc::TimeInterpolatableBuffer<frc::Pose3d>>
477 camTrfMap;
478 frc::TimeInterpolatableBuffer<frc::Pose3d> robotPoseBuffer{bufferLength};
479 std::unordered_map<std::string, std::vector<VisionTargetSim>> targetSets{};
480 frc::Field2d dbgField{};
481 const frc::Transform3d kEmptyTrf{};
482};
483} // namespace photon
const std::string_view GetCameraName() const
Returns the name of the camera.
Definition PhotonCameraSim.h:49
PhotonCamera * GetCamera()
Returns the camera being simulated.
Definition PhotonCameraSim.h:105
A simulated vision system involving a camera(s) and coprocessor(s) mounted on a mobile robot running ...
Definition VisionSystemSim.h:48
void ResetRobotPose(const frc::Pose2d &robotPose)
Clears all previous robot poses and sets robotPose at current time.
Definition VisionSystemSim.h:384
std::optional< PhotonCameraSim * > GetCameraSim(std::string name)
Get one of the simulated cameras.
Definition VisionSystemSim.h:67
std::optional< frc::Transform3d > GetRobotToCamera(PhotonCameraSim *cameraSim, units::second_t time)
Get a simulated camera's position relative to the robot.
Definition VisionSystemSim.h:151
std::optional< frc::Pose3d > GetCameraPose(PhotonCameraSim *cameraSim)
Get a simulated camera's position on the field.
Definition VisionSystemSim.h:175
void ResetRobotPose(const frc::Pose3d &robotPose)
Clears all previous robot poses and sets robotPose at current time.
Definition VisionSystemSim.h:393
std::vector< VisionTargetSim > RemoveVisionTargets(const std::vector< VisionTargetSim > &targets)
Removes the specified VisionTargetSims from the simulated field.
Definition VisionSystemSim.h:345
void AddAprilTags(const frc::AprilTagFieldLayout &layout)
Adds targets on the field which your vision system is designed to detect.
Definition VisionSystemSim.h:315
void Update(const frc::Pose3d &robotPose)
Periodic update.
Definition VisionSystemSim.h:413
void AddVisionTargets(std::string type, const std::vector< VisionTargetSim > &targets)
Adds targets on the field which your vision system is designed to detect.
Definition VisionSystemSim.h:292
void ResetCameraTransforms()
Reset the previous transforms for all cameras to their current transform.
Definition VisionSystemSim.h:218
void RemoveVisionTargets(std::string type)
Removes every VisionTargetSim of the specified type from the simulated field.
Definition VisionSystemSim.h:337
bool ResetCameraTransforms(PhotonCameraSim *cameraSim)
Reset the transform history for this camera to just the current transform.
Definition VisionSystemSim.h:230
frc::Field2d & GetDebugField()
Definition VisionSystemSim.h:397
void Update(const frc::Pose2d &robotPose)
Periodic update.
Definition VisionSystemSim.h:405
bool AdjustCamera(PhotonCameraSim *cameraSim, const frc::Transform3d &robotToCamera)
Adjust a camera's position relative to the robot.
Definition VisionSystemSim.h:205
void AddCamera(PhotonCameraSim *cameraSim, const frc::Transform3d &robotToCamera)
Adds a simulated camera to this vision system with a specified robot-to-camera transformation.
Definition VisionSystemSim.h:93
std::vector< PhotonCameraSim * > GetCameraSims()
Get all the simulated cameras.
Definition VisionSystemSim.h:77
VisionSystemSim(std::string visionSystemName)
A simulated vision system involving a camera(s) and coprocessor(s) mounted on a mobile robot running ...
Definition VisionSystemSim.h:61
void ClearVisionTargets()
Removes every VisionTargetSim from the simulated field.
Definition VisionSystemSim.h:324
std::vector< VisionTargetSim > GetVisionTargets()
Returns all the vision targets on the field.
Definition VisionSystemSim.h:249
void AddVisionTargets(const std::vector< VisionTargetSim > &targets)
Adds targets on the field which your vision system is designed to detect.
Definition VisionSystemSim.h:279
std::vector< VisionTargetSim > GetVisionTargets(std::string type)
Returns all the vision targets of the specified type on the field.
Definition VisionSystemSim.h:265
frc::Pose3d GetRobotPose()
Get the latest robot pose in meters saved by the vision system.
Definition VisionSystemSim.h:365
void ClearAprilTags()
Removes all simulated AprilTag targets from the simulated field.
Definition VisionSystemSim.h:326
void ClearCameras()
Remove all simulated cameras from this vision system.
Definition VisionSystemSim.h:109
frc::Pose3d GetRobotPose(units::second_t timestamp)
Get the robot pose in meters saved by the vision system at this timestamp.
Definition VisionSystemSim.h:375
std::optional< frc::Pose3d > GetCameraPose(PhotonCameraSim *cameraSim, units::second_t time)
Get a simulated camera's position on the field.
Definition VisionSystemSim.h:187
std::optional< frc::Transform3d > GetRobotToCamera(PhotonCameraSim *cameraSim)
Get a simulated camera's position relative to the robot.
Definition VisionSystemSim.h:138
bool RemoveCamera(PhotonCameraSim *cameraSim)
Remove a simulated camera from this vision system.
Definition VisionSystemSim.h:120
Definition VisionTargetSim.h:34
Definition TargetModel.h:27
static const TargetModel kAprilTag36h11
Definition TargetModel.h:114