Package org.photonvision.vision.opencv
Enum Class ImageRotationMode
- All Implemented Interfaces:
Serializable
,Comparable<ImageRotationMode>
,Constable
An image rotation about the camera's +Z axis, which points out of the camera towards the world.
This is mirrored relative to what you might traditionally think of as image rotation, which is
about an axis coming out of the image towards the viewer or camera. TODO: pull this from
image-rotation.md
-
Nested Class Summary
Nested classes/interfaces inherited from class java.lang.Enum
Enum.EnumDesc<E extends Enum<E>>
-
Enum Constant Summary
-
Field Summary
-
Method Summary
Modifier and TypeMethodDescriptionorg.opencv.core.Point
rotatePoint
(org.opencv.core.Point point, double width, double height) Rotate a point in an imagestatic ImageRotationMode
Returns the enum constant of this class with the specified name.static ImageRotationMode[]
values()
Returns an array containing the constants of this enum class, in the order they are declared.
-
Enum Constant Details
-
DEG_0
-
DEG_90_CCW
-
DEG_180_CCW
-
DEG_270_CCW
-
-
Field Details
-
value
public final int value -
rotation2d
-
-
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
-
rotatePoint
public org.opencv.core.Point rotatePoint(org.opencv.core.Point point, double width, double height) Rotate a point in an image- Parameters:
point
- The point in the unrotated imagewidth
- Image width, in pixelsheight
- Image height, in pixels- Returns:
- The point in the rotated frame
-