Go to the documentation of this file.
   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;
 
  120   initialEstimate.
print(
"Initial Estimate:\n");
 
  
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
virtual const Values & optimize()
int main(int argc, char **argv)
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Matrix marginalCovariance(Key variable) const
Pose3 x3(Rot3::Ypr(M_PI/4.0, 0.0, 0.0), l2)
Pose2 odometry(2.0, 0.0, 0.0)
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
A class for computing marginals in a NonlinearFactorGraph.
Factor Graph consisting of non-linear factors.
void insert(Key j, const Value &val)
NonlinearFactorGraph graph
Marginals marginals(graph, result)
Pose3 x2(Rot3::Ypr(0.0, 0.0, 0.0), l2)
Jet< T, N > sqrt(const Jet< T, N > &f)
A non-templated config holding any types of Manifold-group elements.
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
a single factor contains both the bearing and the range to prevent handle to pair bearing and range f...
void print(const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
gtsam
Author(s): 
autogenerated on Wed May 28 2025 03:02:35