69 using namespace gtsam;
71 int main(
int argc,
char** argv) {
82 auto priorNoise = noiseModel::Diagonal::Sigmas(
96 auto measurementNoise = noiseModel::Diagonal::Sigmas(
99 Rot2 bearing11 = Rot2::fromDegrees(45), bearing21 = Rot2::fromDegrees(90),
100 bearing32 = Rot2::fromDegrees(90);
101 double range11 =
std::sqrt(4.0 + 4.0), range21 = 2.0, range32 = 2.0;
109 graph.
print(
"Factor Graph:\n");
120 initialEstimate.
print(
"Initial Estimate:\n");
130 result.
print(
"Final Result:\n");
Matrix marginalCovariance(Key variable) const
virtual const Values & optimize()
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
Point2 prior(const Point2 &x)
Prior on a single pose.
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
NonlinearFactorGraph graph
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
void print(const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
void insert(Key j, const Value &val)
A class for computing marginals in a NonlinearFactorGraph.
Jet< T, N > sqrt(const Jet< T, N > &f)
Pose2 odometry(2.0, 0.0, 0.0)
Marginals marginals(graph, result)
int main(int argc, char **argv)