Skip to content

Commit

Permalink
Add ADD
Browse files Browse the repository at this point in the history
  • Loading branch information
mcm001 committed Oct 17, 2024
1 parent 1e38934 commit b8550e0
Show file tree
Hide file tree
Showing 9 changed files with 61 additions and 12 deletions.
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
# Calibration and Image Rotation

To stay consistent with the OpenCV camera coordinate frame, we put the origin in the top left, with X right, Y down, and Z out (as required by the right-hand rule). Intuitively though, if I ask you to rotate an image 90 degrees clockwise though, you'd probably rotate it about -Z in this coordinate system. Just be aware of this inconsistency.

![](images/image_corner_frames.png)

If we have any one point in any of those coordinate systems, we can transform it into any of the other ones using standard geometry libraries by performing relative transformations (like in this pseudocode):

```
Translation2d tag_corner1 = new Translation2d();
Translation2d rotated = tag_corner1.relativeTo(ORIGIN_ROTATED_90_CCW);
```
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
5 changes: 5 additions & 0 deletions docs/source/docs/contributing/design-descriptions/index.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
# Software Architecture Design Descriptions

```{toctree}
image-rotation
```
1 change: 1 addition & 0 deletions docs/source/docs/contributing/index.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,4 +4,5 @@
building-photon
building-docs
developer-docs/index
design-descriptions/index
```
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ public CameraCalibrationCoefficients rotateCoefficients(ImageRotationMode rotati
switch (rotation) {
case DEG_0:
break;
case DEG_270_CCW:
case DEG_90_CCW:
// FX
rotatedIntrinsics.put(0, 0, fy);
// FY
Expand All @@ -143,7 +143,7 @@ public CameraCalibrationCoefficients rotateCoefficients(ImageRotationMode rotati
rotatedDistCoeffs.put(0, 3, p1);

break;
case DEG_180:
case DEG_180_CCW:
// CX
rotatedIntrinsics.put(0, 2, unrotatedImageSize.width - cx);
// CY
Expand All @@ -154,7 +154,7 @@ public CameraCalibrationCoefficients rotateCoefficients(ImageRotationMode rotati
// P2
rotatedDistCoeffs.put(0, 3, -p2);
break;
case DEG_90_CCW:
case DEG_270_CCW:
// FX
rotatedIntrinsics.put(0, 0, fy);
// FY
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -216,7 +216,7 @@ protected void setVideoModeInternal(VideoMode videoMode) {
getConfiguration().path,
mode.width,
mode.height,
(m_rotationMode == ImageRotationMode.DEG_180 ? 180 : 0));
(m_rotationMode == ImageRotationMode.DEG_180_CCW ? 180 : 0));
if (r_ptr == 0) {
logger.error("Couldn't create a zero copy Pi Camera while switching video modes");
if (!LibCameraJNI.destroyCamera(r_ptr)) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -100,7 +100,7 @@ public FrameStaticProperties rotate(ImageRotationMode rotation) {
int newWidth = imageWidth;
int newHeight = imageHeight;

if (rotation == ImageRotationMode.DEG_270_CCW || rotation == ImageRotationMode.DEG_90_CCW) {
if (rotation == ImageRotationMode.DEG_90_CCW || rotation == ImageRotationMode.DEG_270_CCW) {
newWidth = imageHeight;
newHeight = imageWidth;
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -19,15 +19,27 @@

import org.opencv.core.Core;

import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Rotation2d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.util.Units;

/**
* 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.
*/
public enum ImageRotationMode {
DEG_0(-1),
DEG_270_CCW(Core.ROTATE_90_CLOCKWISE),
DEG_180(Core.ROTATE_180),
DEG_90_CCW(Core.ROTATE_90_COUNTERCLOCKWISE);
DEG_0(-1, new Rotation2d()),
// rotating an image matrix clockwise is a ccw rotation about camera +Z, lmao
DEG_90_CCW(Core.ROTATE_90_CLOCKWISE, new Rotation2d(Units.degreesToRadians(90))),
DEG_180_CCW(Core.ROTATE_180, new Rotation2d(Units.degreesToRadians(90))),
DEG_270_CCW(Core.ROTATE_90_COUNTERCLOCKWISE, new Rotation2d(Units.degreesToRadians(90)));

public final int value;
public final Rotation2d rotation2d;

ImageRotationMode(int value) {
ImageRotationMode(int value, Rotation2d tr) {
this.value = value;
this.rotation2d = tr;
}
}
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
package org.photonvision.vision.pipeline;

import static org.junit.jupiter.api.Assertions.assertArrayEquals;
import static org.junit.jupiter.api.Assertions.assertEquals;

import java.io.IOException;

Expand All @@ -10,8 +11,10 @@
import org.junitpioneer.jupiter.cartesian.CartesianTest;
import org.junitpioneer.jupiter.cartesian.CartesianTest.Enum;
import org.opencv.calib3d.Calib3d;
import org.opencv.core.Core;
import org.opencv.core.MatOfPoint2f;
import org.opencv.core.Point;
import org.opencv.core.Size;
import org.photonvision.common.configuration.ConfigManager;
import org.photonvision.common.logging.LogGroup;
import org.photonvision.common.logging.LogLevel;
Expand All @@ -29,6 +32,7 @@

import edu.wpi.first.math.geometry.Pose3d;
import edu.wpi.first.math.geometry.Transform3d;
import edu.wpi.first.math.geometry.Translation2d;
import edu.wpi.first.math.geometry.Rotation3d;
import edu.wpi.first.math.geometry.Translation3d;
import edu.wpi.first.math.util.Units;
Expand All @@ -50,6 +54,21 @@ public static void init() throws IOException {
ConfigManager.getInstance().load();
}

@Test
public void meme() {
var s = new Size(200, 100);
var offset = new Translation2d(s.width, s.height);
var angle = ImageRotationMode.DEG_90_CCW;

var p = new Translation2d(2, 1);
var expected = new Translation2d(s.height - p.getY(), p.getX());

var rotatedP = (p.plus(offset)).rotateBy(angle.rotation2d);


assertEquals(expected, rotatedP);
}

@CartesianTest
public void testUndistortImagePointsWithRotation(@Enum ImageRotationMode rot) {
// Use predefined camera calibration coefficients from TestUtils
Expand Down Expand Up @@ -123,10 +142,10 @@ public void testApriltagRotated() {
CVPipelineResult pipelineResult = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera);
var pose_base = pipelineResult.targets.get(0).getBestCameraToTarget3d();

frameProvider.requestFrameRotation(ImageRotationMode.DEG_90_CCW);
frameProvider.requestFrameRotation(ImageRotationMode.DEG_270_CCW);
CVPipelineResult pipelineResult2 = pipeline.run(frameProvider.get(), QuirkyCamera.DefaultCamera);
var pose_rotated = pipelineResult2.targets.get(0).getBestCameraToTarget3d();
var pose_unrotated = new Transform3d(new Translation3d(), new Rotation3d(Units.degreesToRadians(180), 0, 0)).plus(pose_rotated);
var pose_unrotated = new Transform3d(new Translation3d(), new Rotation3d(0, 0, Units.degreesToRadians(270))).plus(pose_rotated);

Assertions.assertEquals(pose_base.getX(), pose_unrotated.getX(), 0.01);
Assertions.assertEquals(pose_base.getY(), pose_unrotated.getY(), 0.01);
Expand Down

0 comments on commit b8550e0

Please sign in to comment.