Go to the documentation of this file.
21 using namespace gtsam;
45 double theta =
atan2(ray.y(), ray.x());
46 double phi =
atan2(ray.z(),
sqrt(ray.x()*ray.x()+ray.y()*ray.y()));
47 double rho = 1./ray.norm();
92 Point3 world_landmarkBefore(0,0,0);
94 Vector6 landmarkBefore =
values.
at<Vector6>(landmarkKey);
95 double x = landmarkBefore(0),
y = landmarkBefore(1),
z = landmarkBefore(2);
96 double theta = landmarkBefore(3), phi = landmarkBefore(4), rho = landmarkBefore(5);
99 Point3 world_landmarkAfter(0,0,0);
101 Vector6 landmarkAfter =
result.
at<Vector6>(landmarkKey);
102 double x = landmarkAfter(0),
y = landmarkAfter(1),
z = landmarkAfter(2);
103 double theta = landmarkAfter(3), phi = landmarkAfter(4), rho = landmarkAfter(5);
static int runAllTests(TestResult &result)
std::shared_ptr< This > shared_ptr
PinholeCamera< Cal3_S2 > camera1(pose1, *sharedCal)
virtual const Values & optimize()
TEST(InvDepthFactorVariant1, optimize)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Jet< T, N > sin(const Jet< T, N > &f)
#define EXPECT(condition)
int optimize(const SfmData &db, const NonlinearFactorGraph &graph, const Values &initial, bool separateCalibration=false)
The most common 5DOF 3D->2D calibration.
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
static const SmartProjectionParams params
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose={}, OptionalJacobian< 2, 3 > Dpoint={}, OptionalJacobian< 2, DimK > Dcal={}) const
project a 3D point from world coordinates into the image
Jet< T, N > cos(const Jet< T, N > &f)
static const double sigma
const ValueType at(Key j) const
const Point3 & translation(OptionalJacobian< 3, 6 > Hself={}) const
get translation
static Point3 landmark(0, 0, 5)
Base class for all pinhole cameras.
void insert(Key j, const Vector &value)
noiseModel::Base::shared_ptr SharedNoiseModel
std::shared_ptr< Cal3_S2 > shared_ptr
Inverse Depth Factor based on Civera09tro, Montiel06rss. Landmarks are parameterized as (x,...
AnnoyingScalar atan2(const AnnoyingScalar &y, const AnnoyingScalar &x)
static Key poseKey2(X(2))
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
Factor Graph consisting of non-linear factors.
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
The most common 5DOF 3D->2D calibration.
Class retract(const TangentVector &v) const
retract as required by manifold concept: applies v at *this
static Key poseKey1(X(1))
NonlinearFactorGraph graph
std::uint64_t Key
Integer nonlinear key type.
static const Camera2 camera2(pose1, K2)
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Jet< T, N > sqrt(const Jet< T, N > &f)
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:07:44