Package org.photonvision
Enum Class PhotonPoseEstimator.PoseStrategy
- All Implemented Interfaces:
Serializable
,Comparable<PhotonPoseEstimator.PoseStrategy>
,Constable
- Enclosing class:
- PhotonPoseEstimator
Position estimation strategies that can be used by the
PhotonPoseEstimator
class.-
Nested Class Summary
Nested classes/interfaces inherited from class java.lang.Enum
Enum.EnumDesc<E extends Enum<E>>
-
Enum Constant Summary
Enum ConstantDescriptionReturn the average of the best target poses using ambiguity as weight.Choose the Pose which is closest to the camera height.Choose the Pose which is closest to the last pose calculatedChoose the Pose which is closest to a set Reference position.Choose the Pose with the lowest ambiguity.Use all visible tags to compute a single pose estimate on coprocessor.Use all visible tags to compute a single pose estimate. -
Method Summary
Modifier and TypeMethodDescriptionReturns the enum constant of this class with the specified name.static PhotonPoseEstimator.PoseStrategy[]
values()
Returns an array containing the constants of this enum class, in the order they are declared.
-
Enum Constant Details
-
LOWEST_AMBIGUITY
Choose the Pose with the lowest ambiguity. -
CLOSEST_TO_CAMERA_HEIGHT
Choose the Pose which is closest to the camera height. -
CLOSEST_TO_REFERENCE_POSE
Choose the Pose which is closest to a set Reference position. -
CLOSEST_TO_LAST_POSE
Choose the Pose which is closest to the last pose calculated -
AVERAGE_BEST_TARGETS
Return the average of the best target poses using ambiguity as weight. -
MULTI_TAG_PNP_ON_COPROCESSOR
Use all visible tags to compute a single pose estimate on coprocessor. This option needs to be enabled on the PhotonVision web UI as well. -
MULTI_TAG_PNP_ON_RIO
Use all visible tags to compute a single pose estimate. This runs on the RoboRIO, and can take a lot of time.
-
-
Method Details
-
values
Returns an array containing the constants of this enum class, in the order they are declared.- Returns:
- an array containing the constants of this enum class, in the order they are declared
-
valueOf
Returns the enum constant of this class with the specified name. The string must match exactly an identifier used to declare an enum constant in this class. (Extraneous whitespace characters are not permitted.)- Parameters:
name
- the name of the enum constant to be returned.- Returns:
- the enum constant with the specified name
- Throws:
IllegalArgumentException
- if this enum class has no constant with the specified nameNullPointerException
- if the argument is null
-