2 GTSAM Copyright 2010-2019, Georgia Tech Research Corporation, 3 Atlanta, Georgia 30332-0415 6 See LICENSE for the license information 8 A script validating and demonstrating inference with the CombinedImuFactor. 15 from __future__
import print_function
20 import matplotlib.pyplot
as plt
24 from mpl_toolkits.mplot3d
import Axes3D
25 from PreintegrationExample
import POSES_FIG, PreintegrationExample
31 np.set_printoptions(precision=3, suppress=
True)
35 """Parse command line arguments.""" 36 parser = argparse.ArgumentParser(
"CombinedImuFactorExample.py")
37 parser.add_argument(
"--twist_scenario",
39 choices=(
"zero_twist",
"forward_twist",
"loop_twist",
41 parser.add_argument(
"--time",
45 help=
"Total navigation time in seconds")
46 parser.add_argument(
"--compute_covariances",
49 parser.add_argument(
"--verbose", default=
False, action=
'store_true')
50 return parser.parse_args()
54 """Class to run example of the Imu Factor.""" 55 def __init__(self, twist_scenario: str =
"sick_twist"):
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),
69 accBias = np.array([-0.3, 0.1, 0.2])
70 gyroBias = np.array([0.1, 0.3, -0.1])
79 params.setGyroscopeCovariance(gyro_sigma**2 * I_3x3)
80 params.setAccelerometerCovariance(accel_sigma**2 * I_3x3)
81 params.setIntegrationCovariance(1e-7**2 * I_3x3)
84 super(CombinedImuFactorExample,
85 self).
__init__(twist_scenarios[twist_scenario], bias, params, dt)
88 """Add a prior on the navigation state at time `i`.""" 91 gtsam.PriorFactorPose3(
X(i), state.pose(), self.
priorNoise))
93 gtsam.PriorFactorVector(
V(i), state.velocity(), self.
velNoise))
95 gtsam.PriorFactorConstantBias(B(i), self.
actualBias,
98 def optimize(self, graph: gtsam.NonlinearFactorGraph,
100 """Optimize using Levenberg-Marquardt optimization.""" 102 params.setVerbosityLM(
"SUMMARY")
104 result = optimizer.optimize()
108 values: gtsam.Values,
109 title: str =
"Estimated Trajectory",
110 fignum: int = POSES_FIG + 1,
113 Plot poses in values. 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. 124 while values.exists(
X(i)):
125 pose_i = values.atPose3(
X(i))
133 while values.exists(B(i)):
134 print(
"Bias Value {0}".
format(i), values.atConstantBias(B(i)))
144 compute_covariances: bool =
False,
145 verbose: bool =
True):
150 T: Total trajectory time. 151 compute_covariances: Flag indicating whether to compute marginal covariances. 152 verbose: Flag indicating if printing should be verbose. 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())
173 for k, t
in enumerate(np.arange(0, T, self.
dt)):
175 measuredOmega = self.
runner.measuredAngularVelocity(t)
176 measuredAcc = self.
runner.measuredSpecificForce(t)
177 pim.integrateMeasurement(measuredAcc, measuredOmega, self.
dt)
181 self.
plotImu(t, measuredOmega, measuredAcc)
183 if (k + 1) %
int(1 / self.
dt) == 0:
186 plt.title(
"Ground Truth Trajectory")
190 V(i + 1), B(i), B(i + 1), pim)
191 graph.push_back(factor)
197 pim.predict(initial_state_i, self.
actualBias)))
199 pim.resetIntegration()
202 translationNoise =
gtsam.Point3(*np.random.randn(3) * 1)
203 poseNoise =
gtsam.Pose3(rotationNoise, translationNoise)
205 actual_state_i = self.
scenario.navState(t + self.
dt)
207 t + self.
dt, actual_state_i))
210 initial_state_i = actual_state_i
213 actual_state_i.pose().
compose(poseNoise),
214 actual_state_i.velocity() + np.random.randn(3) * 0.1)
216 np.random.randn(3) * 0.1,
217 np.random.randn(3) * 0.1)
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)
227 initial.print(
"Initial values:")
229 result = self.
optimize(graph, initial)
231 result.print(
"Optimized values:")
232 print(
"------------------")
233 print(
"Initial Error =", graph.error(initial))
234 print(
"Final Error =", graph.error(result))
235 print(
"------------------")
237 if compute_covariances:
240 print(
"Covariance on bias:\n",
241 marginals.marginalCovariance(BIAS_KEY))
242 for i
in range(num_poses):
244 i, marginals.marginalCovariance(
X(i))))
246 i, marginals.marginalCovariance(
V(i))))
248 self.
plot(result, show=
True)
251 if __name__ ==
'__main__':
255 args.compute_covariances,
void print(const Matrix &A, const string &s, ostream &stream)
static Rot3 Expmap(const Vector3 &v, OptionalJacobian< 3, 3 > H={})
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)
static std::shared_ptr< PreintegrationCombinedParams > MakeSharedU(double g=9.81)
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)