17 using namespace gtsam;
24 int main(
int argc,
char* argv[]) {
27 auto measurementNoise =
28 noiseModel::Isotropic::Sigma(2, 1.0);
31 sigmas << Vector3::Constant(0.1), Vector3::Constant(0.3);
32 auto noise = noiseModel::Diagonal::Sigmas(sigmas);
69 for (
size_t i = 1;
i < 5;
i++) {
70 cout <<
"****************************************************" << endl;
71 cout <<
"i = " <<
i << endl;
80 cout <<
"Measurement " << i <<
"" << measurement << endl;
83 smartFactor->add(measurement,
X(i));
89 cout <<
"Detailed results:" << endl;
90 for (
auto keyedStatus : result.
detail->variableStatus) {
91 const auto& status = keyedStatus.second;
94 cout <<
"reeliminated: " << status.isReeliminated << endl;
95 cout <<
"relinearized above thresh: " << status.isAboveRelinThreshold
97 cout <<
"relinearized involved: " << status.isRelinearizeInvolved << endl;
98 cout <<
"relinearized: " << status.isRelinearized << endl;
99 cout <<
"observed: " << status.isObserved << endl;
100 cout <<
"new: " << status.isNew << endl;
101 cout <<
"in the root clique: " << status.inRootClique << endl;
106 currentEstimate.
print(
"Current estimate: ");
108 boost::optional<Point3> pointEstimate = smartFactor->point(currentEstimate);
110 cout << *pointEstimate << endl;
112 cout <<
"Point degenerate." << endl;
117 initialEstimate.
clear();
Smart factor on poses, assuming camera calibration is fixed.
static Point2 project(const Pose3 &pose, const Unit3 &pointAtInfinity, const Cal3_S2::shared_ptr &cal)
void insert(Key j, const Value &val)
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
NonlinearFactorGraph graph
T compose(const T &t1, const T &t2)
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
Values calculateEstimate() const
Base class for all pinhole cameras.
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
SmartProjectionPoseFactor< Cal3_S2 > SmartFactor
static Pose3 pose3(rt3, pt3)
NonlinearISAM isam(relinearizeInterval)
void print(const std::string &str="") const
print iSAM2 parameters
static ConjugateGradientParameters parameters
static const Pose3 pose1(Rot3(), Point3(0, 1, 0.5))
RelinearizationThreshold relinearizeThreshold
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Point2 project(const Point3 &pw, OptionalJacobian< 2, 6 > Dpose=boost::none, OptionalJacobian< 2, 3 > Dpoint=boost::none, OptionalJacobian< 2, DimK > Dcal=boost::none) const
project a 3D point from world coordinates into the image
void print(const std::string str="") const
Print results.
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const boost::optional< FastMap< Key, int > > &constrainedKeys=boost::none, const boost::optional< FastList< Key > > &noRelinKeys=boost::none, const boost::optional< FastList< Key > > &extraReelimKeys=boost::none, bool force_relinearize=false)
void PrintKey(Key key, const string &s, const KeyFormatter &keyFormatter)
Utility function to print one key with optional prefix.
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
static const CalibratedCamera camera(kDefaultPose)
bool enableDetailedResults
boost::shared_ptr< Cal3_S2 > shared_ptr
boost::optional< DetailedResults > detail
The most common 5DOF 3D->2D calibration.
bool cacheLinearizedFactors
int main(int argc, char *argv[])