Go to the documentation of this file.
38 using namespace gtsam;
54 emplace_shared<Projection>(
z,
model,
X(
i),
L(
j));
73 double U1 = rand() / (double) (RAND_MAX);
74 double U2 = rand() / (double) (RAND_MAX);
77 S = V1 * V1 +
V2 *
V2;
88 const Symbol cameraFrameNumber(
'x', 1), landmarkNumber(
'l', 1);
90 std::shared_ptr<Projection>
factor1(
93 std::shared_ptr<Projection>
factor2(
120 vector<Point3> landmarks;
121 landmarks.push_back(
Point3(-1., -1.,
z));
122 landmarks.push_back(
Point3(-1., 1.,
z));
123 landmarks.push_back(
Point3(1., 1.,
z));
124 landmarks.push_back(
Point3(1., -1.,
z));
125 landmarks.push_back(
Point3(-1.5, -1.5, 1.5 *
z));
126 landmarks.push_back(
Point3(-1.5, 1.5, 1.5 *
z));
127 landmarks.push_back(
Point3(1.5, 1.5, 1.5 *
z));
128 landmarks.push_back(
Point3(1.5, -1.5, 1.5 *
z));
129 landmarks.push_back(
Point3(-2., -2., 2 *
z));
130 landmarks.push_back(
Point3(-2., 2., 2 *
z));
131 landmarks.push_back(
Point3(2., 2., 2 *
z));
132 landmarks.push_back(
Point3(2., -2., 2 *
z));
156 const std::vector<GeneralCamera>&
cameras,
157 const std::vector<Point3>& landmarks) {
159 for (
size_t i = 0;
i < landmarks.size(); ++
i)
167 TEST( GeneralSFMFactor_Cal3Bundler, optimize_defaultK ) {
175 for (
size_t i = 0;
i < landmarks.size(); ++
i) {
181 const size_t nMeasurements =
cameras.size() * landmarks.size();
184 const double noise =
baseline * 0.1;
189 for (
size_t i = 0;
i < landmarks.size(); ++
i) {
206 TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_SingleMeasurementError ) {
212 for (
size_t i = 0;
i < landmarks.size(); ++
i) {
218 const size_t nMeasurements =
cameras.size() * landmarks.size();
221 const double noise =
baseline * 0.1;
227 for (
size_t i = 0;
i < landmarks.size(); ++
i) {
239 const double reproj_error = 1
e-5;
244 EXPECT(optimizer.
error() < 0.5 * reproj_error * nMeasurements);
248 TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_FixCameras ) {
254 const double noise =
baseline * 0.1;
257 for (
size_t i = 0;
i < landmarks.size(); ++
i) {
263 const size_t nMeasurements = landmarks.
size() *
cameras.size();
269 for (
size_t i = 0;
i < landmarks.size(); ++
i) {
280 const double reproj_error = 1
e-5;
285 EXPECT(optimizer.
error() < 0.5 * reproj_error * nMeasurements);
289 TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_FixLandmarks ) {
297 for (
size_t i = 0;
i < landmarks.size(); ++
i) {
303 const size_t nMeasurements = landmarks.
size() *
cameras.size();
307 const double rot_noise = 1
e-5, trans_noise = 1
e-3, focal_noise = 1,
308 distort_noise = 1
e-3;
314 trans_noise, trans_noise, trans_noise,
315 focal_noise, distort_noise, distort_noise
321 for (
size_t i = 0;
i < landmarks.size(); ++
i) {
327 for (
size_t i = 0;
i < landmarks.size(); ++
i)
328 graph.addPoint3Constraint(
i, landmarks[
i]);
330 const double reproj_error = 1
e-5;
335 EXPECT(optimizer.
error() < 0.5 * reproj_error * nMeasurements);
339 TEST( GeneralSFMFactor_Cal3Bundler, optimize_varK_BA ) {
346 for (
size_t i = 0;
i < landmarks.size(); ++
i) {
352 const size_t nMeasurements =
cameras.size() * landmarks.size();
355 const double noise =
baseline * 0.1;
361 for (
size_t i = 0;
i < landmarks.size(); ++
i) {
374 noiseModel::Isotropic::Sigma(1, 10.));
376 const double reproj_error = 1
e-5;
381 EXPECT(optimizer.
error() < 0.5 * reproj_error * nMeasurements);
static int runAllTests(TestResult &result)
virtual const Values & optimize()
static double getGaussian()
std::array< PinholeCamera< Cal3_S2 >, 3 > cameras
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Concept check for values that can be used in unit tests.
#define EXPECT(condition)
static vector< Point3 > genPoint3()
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Serializable factor induced by a range measurement.
static const Point3 pt(1.0, 2.0, 3.0)
const EIGEN_DEVICE_FUNC LogReturnType log() const
a general SFM factor with an unknown calibration
static const double sigma
double error() const
return error in current optimizer state
void addPoint3Constraint(int j, const Point3 &p)
DecisionTreeFactor factor(D &C &B &A, "0.0 0.0 0.0 0.60658897 0.61241912 0.61241969 0.61247685 0.61247742 0.0 " "0.0 0.0 0.99995287 1.0 1.0 1.0 1.0")
NonlinearEquality< GeneralCamera > CameraConstraint
TEST(GeneralSFMFactor_Cal3Bundler, equals)
static vector< GeneralCamera > genCameraVariableCalibration()
static vector< GeneralCamera > genCameraDefaultCalibration()
static const SharedNoiseModel sigma1(noiseModel::Unit::Create(2))
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Base class for all pinhole cameras.
Calibration used by Bundler.
void insert(Key j, const Vector &value)
noiseModel::Base::shared_ptr SharedNoiseModel
GeneralSFMFactor< GeneralCamera, Point3 > Projection
noiseModel::Diagonal::shared_ptr model
static enum @1096 ordering
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
static const Point3 V2(-6.5, 3.5, 6.2)
static std::shared_ptr< Ordering > getOrdering(const std::vector< GeneralCamera > &cameras, const std::vector< Point3 > &landmarks)
Factor Graph consisting of non-linear factors.
PinholeCamera< Cal3Bundler > GeneralCamera
NonlinearEquality< Point3 > Point3Constraint
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
static const double baseline
NonlinearFactorGraph graph
void addCameraConstraint(int j, const GeneralCamera &p)
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Calibration used by Bundler.
Jet< T, N > sqrt(const Jet< T, N > &f)
void addMeasurement(const int &i, const int &j, const Point2 &z, const SharedNoiseModel &model)
Rot2 R(Rot2::fromAngle(0.1))
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
gtsam
Author(s):
autogenerated on Wed Jan 1 2025 04:06:21