2 GTSAM Copyright 2010, Georgia Tech Research Corporation, 3 Atlanta, Georgia 30332-0415 5 Authors: Frank Dellaert, et al. (see THANKS for the full author list) 7 See LICENSE for the license information 9 This example will perform a relatively trivial optimization on 10 a single variable with a single factor. 19 Step 1: Create a factor to express a unary constraint 21 The "prior" in this case is the measurement from a sensor, 22 with a model of the noise on the measurement. 24 The "Key" created here is a label used to associate parts of the 25 state (stored in "RotValues") with particular factors. They require 26 an index to allow for lookup, and should be unique. 28 In general, creating a factor requires: 29 - A key or set of keys labeling the variables that are acted upon 31 - A measurement model with the correct dimensionality for the factor 34 prior.print(
'goal angle')
37 factor = gtsam.PriorFactorRot2(key, prior, model)
40 Step 2: Create a graph container and add the factor to it 42 Before optimizing, all factors need to be added to a Graph container, 43 which provides the necessary top-level functionality for defining a 44 system of constraints. 46 In this case, there is only one factor, but in a practical scenario, 47 many more factors would be added. 50 graph.push_back(factor)
51 graph.print(
'full graph')
54 Step 3: Create an initial estimate 56 An initial estimate of the solution for the system is necessary to 57 start optimization. This system state is the "Values" instance, 58 which is similar in structure to a dictionary, in that it maps 59 keys (the label created in step 1) to specific values. 61 The initial estimate provided to optimization will be used as 62 a linearization point for optimization, so it is important that 63 all of the variables in the graph have a corresponding value in 68 initial.print(
'initial estimate')
73 After formulating the problem with a graph of constraints 74 and an initial estimate, executing optimization is as simple 75 as calling a general optimization function with the graph and 76 initial estimate. This will yield a new RotValues structure 77 with the final state of the optimization. 80 result.print(
'final result')
83 if __name__ ==
'__main__':
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
static Rot2 fromAngle(double theta)
Named constructor from angle in radians.
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)