PhotonUtils

class photonvision.PhotonUtils

Bases: pybind11_object

static calculateDistanceToTarget(cameraHeight: meters, targetHeight: meters, cameraPitch: radians, targetPitch: radians) meters

Algorithm from https://docs.limelightvision.io/en/latest/cs_estimating_distance.html Estimates range to a target using the target’s elevation. This method can produce more stable results than SolvePNP when well tuned, if the full 6d robot pose is not required.

Parameters:
  • cameraHeight – The height of the camera off the floor.

  • targetHeight – The height of the target off the floor.

  • cameraPitch – The pitch of the camera from the horizontal plane. Positive valueBytes up.

  • targetPitch – The pitch of the target in the camera’s lens. Positive values up.

Returns:

The estimated distance to the target.

static estimateCameraToTarget(cameraToTargetTranslation: wpimath.geometry._geometry.Translation2d, fieldToTarget: wpimath.geometry._geometry.Pose2d, gyroAngle: wpimath.geometry._geometry.Rotation2d) wpimath.geometry._geometry.Transform2d

Estimates a {@link frc::Transform2d} that maps the camera position to the target position, using the robot’s gyro. Note that the gyro angle provided must line up with the field coordinate system – that is, it should read zero degrees when pointed towards the opposing alliance station, and increase as the robot rotates CCW.

Parameters:
  • cameraToTargetTranslation – A Translation2d that encodes the x/y position of the target relative to the camera.

  • fieldToTarget – A frc::Pose2d representing the target position in the field coordinate system.

  • gyroAngle – The current robot gyro angle, likely from odometry.

Returns:

A frc::Transform2d that takes us from the camera to the target.

static estimateCameraToTargetTranslation(targetDistance: meters, yaw: wpimath.geometry._geometry.Rotation2d) wpimath.geometry._geometry.Translation2d

Estimate the Translation2d of the target relative to the camera.

Parameters:
  • targetDistance – The distance to the target.

  • yaw – The observed yaw of the target.

Returns:

The target’s camera-relative translation.

static estimateFieldToCamera(cameraToTarget: wpimath.geometry._geometry.Transform2d, fieldToTarget: wpimath.geometry._geometry.Pose2d) wpimath.geometry._geometry.Pose2d

Estimates the pose of the camera in the field coordinate system, given the position of the target relative to the camera, and the target relative to the field. This only tracks the position of the camera, not the position of the robot itself.

Parameters:
  • cameraToTarget – The position of the target relative to the camera.

  • fieldToTarget – The position of the target in the field.

Returns:

The position of the camera in the field.

static estimateFieldToRobot(*args, **kwargs)

Overloaded function.

  1. estimateFieldToRobot(cameraHeight: meters, targetHeight: meters, cameraPitch: radians, targetPitch: radians, targetYaw: wpimath.geometry._geometry.Rotation2d, gyroAngle: wpimath.geometry._geometry.Rotation2d, fieldToTarget: wpimath.geometry._geometry.Pose2d, cameraToRobot: wpimath.geometry._geometry.Transform2d) -> wpimath.geometry._geometry.Pose2d

Estimate the position of the robot in the field.

Parameters:
  • cameraHeightMeters – The physical height of the camera off the floor in meters.

  • targetHeightMeters – The physical height of the target off the floor in meters. This should be the height of whatever is being targeted (i.e. if the targeting region is set to top, this should be the height of the top of the target).

  • cameraPitchRadians – The pitch of the camera from the horizontal plane in radians. Positive values up.

  • targetPitchRadians – The pitch of the target in the camera’s lens in radians. Positive values up.

  • targetYaw – The observed yaw of the target. Note that this must be CCW-positive, and Photon returns CW-positive.

  • gyroAngle – The current robot gyro angle, likely from odometry.

  • fieldToTarget – A frc::Pose2d representing the target position in the field coordinate system.

  • cameraToRobot – The position of the robot relative to the camera. If the camera was mounted 3 inches behind the “origin” (usually physical center) of the robot, this would be frc::Transform2d(3 inches, 0 inches, 0 degrees).

Returns:

The position of the robot in the field.

  1. estimateFieldToRobot(cameraToTarget: wpimath.geometry._geometry.Transform2d, fieldToTarget: wpimath.geometry._geometry.Pose2d, cameraToRobot: wpimath.geometry._geometry.Transform2d) -> wpimath.geometry._geometry.Pose2d

Estimates the pose of the robot in the field coordinate system, given the position of the target relative to the camera, the target relative to the field, and the robot relative to the camera.

Parameters:
  • cameraToTarget – The position of the target relative to the camera.

  • fieldToTarget – The position of the target in the field.

  • cameraToRobot – The position of the robot relative to the camera. If the camera was mounted 3 inches behind the “origin” (usually physical center) of the robot, this would be frc::Transform2d(3 inches, 0 inches, 0 degrees).

Returns:

The position of the robot in the field.