1 from __future__
import print_function
7 from gtsam
import Point3, Pose3, PinholeCameraCal3_S2, Cal3_S2
12 Options to generate test scenario 15 def __init__(self, triangle=False, nrCameras=3, K=Cal3_S2()):
17 Options to generate test scenario 18 @param triangle: generate a triangle scene with 3 points if True, otherwise 20 @param nrCameras: number of cameras to generate 21 @param K: camera calibration object 29 Object holding generated ground-truth data 32 def __init__(self, K=Cal3_S2(), nrCameras=3, nrPoints=4):
51 Object holding generated measurement data 57 def __init__(self, K=Cal3_S2(), nrCameras=3, nrPoints=4):
60 self.
J = [x[:]
for x
in [[0] * nrPoints] * nrCameras]
66 np.array([0.001, 0.001, 0.001, 0.1, 0.1, 0.1]))
70 np.array([0.05, 0.05, 0.05, 0.2, 0.2, 0.2]))
76 """ Generate ground-truth and measurement data. """ 78 K =
Cal3_S2(500, 500, 0, 640. / 2., 480. / 2.)
79 nrPoints = 3
if options.triangle
else 8
81 truth =
GroundTruth(K=K, nrCameras=options.nrCameras, nrPoints=nrPoints)
82 data =
Data(K, nrCameras=options.nrCameras, nrPoints=nrPoints)
87 for j
in range(
len(truth.points)):
88 theta = j * 2 * pi / nrPoints
89 truth.points[j] =
Point3(r * math.cos(theta), r * math.sin(theta), 0)
101 for i
in range(options.nrCameras):
102 theta = i * 2 * pi / options.nrCameras
103 t =
Point3(r * math.cos(theta), r * math.sin(theta), height)
104 truth.cameras[i] = PinholeCameraCal3_S2.Lookat(t,
109 for j
in range(nrPoints):
111 data.Z[i][j] = truth.cameras[i].
project(truth.points[j])
115 for i
in range(1, options.nrCameras):
116 data.odometry[i] = truth.cameras[i - 1].
pose().
between(
117 truth.cameras[i].
pose())
void print(const Matrix &A, const string &s, ostream &stream)
Point2_ project(const Point3_ &p_cam)
Expression version of PinholeBase::Project.
def generate_data(options)
def __init__(self, triangle=False, nrCameras=3, K=Cal3_S2())
static const Pose3 pose(Rot3(Vector3(1,-1,-1).asDiagonal()), Point3(0, 0, 0.5))
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
def __init__(self, K=Cal3_S2(), nrCameras=3, nrPoints=4)
Expression< T > between(const Expression< T > &t1, const Expression< T > &t2)
def __init__(self, K=Cal3_S2(), nrCameras=3, nrPoints=4)
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)