PhotonVision C++ v2026.2.2
Loading...
Searching...
No Matches
photon::VisionSystemSim Class Reference

A simulated vision system involving a camera(s) and coprocessor(s) mounted on a mobile robot running PhotonVision, detecting targets placed on the field. More...

#include <photon/simulation/VisionSystemSim.h>

Public Member Functions

 VisionSystemSim (std::string visionSystemName)
 A simulated vision system involving a camera(s) and coprocessor(s) mounted on a mobile robot running PhotonVision, detecting targets placed on the field.
 
std::optional< PhotonCameraSim * > GetCameraSim (std::string name)
 Get one of the simulated cameras.
 
std::vector< PhotonCameraSim * > GetCameraSims ()
 Get all the simulated cameras.
 
void AddCamera (PhotonCameraSim *cameraSim, const frc::Transform3d &robotToCamera)
 Adds a simulated camera to this vision system with a specified robot-to-camera transformation.
 
void ClearCameras ()
 Remove all simulated cameras from this vision system.
 
bool RemoveCamera (PhotonCameraSim *cameraSim)
 Remove a simulated camera from this vision system.
 
std::optional< frc::Transform3d > GetRobotToCamera (PhotonCameraSim *cameraSim)
 Get a simulated camera's position relative to the robot.
 
std::optional< frc::Transform3d > GetRobotToCamera (PhotonCameraSim *cameraSim, units::second_t time)
 Get a simulated camera's position relative to the robot.
 
std::optional< frc::Pose3d > GetCameraPose (PhotonCameraSim *cameraSim)
 Get a simulated camera's position on the field.
 
std::optional< frc::Pose3d > GetCameraPose (PhotonCameraSim *cameraSim, units::second_t time)
 Get a simulated camera's position on the field.
 
bool AdjustCamera (PhotonCameraSim *cameraSim, const frc::Transform3d &robotToCamera)
 Adjust a camera's position relative to the robot.
 
void ResetCameraTransforms ()
 Reset the previous transforms for all cameras to their current transform.
 
bool ResetCameraTransforms (PhotonCameraSim *cameraSim)
 Reset the transform history for this camera to just the current transform.
 
std::vector< VisionTargetSimGetVisionTargets ()
 Returns all the vision targets on the field.
 
std::vector< VisionTargetSimGetVisionTargets (std::string type)
 Returns all the vision targets of the specified type on the field.
 
void AddVisionTargets (const std::vector< VisionTargetSim > &targets)
 Adds targets on the field which your vision system is designed to detect.
 
void AddVisionTargets (std::string type, const std::vector< VisionTargetSim > &targets)
 Adds targets on the field which your vision system is designed to detect.
 
void AddAprilTags (const frc::AprilTagFieldLayout &layout)
 Adds targets on the field which your vision system is designed to detect.
 
void ClearVisionTargets ()
 Removes every VisionTargetSim from the simulated field.
 
void ClearAprilTags ()
 Removes all simulated AprilTag targets from the simulated field.
 
void RemoveVisionTargets (std::string type)
 Removes every VisionTargetSim of the specified type from the simulated field.
 
std::vector< VisionTargetSimRemoveVisionTargets (const std::vector< VisionTargetSim > &targets)
 Removes the specified VisionTargetSims from the simulated field.
 
frc::Pose3d GetRobotPose ()
 Get the latest robot pose in meters saved by the vision system.
 
frc::Pose3d GetRobotPose (units::second_t timestamp)
 Get the robot pose in meters saved by the vision system at this timestamp.
 
void ResetRobotPose (const frc::Pose2d &robotPose)
 Clears all previous robot poses and sets robotPose at current time.
 
void ResetRobotPose (const frc::Pose3d &robotPose)
 Clears all previous robot poses and sets robotPose at current time.
 
frc::Field2d & GetDebugField ()
 
void Update (const frc::Pose2d &robotPose)
 Periodic update.
 
void Update (const frc::Pose3d &robotPose)
 Periodic update.
 

Detailed Description

A simulated vision system involving a camera(s) and coprocessor(s) mounted on a mobile robot running PhotonVision, detecting targets placed on the field.

VisionTargetSims added to this class will be detected by the PhotonCameraSim added to this class. This class should be updated periodically with the robot's current pose in order to publish the simulated camera target info.

Constructor & Destructor Documentation

◆ VisionSystemSim()

photon::VisionSystemSim::VisionSystemSim ( std::string visionSystemName)
inlineexplicit

A simulated vision system involving a camera(s) and coprocessor(s) mounted on a mobile robot running PhotonVision, detecting targets placed on the field.

VisionTargetSims added to this class will be detected by the PhotonCameraSims added to this class. This class should be updated periodically with the robot's current pose in order to publish the simulated camera target info.

Parameters
visionSystemNameThe specific identifier for this vision system in NetworkTables.

Member Function Documentation

◆ AddAprilTags()

void photon::VisionSystemSim::AddAprilTags ( const frc::AprilTagFieldLayout & layout)
inline

Adds targets on the field which your vision system is designed to detect.

The PhotonCameras simulated from this system will report the location of the camera relative to the subset of these targets which are visible from the given camera position.

The AprilTags from this layout will be added as vision targets under the type "apriltag". The poses added preserve the tag layout's current alliance origin. If the tag layout's alliance origin is changed, these added tags will have to be cleared and re-added.

Parameters
layoutThe field tag layout to get Apriltag poses and IDs from

◆ AddCamera()

void photon::VisionSystemSim::AddCamera ( PhotonCameraSim * cameraSim,
const frc::Transform3d & robotToCamera )
inline

Adds a simulated camera to this vision system with a specified robot-to-camera transformation.

The vision targets registered with this vision system simulation will be observed by the simulated PhotonCamera.

Parameters
cameraSimThe camera simulation
robotToCameraThe transform from the robot pose to the camera pose

◆ AddVisionTargets() [1/2]

void photon::VisionSystemSim::AddVisionTargets ( const std::vector< VisionTargetSim > & targets)
inline

Adds targets on the field which your vision system is designed to detect.

The PhotonCameras simulated from this system will report the location of the camera relative to the subset of these targets which are visible from the given camera position.

By default these are added under the type "targets".

Parameters
targetsTargets to add to the simulated field

◆ AddVisionTargets() [2/2]

void photon::VisionSystemSim::AddVisionTargets ( std::string type,
const std::vector< VisionTargetSim > & targets )
inline

Adds targets on the field which your vision system is designed to detect.

The PhotonCameras simulated from this system will report the location of the camera relative to the subset of these targets which are visible from the given camera position.

Parameters
typeType of target (e.g. "cargo").
targetsTargets to add to the simulated field

◆ AdjustCamera()

bool photon::VisionSystemSim::AdjustCamera ( PhotonCameraSim * cameraSim,
const frc::Transform3d & robotToCamera )
inline

Adjust a camera's position relative to the robot.

Use this if your camera is on a gimbal or turret or some other mobile platform.

Parameters
cameraSimThe simulated camera to change the relative position of
robotToCameraNew transform from the robot to the camera
Returns
If the cameraSim was valid and transform was adjusted

◆ ClearAprilTags()

void photon::VisionSystemSim::ClearAprilTags ( )
inline

Removes all simulated AprilTag targets from the simulated field.

◆ ClearCameras()

void photon::VisionSystemSim::ClearCameras ( )
inline

Remove all simulated cameras from this vision system.

◆ ClearVisionTargets()

void photon::VisionSystemSim::ClearVisionTargets ( )
inline

Removes every VisionTargetSim from the simulated field.

◆ GetCameraPose() [1/2]

std::optional< frc::Pose3d > photon::VisionSystemSim::GetCameraPose ( PhotonCameraSim * cameraSim)
inline

Get a simulated camera's position on the field.

If the requested camera is invalid, an empty optional is returned.

Parameters
cameraSimThe specific camera to get the field pose of
Returns
The pose of this camera, or an empty optional if it is invalid

◆ GetCameraPose() [2/2]

std::optional< frc::Pose3d > photon::VisionSystemSim::GetCameraPose ( PhotonCameraSim * cameraSim,
units::second_t time )
inline

Get a simulated camera's position on the field.

If the requested camera is invalid, an empty optional is returned.

Parameters
cameraSimThe specific camera to get the field pose of
timeTimestamp of when the pose should be observed
Returns
The pose of this camera, or an empty optional if it is invalid

◆ GetCameraSim()

std::optional< PhotonCameraSim * > photon::VisionSystemSim::GetCameraSim ( std::string name)
inline

Get one of the simulated cameras.

◆ GetCameraSims()

std::vector< PhotonCameraSim * > photon::VisionSystemSim::GetCameraSims ( )
inline

Get all the simulated cameras.

◆ GetDebugField()

frc::Field2d & photon::VisionSystemSim::GetDebugField ( )
inline

◆ GetRobotPose() [1/2]

frc::Pose3d photon::VisionSystemSim::GetRobotPose ( )
inline

Get the latest robot pose in meters saved by the vision system.

Returns
The latest robot pose

◆ GetRobotPose() [2/2]

frc::Pose3d photon::VisionSystemSim::GetRobotPose ( units::second_t timestamp)
inline

Get the robot pose in meters saved by the vision system at this timestamp.

Parameters
timestampTimestamp of the desired robot pose
Returns
The robot pose

◆ GetRobotToCamera() [1/2]

std::optional< frc::Transform3d > photon::VisionSystemSim::GetRobotToCamera ( PhotonCameraSim * cameraSim)
inline

Get a simulated camera's position relative to the robot.

If the requested camera is invalid, an empty optional is returned.

Parameters
cameraSimThe specific camera to get the robot-to-camera transform of
Returns
The transform of this camera, or an empty optional if it is invalid

◆ GetRobotToCamera() [2/2]

std::optional< frc::Transform3d > photon::VisionSystemSim::GetRobotToCamera ( PhotonCameraSim * cameraSim,
units::second_t time )
inline

Get a simulated camera's position relative to the robot.

If the requested camera is invalid, an empty optional is returned.

Parameters
cameraSimThe specific camera to get the robot-to-camera transform of
timeTimestamp of when the transform should be observed
Returns
The transform of this camera, or an empty optional if it is invalid

◆ GetVisionTargets() [1/2]

std::vector< VisionTargetSim > photon::VisionSystemSim::GetVisionTargets ( )
inline

Returns all the vision targets on the field.

Returns
The vision targets

◆ GetVisionTargets() [2/2]

std::vector< VisionTargetSim > photon::VisionSystemSim::GetVisionTargets ( std::string type)
inline

Returns all the vision targets of the specified type on the field.

Parameters
typeThe type of vision targets to return
Returns
The vision targets

◆ RemoveCamera()

bool photon::VisionSystemSim::RemoveCamera ( PhotonCameraSim * cameraSim)
inline

Remove a simulated camera from this vision system.

Parameters
cameraSimThe camera to remove
Returns
If the camera was present and removed

◆ RemoveVisionTargets() [1/2]

std::vector< VisionTargetSim > photon::VisionSystemSim::RemoveVisionTargets ( const std::vector< VisionTargetSim > & targets)
inline

Removes the specified VisionTargetSims from the simulated field.

Parameters
targetsThe targets to remove
Returns
The targets that were actually removed

◆ RemoveVisionTargets() [2/2]

void photon::VisionSystemSim::RemoveVisionTargets ( std::string type)
inline

Removes every VisionTargetSim of the specified type from the simulated field.

Parameters
typeType of target (e.g. "cargo"). Same as the type passed into #addVisionTargets(String, VisionTargetSim...)
Returns
The removed targets, or null if no targets of the specified type exist

◆ ResetCameraTransforms() [1/2]

void photon::VisionSystemSim::ResetCameraTransforms ( )
inline

Reset the previous transforms for all cameras to their current transform.

◆ ResetCameraTransforms() [2/2]

bool photon::VisionSystemSim::ResetCameraTransforms ( PhotonCameraSim * cameraSim)
inline

Reset the transform history for this camera to just the current transform.

Parameters
cameraSimThe camera to reset
Returns
If the cameraSim was valid and transforms were reset

◆ ResetRobotPose() [1/2]

void photon::VisionSystemSim::ResetRobotPose ( const frc::Pose2d & robotPose)
inline

Clears all previous robot poses and sets robotPose at current time.

Parameters
robotPoseThe robot pose

◆ ResetRobotPose() [2/2]

void photon::VisionSystemSim::ResetRobotPose ( const frc::Pose3d & robotPose)
inline

Clears all previous robot poses and sets robotPose at current time.

Parameters
robotPoseThe robot pose

◆ Update() [1/2]

void photon::VisionSystemSim::Update ( const frc::Pose2d & robotPose)
inline

Periodic update.

Ensure this is called repeatedly– camera performance is used to automatically determine if a new frame should be submitted.

Parameters
robotPoseMetersThe simulated robot pose in meters

◆ Update() [2/2]

void photon::VisionSystemSim::Update ( const frc::Pose3d & robotPose)
inline

Periodic update.

Ensure this is called repeatedly– camera performance is used to automatically determine if a new frame should be submitted.

Parameters
robotPoseMetersThe simulated robot pose in meters

The documentation for this class was generated from the following file: