Public Attributes | |
fisheye_cameras | |
fisheye_measurements | |
landmark | |
origin | |
poses | |
stereographic | |
triangulation_poses | |
Set up two camera poses Looking along X-axis, 1 meter above ground plane (x-y) More... | |
unified_cameras | |
unified_measurements | |
Tests for backwards compatibility of the Python wrapper.
Definition at line 31 of file test_backwards_compatibility.py.
Tuple[List[Point2], Union[CameraSetCal3Bundler, CameraSetCal3_S2, List[Cal3Bundler], List[Cal3_S2]]] test_backwards_compatibility.TestBackwardsCompatibility.generate_measurements | ( | self, | |
Union[Cal3Bundler, Cal3_S2] | calibration, | ||
Union[PinholeCameraCal3Bundler, PinholeCameraCal3_S2] | camera_model, | ||
Iterable[Iterable[Union[int, float]]] | cal_params, | ||
Optional[Union[CameraSetCal3Bundler, CameraSetCal3_S2]] | camera_set = None |
||
) |
Generate vector of measurements for given calibration and camera model. Args: calibration: Camera calibration e.g. Cal3_S2 camera_model: Camera model e.g. PinholeCameraCal3_S2 cal_params: Iterable of camera parameters for `calibration` e.g. [K1, K2] camera_set: Cameraset object (for individual calibrations) Returns: list of measurements and list/CameraSet object for cameras
Definition at line 698 of file test_backwards_compatibility.py.
def test_backwards_compatibility.TestBackwardsCompatibility.setUp | ( | self | ) |
Setup test fixtures
Definition at line 34 of file test_backwards_compatibility.py.
None test_backwards_compatibility.TestBackwardsCompatibility.test_align | ( | self | ) |
Ensure estimation of the Pose2 element to align two 2d point clouds succeeds. Two point clouds represent horseshoe-shapes of the same size, just rotated and translated: | X---X | | | X---X ------------------ | | O | O | | | O---O
Definition at line 363 of file test_backwards_compatibility.py.
None test_backwards_compatibility.TestBackwardsCompatibility.test_align_poses2_along_straight_line | ( | self | ) |
Test Align of list of Pose2Pair. Scenario: 3 object poses same scale (no gauge ambiguity) world frame has poses rotated about 180 degrees. world and egovehicle frame translated by 15 meters w.r.t. each other
Definition at line 482 of file test_backwards_compatibility.py.
def test_backwards_compatibility.TestBackwardsCompatibility.test_align_poses2_along_straight_line_gauge | ( | self | ) |
Test if Align Pose2Pairs method can account for gauge ambiguity. Scenario: 3 object poses with gauge ambiguity (2x scale) world frame has poses rotated by 90 degrees. world and egovehicle frame translated by 11 meters w.r.t. each other
Definition at line 517 of file test_backwards_compatibility.py.
def test_backwards_compatibility.TestBackwardsCompatibility.test_align_poses2_scaled_squares | ( | self | ) |
Test if Align Pose2Pairs method can account for gauge ambiguity. Make sure a big and small square can be aligned. The u's represent a big square (10x10), and v's represents a small square (4x4). Scenario: 4 object poses with gauge ambiguity (2.5x scale)
Definition at line 552 of file test_backwards_compatibility.py.
def test_backwards_compatibility.TestBackwardsCompatibility.test_align_poses3_along_straight_line | ( | self | ) |
Test Align Pose3Pairs method. Scenario: 3 object poses same scale (no gauge ambiguity) world frame has poses rotated about x-axis (90 degree roll) world and egovehicle frame translated by 15 meters w.r.t. each other
Definition at line 590 of file test_backwards_compatibility.py.
def test_backwards_compatibility.TestBackwardsCompatibility.test_align_poses3_along_straight_line_gauge | ( | self | ) |
Test if Align Pose3Pairs method can account for gauge ambiguity. Scenario: 3 object poses with gauge ambiguity (2x scale) world frame has poses rotated about z-axis (90 degree yaw) world and egovehicle frame translated by 11 meters w.r.t. each other
Definition at line 625 of file test_backwards_compatibility.py.
def test_backwards_compatibility.TestBackwardsCompatibility.test_align_poses3_scaled_squares | ( | self | ) |
Test if Align Pose3Pairs method can account for gauge ambiguity. Make sure a big and small square can be aligned. The u's represent a big square (10x10), and v's represents a small square (4x4). Scenario: 4 object poses with gauge ambiguity (2.5x scale)
Definition at line 660 of file test_backwards_compatibility.py.
def test_backwards_compatibility.TestBackwardsCompatibility.test_align_squares | ( | self | ) |
Test if Align method can align 2 squares.
Definition at line 409 of file test_backwards_compatibility.py.
def test_backwards_compatibility.TestBackwardsCompatibility.test_Cal3Fisheye_triangulation_rectify | ( | self | ) |
Estimate spatial point from image measurements using rectification from a Cal3Fisheye camera model.
Definition at line 76 of file test_backwards_compatibility.py.
def test_backwards_compatibility.TestBackwardsCompatibility.test_Cal3Unified_triangulation_rectify | ( | self | ) |
Estimate spatial point from image measurements using rectification from a Cal3Unified camera model.
Definition at line 93 of file test_backwards_compatibility.py.
None test_backwards_compatibility.TestBackwardsCompatibility.test_constructorBetweenFactorPose2s | ( | self | ) |
Check if ShonanAveraging2 constructor works when not initialized from g2o file. GT pose graph: | cam 1 = (0,4) --o | . . . . . | | o-- ... o-- cam 0 cam 2 = (4,0) (0,0)
Definition at line 428 of file test_backwards_compatibility.py.
def test_backwards_compatibility.TestBackwardsCompatibility.test_factor | ( | self | ) |
Check that the InnerConstraint factor leaves the mean unchanged.
Definition at line 333 of file test_backwards_compatibility.py.
def test_backwards_compatibility.TestBackwardsCompatibility.test_find | ( | self | ) |
Check that optimizing for Karcher mean (which minimizes Between distance) gets correct result.
Definition at line 309 of file test_backwards_compatibility.py.
def test_backwards_compatibility.TestBackwardsCompatibility.test_find_karcher_mean_identity | ( | self | ) |
Averaging 3 identity rotations should yield the identity.
Definition at line 321 of file test_backwards_compatibility.py.
def test_backwards_compatibility.TestBackwardsCompatibility.test_FixedLagSmootherExample | ( | self | ) |
Simple test that checks for equality between C++ example file and the Python implementation. See gtsam_unstable/examples/FixedLagSmootherExample.cpp
Definition at line 182 of file test_backwards_compatibility.py.
def test_backwards_compatibility.TestBackwardsCompatibility.test_ordering | ( | self | ) |
Test ordering
Definition at line 279 of file test_backwards_compatibility.py.
None test_backwards_compatibility.TestBackwardsCompatibility.test_outliers_and_far_landmarks | ( | self | ) |
Check safe triangulation function.
Definition at line 831 of file test_backwards_compatibility.py.
None test_backwards_compatibility.TestBackwardsCompatibility.test_sfm_track_2d_constructor | ( | self | ) |
Test construction of 2D SfM track.
Definition at line 174 of file test_backwards_compatibility.py.
None test_backwards_compatibility.TestBackwardsCompatibility.test_track_generation | ( | self | ) |
Ensures that DSF generates three tracks from measurements in 3 images (H=200,W=400).
Definition at line 110 of file test_backwards_compatibility.py.
None test_backwards_compatibility.TestBackwardsCompatibility.test_triangulation_robust_three_poses | ( | self | ) |
Ensure triangulation with a robust model works.
Definition at line 766 of file test_backwards_compatibility.py.
None test_backwards_compatibility.TestBackwardsCompatibility.test_TriangulationExample | ( | self | ) |
Tests triangulation with shared Cal3_S2 calibration
Definition at line 734 of file test_backwards_compatibility.py.
test_backwards_compatibility.TestBackwardsCompatibility.fisheye_cameras |
Definition at line 47 of file test_backwards_compatibility.py.
test_backwards_compatibility.TestBackwardsCompatibility.fisheye_measurements |
Definition at line 48 of file test_backwards_compatibility.py.
test_backwards_compatibility.TestBackwardsCompatibility.landmark |
Definition at line 74 of file test_backwards_compatibility.py.
test_backwards_compatibility.TestBackwardsCompatibility.origin |
Definition at line 44 of file test_backwards_compatibility.py.
test_backwards_compatibility.TestBackwardsCompatibility.poses |
Definition at line 45 of file test_backwards_compatibility.py.
test_backwards_compatibility.TestBackwardsCompatibility.stereographic |
Definition at line 54 of file test_backwards_compatibility.py.
test_backwards_compatibility.TestBackwardsCompatibility.triangulation_poses |
Set up two camera poses Looking along X-axis, 1 meter above ground plane (x-y)
Definition at line 69 of file test_backwards_compatibility.py.
test_backwards_compatibility.TestBackwardsCompatibility.unified_cameras |
Definition at line 58 of file test_backwards_compatibility.py.
test_backwards_compatibility.TestBackwardsCompatibility.unified_measurements |
Definition at line 59 of file test_backwards_compatibility.py.