Skip to content
This repository was archived by the owner on Jul 26, 2020. It is now read-only.
8 changes: 8 additions & 0 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -86,6 +86,14 @@ markers are roughly level with the observer:

Available as a typed named tuple `Spherical` from `Token.spherical`.

### Orientation

Rotation of the marker around its centre (relative to the observer)
- `rot_x`: rotation about the Cartesian x-axis, positive angles represent the front going downwards.
- `rot_y`: rotation about the Cartesian y-axis, positive angles represent the front going leftwards.
- `rot_z`: rotation about the Cartesian z-axis, positive angles represent the top going rightwards.

Available as a typed named tuple `Orientation` from `Token.orientation`.

## Camera support

Expand Down
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added calibrations/tecknet_rotations/-90rot_z.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added calibrations/tecknet_rotations/135rot_z.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added calibrations/tecknet_rotations/180rot_z.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added calibrations/tecknet_rotations/45rot_z.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
Binary file added calibrations/tecknet_rotations/90rot_z.png
Loading
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.
9 changes: 8 additions & 1 deletion sb_vision/__init__.py
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,13 @@
"""

from .camera import Camera, FileCamera
from .coordinates import Cartesian, LegacyPolar, Spherical, cartesian_to_spherical
from .coordinates import (
Cartesian,
Orientation,
LegacyPolar,
Spherical,
cartesian_to_spherical,
)
from .tokens import Token
from .vision import Vision

Expand All @@ -17,6 +23,7 @@
'FileCamera',
'Token',
'Cartesian',
'Orientation',
'LegacyPolar',
'Spherical',
'cartesian_to_spherical',
Expand Down
5 changes: 5 additions & 0 deletions sb_vision/coordinates.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,11 @@ def tolist(self):
('dist', AnyFloat),
))

Orientation = NamedTuple('Orientation', (
('rot_x', AnyFloat),
('rot_y', AnyFloat),
('rot_z', AnyFloat),
))

PixelCoordinate = NamedTuple('PixelCoordinate', [('x', AnyFloat), ('y', AnyFloat)])

Expand Down
10 changes: 3 additions & 7 deletions sb_vision/cv3d.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@

from sb_vision.native import _cv3d # type: ignore

from .coordinates import Cartesian, PixelCoordinate
from .coordinates import Cartesian, Orientation, PixelCoordinate


class Cv3dError(RuntimeError):
Expand Down Expand Up @@ -39,7 +39,7 @@ def solve_pnp(
pixel_corners: Sequence[PixelCoordinate],
camera_matrix: Sequence[Sequence[float]],
distance_coefficients: Sequence[Sequence[float]],
) -> Tuple[Cartesian, Tuple[float, float, float]]:
) -> Tuple[Cartesian, Orientation]:
"""
Wrapper around OpenCV solvePnP.

Expand All @@ -64,9 +64,5 @@ def solve_pnp(

return (
Cartesian(*translation_vector),
(
float(orientation_vector[0]),
float(orientation_vector[1]),
float(orientation_vector[2]),
),
Orientation(*orientation_vector),
)
6 changes: 3 additions & 3 deletions sb_vision/find_3D_coords.py
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@

import numpy as np

from sb_vision.coordinates import Cartesian, PixelCoordinate
from sb_vision.coordinates import Cartesian, Orientation, PixelCoordinate

from . import cv3d

Expand Down Expand Up @@ -151,7 +151,7 @@ def calculate_transforms(
pixel_corners: List[PixelCoordinate],
camera_matrix: List[List[float]],
distance_coefficients: List[List[float]],
) -> Tuple[Cartesian, Tuple[float, float, float]]:
) -> Tuple[Cartesian, Orientation]:
"""
Calculate the position of a marker.

Expand All @@ -171,10 +171,10 @@ def calculate_transforms(

# create the rectangle representing the marker in 3D
object_points = [
[-width_from_centre, height_from_centre, 0],
[width_from_centre, height_from_centre, 0],
[width_from_centre, -height_from_centre, 0],
[-width_from_centre, -height_from_centre, 0],
[-width_from_centre, height_from_centre, 0],
]

translation_vector, orientation_vector = cv3d.solve_pnp(
Expand Down
7 changes: 6 additions & 1 deletion sb_vision/tokens.py
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@

from .coordinates import (
Cartesian,
Orientation,
cartesian_to_legacy_polar,
cartesian_to_spherical,
)
Expand Down Expand Up @@ -79,6 +80,7 @@ def from_apriltag_detection(

instance.update_3D_transforms(
translation=translation,
orientation=orientation,
)
return instance

Expand Down Expand Up @@ -106,13 +108,16 @@ def update_pixel_coords(
def update_3D_transforms(
self,
*,
translation: Cartesian
translation: Cartesian,
orientation: Orientation
):
"""Calculate 3D coordinate information from the given transformations."""
# Cartesian Co-ordinates in the 3D World, relative to the camera
# (as opposed to somehow being compass-aligned)
self.cartesian = translation

self.orientation = orientation

# Polar co-ordinates in the 3D world, relative to the camera
self.polar = cartesian_to_legacy_polar(self.cartesian)
self.legacy_polar = cartesian_to_legacy_polar(self.cartesian)
Expand Down
97 changes: 97 additions & 0 deletions tests/test_orientation.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,97 @@
"""Tests for marker orientations."""

import math
from pathlib import Path

import pytest
from pytest import approx

from sb_vision import FileCamera, Orientation, Vision

ROTATION_TOLERANCE_DEGREES = 6

CALIBRATIONS = Path(__file__).parent.parent / 'calibrations' / 'tecknet_rotations'

TEST_IMAGES = [
(
'0rot_x-45rot_y1.1z.png',
False,
Orientation(rot_x=0, rot_y=math.radians(-45), rot_z=0),
),
(
'-45rot_x0rot_y1.1z.png',
False,
Orientation(rot_x=math.radians(-45), rot_y=0, rot_z=0),
),
(
'-22.5rot_x0rot_y0.6z.png',
False,
Orientation(rot_x=math.radians(-22.5), rot_y=0, rot_z=0),
),
(
'0rot_x-22.5rot_y0.6z.png',
False,
Orientation(rot_x=0, rot_y=math.radians(-22.5), rot_z=0),
),
(
'0rot_x0rot_y0.55z.png',
False,
Orientation(rot_x=0, rot_y=0, rot_z=0),
),
(
'-90rot_z.png',
False,
Orientation(rot_x=0, rot_y=0, rot_z=math.radians(-90)),
),
(
'90rot_z.png',
False,
Orientation(rot_x=0, rot_y=0, rot_z=math.radians(90)),
),
(
'180rot_z.png',
True,
Orientation(rot_x=0, rot_y=0, rot_z=math.radians(180)),
),
(
'135rot_z.png',
False,
Orientation(rot_x=0, rot_y=0, rot_z=math.radians(135)),
),
(
'45rot_z.png',
False,
Orientation(rot_x=0, rot_y=0, rot_z=math.radians(45)),
),
]


@pytest.mark.parametrize(
"photo, allow_wrapping, expected_orientation",
TEST_IMAGES,
)
def test_image_coordinates(photo, allow_wrapping, expected_orientation):
"""Make sure that this particular file gives these particular tokens."""
camera = FileCamera(CALIBRATIONS / photo, camera_model='C016')
vision = Vision(camera)
token, = vision.snapshot()

def approx_ang(expected_degrees):
return approx(expected_degrees, abs=ROTATION_TOLERANCE_DEGREES)

def assert_angle(angle_radians, expected_degrees, message):
expected_degrees = approx_ang(math.degrees(expected_degrees))
# Check both +0 and +360 so approx can cover the jump between -180 and 180
if allow_wrapping:
assert \
math.degrees(angle_radians) == expected_degrees or \
math.degrees(angle_radians) + 360 == expected_degrees, \
message
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Why do we need to do this?

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

so we can allow for a small error on a value which is close to 180 or -180. it means it checks both the 180 version and the -180 version in one check.

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Right, but these are tests -- they're dealing with fixed inputs which should mean that they have fixed outputs. We should know which side the result is and just assert that.

Are you saying that we get varying results from solvePnP even for constant input data?

An alternative way of spelling this, iff it's absolutely needed, might be to declare that the tests operate in a positive-only frame and run all the values through % 360 first.
I'm still not sure I like this approach as it means we're not really checking the direct output from the API. The not-checking-the-real-value aspect could be mitigated by adding a range bounds first, perhaps like this:

assert -180 < actual_degrees < 180, \
    "{} is outside the expected range (-180° to 180°)".format(angle_name)
    # angle_name is one of rot_x, rot_y, etc.

# Bound to positive numbers for easier comparisons
actual_degrees %= 360

assert actual_degrees == expected_degrees, ...

While I'll admit there's a bit more processing here, degrees being a modulo thing is fairly obvious to everyone since we're used to the idea that 720° is the direction same as 0°.

Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I respect what you're saying but I disagree that we should check exact values. It makes the tests extremely fragile for changes higher up the pipeline (i.e. thresholding). If we want to check that the outputs don't vary, we should have a separate test

Copy link
Member Author

@Adimote Adimote Mar 5, 2018

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

%360 doesn't solve the problem, it shifts the barrier to be between 0 and 360

else:
assert math.degrees(angle_radians) == expected_degrees, message

rot_x, rot_y, rot_z = token.orientation

assert_angle(rot_x, expected_orientation.rot_x, "Wrong Orientation rot_x")
assert_angle(rot_y, expected_orientation.rot_y, "Wrong Orientation rot_y")
assert_angle(rot_z, expected_orientation.rot_z, "Wrong Orientation rot_z")