Functions | Variables
SimpleRotation.cpp File Reference

This is a super-simple example of optimizing a single rotation according to a single prior. More...

#include <gtsam/geometry/Rot2.h>
#include <gtsam/inference/Symbol.h>
#include <gtsam/nonlinear/NonlinearFactorGraph.h>
#include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
Include dependency graph for SimpleRotation.cpp:

Go to the source code of this file.

Functions

int main ()
 

Variables

const double degree = M_PI / 180
 

Detailed Description

This is a super-simple example of optimizing a single rotation according to a single prior.

Date
Jul 1, 2010
Author
Frank Dellaert
Alex Cunningham

Definition in file SimpleRotation.cpp.

Function Documentation

◆ main()

int main ( )

Step 1: Create a factor to express a unary constraint The "prior" in this case is the measurement from a sensor, with a model of the noise on the measurement.

The "Key" created here is a label used to associate parts of the state (stored in "RotValues") with particular factors. They require an index to allow for lookup, and should be unique.

In general, creating a factor requires:

  • A key or set of keys labeling the variables that are acted upon
  • A measurement value
  • A measurement model with the correct dimensionality for the factor

    Step 2: Create a graph container and add the factor to it Before optimizing, all factors need to be added to a Graph container, which provides the necessary top-level functionality for defining a system of constraints.

In this case, there is only one factor, but in a practical scenario, many more factors would be added.

Step 3: Create an initial estimate An initial estimate of the solution for the system is necessary to start optimization. This system state is the "RotValues" structure, which is similar in structure to a STL map, in that it maps keys (the label created in step 1) to specific values.

The initial estimate provided to optimization will be used as a linearization point for optimization, so it is important that all of the variables in the graph have a corresponding value in this structure.

The interface to all RotValues types is the same, it only depends on the type of key used to find the appropriate value map if there are multiple types of variables.

Step 4: Optimize After formulating the problem with a graph of constraints and an initial estimate, executing optimization is as simple as calling a general optimization function with the graph and initial estimate. This will yield a new RotValues structure with the final state of the optimization.

Definition at line 61 of file SimpleRotation.cpp.

Variable Documentation

◆ degree

const double degree = M_PI / 180

Definition at line 59 of file SimpleRotation.cpp.



gtsam
Author(s):
autogenerated on Thu Dec 19 2024 04:08:41