CombinedImuFactorExample.py
Go to the documentation of this file.
1 """
2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation,
3 Atlanta, Georgia 30332-0415
4 All Rights Reserved
5 
6 See LICENSE for the license information
7 
8 A script validating and demonstrating inference with the CombinedImuFactor.
9 
10 Author: Varun Agrawal
11 """
12 
13 # pylint: disable=no-name-in-module,unused-import,arguments-differ,import-error,wrong-import-order
14 
15 from __future__ import print_function
16 
17 import argparse
18 import math
19 
20 import matplotlib.pyplot as plt
21 import numpy as np
22 from gtsam.symbol_shorthand import B, V, X
23 from gtsam.utils.plot import plot_pose3
24 from mpl_toolkits.mplot3d import Axes3D
25 from PreintegrationExample import POSES_FIG, PreintegrationExample
26 
27 import gtsam
28 
29 GRAVITY = 9.81
30 
31 np.set_printoptions(precision=3, suppress=True)
32 
33 
34 def parse_args() -> argparse.Namespace:
35  """Parse command line arguments."""
36  parser = argparse.ArgumentParser("CombinedImuFactorExample.py")
37  parser.add_argument("--twist_scenario",
38  default="sick_twist",
39  choices=("zero_twist", "forward_twist", "loop_twist",
40  "sick_twist"))
41  parser.add_argument("--time",
42  "-T",
43  default=12,
44  type=int,
45  help="Total navigation time in seconds")
46  parser.add_argument("--compute_covariances",
47  default=False,
48  action='store_true')
49  parser.add_argument("--verbose", default=False, action='store_true')
50  return parser.parse_args()
51 
52 
54  """Class to run example of the Imu Factor."""
55  def __init__(self, twist_scenario: str = "sick_twist"):
56  self.velocity = np.array([2, 0, 0])
60 
61  # Choose one of these twists to change scenario:
62  twist_scenarios = dict(
63  zero_twist=(np.zeros(3), np.zeros(3)),
64  forward_twist=(np.zeros(3), self.velocity),
65  loop_twist=(np.array([0, -math.radians(30), 0]), self.velocity),
66  sick_twist=(np.array([math.radians(30), -math.radians(30),
67  0]), self.velocity))
68 
69  accBias = np.array([-0.3, 0.1, 0.2])
70  gyroBias = np.array([0.1, 0.3, -0.1])
71  bias = gtsam.imuBias.ConstantBias(accBias, gyroBias)
72 
74 
75  # Some arbitrary noise sigmas
76  gyro_sigma = 1e-3
77  accel_sigma = 1e-3
78  I_3x3 = np.eye(3)
79  params.setGyroscopeCovariance(gyro_sigma**2 * I_3x3)
80  params.setAccelerometerCovariance(accel_sigma**2 * I_3x3)
81  params.setIntegrationCovariance(1e-7**2 * I_3x3)
82 
83  dt = 1e-2
84  super(CombinedImuFactorExample,
85  self).__init__(twist_scenarios[twist_scenario], bias, params, dt)
86 
87  def addPrior(self, i: int, graph: gtsam.NonlinearFactorGraph):
88  """Add a prior on the navigation state at time `i`."""
89  state = self.scenario.navState(i)
90  graph.push_back(
91  gtsam.PriorFactorPose3(X(i), state.pose(), self.priorNoise))
92  graph.push_back(
93  gtsam.PriorFactorVector(V(i), state.velocity(), self.velNoise))
94  graph.push_back(
95  gtsam.PriorFactorConstantBias(B(i), self.actualBias,
96  self.biasNoise))
97 
98  def optimize(self, graph: gtsam.NonlinearFactorGraph,
99  initial: gtsam.Values):
100  """Optimize using Levenberg-Marquardt optimization."""
102  params.setVerbosityLM("SUMMARY")
103  optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params)
104  result = optimizer.optimize()
105  return result
106 
107  def plot(self,
108  values: gtsam.Values,
109  title: str = "Estimated Trajectory",
110  fignum: int = POSES_FIG + 1,
111  show: bool = False):
112  """
113  Plot poses in values.
114 
115  Args:
116  values: The values object with the poses to plot.
117  title: The title of the plot.
118  fignum: The matplotlib figure number.
119  POSES_FIG is a value from the PreintegrationExample
120  which we simply increment to generate a new figure.
121  show: Flag indicating whether to display the figure.
122  """
123  i = 0
124  while values.exists(X(i)):
125  pose_i = values.atPose3(X(i))
126  plot_pose3(fignum, pose_i, 1)
127  i += 1
128  plt.title(title)
129 
131 
132  i = 0
133  while values.exists(B(i)):
134  print("Bias Value {0}".format(i), values.atConstantBias(B(i)))
135  i += 1
136 
137  plt.ioff()
138 
139  if show:
140  plt.show()
141 
142  def run(self,
143  T: int = 12,
144  compute_covariances: bool = False,
145  verbose: bool = True):
146  """
147  Main runner.
148 
149  Args:
150  T: Total trajectory time.
151  compute_covariances: Flag indicating whether to compute marginal covariances.
152  verbose: Flag indicating if printing should be verbose.
153  """
155 
156  # initialize data structure for pre-integrated IMU measurements
158  self.actualBias)
159 
160  num_poses = T # assumes 1 factor per second
161  initial = gtsam.Values()
162 
163  # simulate the loop
164  i = 0 # state index
165  initial_state_i = self.scenario.navState(0)
166  initial.insert(X(i), initial_state_i.pose())
167  initial.insert(V(i), initial_state_i.velocity())
168  initial.insert(B(i), self.actualBias)
169 
170  # add prior on beginning
171  self.addPrior(0, graph)
172 
173  for k, t in enumerate(np.arange(0, T, self.dt)):
174  # get measurements and add them to PIM
175  measuredOmega = self.runner.measuredAngularVelocity(t)
176  measuredAcc = self.runner.measuredSpecificForce(t)
177  pim.integrateMeasurement(measuredAcc, measuredOmega, self.dt)
178 
179  # Plot IMU many times
180  if k % 10 == 0:
181  self.plotImu(t, measuredOmega, measuredAcc)
182 
183  if (k + 1) % int(1 / self.dt) == 0:
184  # Plot every second
185  self.plotGroundTruthPose(t, scale=1)
186  plt.title("Ground Truth Trajectory")
187 
188  # create IMU factor every second
189  factor = gtsam.CombinedImuFactor(X(i), V(i), X(i + 1),
190  V(i + 1), B(i), B(i + 1), pim)
191  graph.push_back(factor)
192 
193  if verbose:
194  print(factor)
195  print("Predicted state at {0}:\n{1}".format(
196  t + self.dt,
197  pim.predict(initial_state_i, self.actualBias)))
198 
199  pim.resetIntegration()
200 
201  rotationNoise = gtsam.Rot3.Expmap(np.random.randn(3) * 0.1)
202  translationNoise = gtsam.Point3(*np.random.randn(3) * 1)
203  poseNoise = gtsam.Pose3(rotationNoise, translationNoise)
204 
205  actual_state_i = self.scenario.navState(t + self.dt)
206  print("Actual state at {0}:\n{1}".format(
207  t + self.dt, actual_state_i))
208 
209  # Set initial state to current
210  initial_state_i = actual_state_i
211 
212  noisy_state_i = gtsam.NavState(
213  actual_state_i.pose().compose(poseNoise),
214  actual_state_i.velocity() + np.random.randn(3) * 0.1)
215  noisy_bias_i = self.actualBias + gtsam.imuBias.ConstantBias(
216  np.random.randn(3) * 0.1,
217  np.random.randn(3) * 0.1)
218 
219  initial.insert(X(i + 1), noisy_state_i.pose())
220  initial.insert(V(i + 1), noisy_state_i.velocity())
221  initial.insert(B(i + 1), noisy_bias_i)
222  i += 1
223 
224  # add priors on end
225  self.addPrior(num_poses - 1, graph)
226 
227  initial.print("Initial values:")
228 
229  result = self.optimize(graph, initial)
230 
231  result.print("Optimized values:")
232  print("------------------")
233  print("Initial Error =", graph.error(initial))
234  print("Final Error =", graph.error(result))
235  print("------------------")
236 
237  if compute_covariances:
238  # Calculate and print marginal covariances
239  marginals = gtsam.Marginals(graph, result)
240  print("Covariance on bias:\n",
241  marginals.marginalCovariance(BIAS_KEY))
242  for i in range(num_poses):
243  print("Covariance on pose {}:\n{}\n".format(
244  i, marginals.marginalCovariance(X(i))))
245  print("Covariance on vel {}:\n{}\n".format(
246  i, marginals.marginalCovariance(V(i))))
247 
248  self.plot(result, show=True)
249 
250 
251 if __name__ == '__main__':
252  args = parse_args()
253 
254  CombinedImuFactorExample(args.twist_scenario).run(args.time,
255  args.compute_covariances,
256  args.verbose)
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
def plot_pose3
Definition: plot.py:436
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
Definition: Rot3.h:374
def set_axes_equal
Definition: plot.py:35
Double_ range(const Point2_ &p, const Point2_ &q)
Expression< T > compose(const Expression< T > &t1, const Expression< T > &t2)
std::string format(const std::string &str, const std::vector< std::string > &find, const std::vector< std::string > &replace)
Definition: pytypes.h:1924
Vector3 Point3
Definition: Point3.h:38
#define X
Definition: icosphere.cpp:20
static std::shared_ptr< PreintegrationCombinedParams > MakeSharedU(double g=9.81)
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)
Definition: NoiseModel.cpp:594


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:02