Classes | Functions
test_Sim3 Namespace Reference

Classes

class  TestSim3
 

Functions

Similarity3 align_poses_sim3 (List[Pose3] aTi_list, List[Pose3] bTi_list)
 
Similarity3 align_poses_sim3_ignore_missing (List[Optional[Pose3]] aTi_list, List[Optional[Pose3]] bTi_list)
 

Detailed Description

GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
Atlanta, Georgia 30332-0415
All Rights Reserved

See LICENSE for the license information

Sim3 unit tests.
Author: John Lambert

Function Documentation

◆ align_poses_sim3()

Similarity3 test_Sim3.align_poses_sim3 ( List[Pose3 aTi_list,
List[Pose3 bTi_list 
)
Align two pose graphs via similarity transformation. Note: poses cannot be missing/invalid.

We force SIM(3) alignment rather than SE(3) alignment.
We assume the two trajectories are of the exact same length.

Args:
    aTi_list: reference poses in frame "a" which are the targets for alignment
    bTi_list: input poses which need to be aligned to frame "a"

Returns:
    aSb: Similarity(3) object that aligns the two pose graphs.

Definition at line 675 of file test_Sim3.py.

◆ align_poses_sim3_ignore_missing()

Similarity3 test_Sim3.align_poses_sim3_ignore_missing ( List[Optional[Pose3]]  aTi_list,
List[Optional[Pose3]]  bTi_list 
)
Align by similarity transformation, but allow missing estimated poses in the input.

Note: this is a wrapper for align_poses_sim3() that allows for missing poses/dropped cameras.
This is necessary, as align_poses_sim3() requires a valid pose for every input pair.

We force SIM(3) alignment rather than SE(3) alignment.
We assume the two trajectories are of the exact same length.

Args:
    aTi_list: reference poses in frame "a" which are the targets for alignment
    bTi_list: input poses which need to be aligned to frame "a"

Returns:
    aSb: Similarity(3) object that aligns the two pose graphs.

Definition at line 643 of file test_Sim3.py.



gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:25:07