28#include <unordered_map>
33#include <frc/interpolation/TimeInterpolatableBuffer.h>
34#include <frc/smartdashboard/Field2d.h>
35#include <frc/smartdashboard/FieldObject2d.h>
36#include <frc/smartdashboard/SmartDashboard.h>
62 std::string tableName =
"VisionSystemSim-" + visionSystemName;
63 frc::SmartDashboard::PutData(tableName +
"/Sim Field", &dbgField);
68 auto it = camSimMap.find(name);
69 if (it != camSimMap.end()) {
70 return std::make_optional(it->second);
78 std::vector<PhotonCameraSim*> retVal;
79 for (
auto const& cam : camSimMap) {
80 retVal.emplace_back(cam.second);
94 const frc::Transform3d& robotToCamera) {
97 if (found == camSimMap.end()) {
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);
121 int numOfElementsRemoved =
123 if (numOfElementsRemoved == 1) {
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);
160 return std::make_optional(
161 frc::Transform3d{frc::Pose3d{}, sample.value_or(frc::Pose3d{})});
176 return GetCameraPose(cameraSim, frc::Timer::GetFPGATimestamp());
188 units::second_t time) {
190 if (!robotToCamera) {
193 return std::make_optional(
GetRobotPose(time) + robotToCamera.value());
206 const frc::Transform3d& robotToCamera) {
207 if (camTrfMap.find(cameraSim) != camTrfMap.end()) {
208 camTrfMap.at(cameraSim).AddSample(frc::Timer::GetFPGATimestamp(),
209 frc::Pose3d{} + robotToCamera);
219 for (
const auto& pair : camTrfMap) {
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{})};
250 std::vector<VisionTargetSim> all{};
251 for (
const auto& entry : targetSets) {
252 for (
const auto& target : entry.second) {
253 all.emplace_back(target);
266 return targetSets[type];
293 const std::vector<VisionTargetSim>& targets) {
294 if (!targetSets.contains(type)) {
295 targetSets[type] = std::vector<VisionTargetSim>{};
297 for (
const auto& tgt : targets) {
298 targetSets[type].emplace_back(tgt);
316 std::vector<VisionTargetSim> targets;
317 for (
const frc::AprilTag& tag : layout.GetTags()) {
318 targets.emplace_back(
VisionTargetSim{layout.GetTagPose(tag.ID).value(),
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);
376 return robotPoseBuffer.Sample(timestamp).value_or(frc::Pose3d{});
394 robotPoseBuffer.Clear();
395 robotPoseBuffer.AddSample(frc::Timer::GetFPGATimestamp(), robotPose);
405 void Update(
const frc::Pose2d& robotPose) {
Update(frc::Pose3d{robotPose}); }
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());
419 dbgField.GetObject(set.first)->SetPoses(posesToAdd);
422 units::second_t now = frc::Timer::GetFPGATimestamp();
423 robotPoseBuffer.AddSample(now, robotPose);
424 dbgField.SetRobotPose(robotPose.ToPose2d());
426 std::vector<VisionTargetSim> allTargets{};
427 for (
const auto& set : targetSets) {
428 for (
const auto& target : set.second) {
429 allTargets.emplace_back(target);
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();
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;
449 frc::Pose3d lateRobotPose =
GetRobotPose(timestampCapture);
450 frc::Pose3d lateCameraPose =
452 cameraPoses2d.push_back(lateCameraPose.ToPose2d());
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) {
461 visTgtPoses2d.push_back(lateCameraPose.TransformBy(trf).ToPose2d());
465 dbgField.GetObject(
"visibleTargetPoses")->SetPoses(visTgtPoses2d);
467 if (cameraPoses2d.size() != 0) {
468 dbgField.GetObject(
"cameras")->SetPoses(cameraPoses2d);
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>>
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{};
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