Main Page
Related Pages
Modules
Namespaces
Classes
Files
Examples
File List
File Members
python
gtsam
examples
GPSFactorExample.py
Go to the documentation of this file.
1
"""
2
GTSAM Copyright 2010-2018, Georgia Tech Research Corporation,
3
Atlanta, Georgia 30332-0415
4
All Rights Reserved
5
Authors: Frank Dellaert, et al. (see THANKS for the full author list)
6
7
See LICENSE for the license information
8
9
Simple robot motion example, with prior and one GPS measurements
10
Author: Mandy Xie
11
"""
12
# pylint: disable=invalid-name, E1101
13
14
from
__future__
import
print_function
15
16
import
numpy
as
np
17
18
import
gtsam
19
20
import
matplotlib.pyplot
as
plt
21
import
gtsam.utils.plot
as
gtsam_plot
22
23
# ENU Origin is where the plane was in hold next to runway
24
lat0 = 33.86998
25
lon0 = -84.30626
26
h0 = 274
27
28
# Create noise models
29
GPS_NOISE =
gtsam.noiseModel.Isotropic.Sigma
(3, 0.1)
30
PRIOR_NOISE =
gtsam.noiseModel.Isotropic.Sigma
(6, 0.25)
31
32
# Create an empty nonlinear factor graph
33
graph =
gtsam.NonlinearFactorGraph
()
34
35
# Add a prior on the first point, setting it to the origin
36
# A prior factor consists of a mean and a noise model (covariance matrix)
37
priorMean =
gtsam.Pose3
()
# prior at origin
38
graph.add(gtsam.PriorFactorPose3(1, priorMean, PRIOR_NOISE))
39
40
# Add GPS factors
41
gps =
gtsam.Point3
(lat0, lon0, h0)
42
graph.add(
gtsam.GPSFactor
(1, gps, GPS_NOISE))
43
print
(
"\nFactor Graph:\n{}"
.format(graph))
44
45
# Create the data structure to hold the initialEstimate estimate to the solution
46
# For illustrative purposes, these have been deliberately set to incorrect values
47
initial =
gtsam.Values
()
48
initial.insert(1,
gtsam.Pose3
())
49
print
(
"\nInitial Estimate:\n{}"
.format(initial))
50
51
# optimize using Levenberg-Marquardt optimization
52
params =
gtsam.LevenbergMarquardtParams
()
53
optimizer =
gtsam.LevenbergMarquardtOptimizer
(graph, initial, params)
54
result = optimizer.optimize()
55
print
(
"\nFinal Result:\n{}"
.format(result))
56
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition:
Matrix.cpp:155
gtsam::LevenbergMarquardtParams
Definition:
LevenbergMarquardtParams.h:35
gtsam.utils.plot
Definition:
plot.py:1
gtsam::LevenbergMarquardtOptimizer
Definition:
LevenbergMarquardtOptimizer.h:35
gtsam::Values
Definition:
Values.h:71
gtsam::NonlinearFactorGraph
Definition:
NonlinearFactorGraph.h:78
gtsam::Point3
Vector3 Point3
Definition:
Point3.h:35
gtsam::Pose3
Definition:
Pose3.h:37
gtsam::GPSFactor
Definition:
GPSFactor.h:35
gtsam::noiseModel::Isotropic::Sigma
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition:
NoiseModel.cpp:567
gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:09