2 ImuFactor example with iSAM2. 3 Authors: Robert Truax (C++), Frank Dellaert, Varun Agrawal (Python) 7 from __future__
import print_function
11 import matplotlib.pyplot
as plt
13 from mpl_toolkits.mplot3d
import Axes3D
16 from gtsam
import (ISAM2, BetweenFactorConstantBias, Cal3_S2,
17 ConstantTwistScenario, ImuFactor, NonlinearFactorGraph,
18 PinholeCameraCal3_S2, Point3, Pose3,
19 PriorFactorConstantBias, PriorFactorPose3,
20 PriorFactorVector, Rot3, Values)
26 """Create 3d double numpy array.""" 27 return np.array([x, y, z], dtype=float)
39 PARAMS.setAccelerometerCovariance(I * 0.1)
40 PARAMS.setGyroscopeCovariance(I * 0.1)
41 PARAMS.setIntegrationCovariance(I * 0.1)
42 PARAMS.setUse2ndOrderCoriolis(
False)
43 PARAMS.setOmegaCoriolis(
vector3(0, 0, 0))
46 DELTA =
Pose3(Rot3.Rodrigues(0, 0, 0),
47 Point3(0.05, -0.10, 0.20))
49 return PARAMS, BIAS_COVARIANCE, DELTA
54 target = Point3(0, 0, 0)
55 position = Point3(radius, 0, 0)
56 camera = PinholeCameraCal3_S2.Lookat(position, target, up,
Cal3_S2())
61 """Create the set of ground-truth landmarks and poses""" 62 angular_velocity_vector =
vector3(0, -angular_velocity, 0)
63 linear_velocity_vector =
vector3(radius * angular_velocity, 0, 0)
65 angular_velocity_vector, linear_velocity_vector, pose_0)
71 """Run iSAM 2 example with IMU factor.""" 76 pose_0 = camera.pose()
79 angular_velocity = math.radians(180)
80 scenario =
get_scenario(radius, pose_0, angular_velocity, delta_t)
97 np.array([0.1, 0.1, 0.1, 0.3, 0.3, 0.3]))
98 graph.push_back(PriorFactorPose3(
X(0), pose_0, noise))
105 graph.push_back(biasprior)
110 n_velocity =
vector3(0, angular_velocity * radius, 0)
111 velprior = PriorFactorVector(
V(0), n_velocity, velnoise)
112 graph.push_back(velprior)
113 initialEstimate.insert(
V(0), n_velocity)
121 pose_1 = scenario.pose(delta_t)
122 initialEstimate.insert(
X(0), pose_0.compose(DELTA))
123 initialEstimate.insert(
X(1), pose_1.compose(DELTA))
125 pose_i = scenario.pose(t)
126 initialEstimate.insert(
X(i), pose_i.compose(DELTA))
132 factor = BetweenFactorConstantBias(
138 nRb = scenario.rotation(t).
matrix()
139 bRn = np.transpose(nRb)
140 measuredAcc = scenario.acceleration_b(t) - np.dot(bRn, n_gravity)
141 measuredOmega = scenario.omega_b(t)
142 accum.integrateMeasurement(measuredAcc, measuredOmega, delta_t)
145 imufac =
ImuFactor(
X(i - 1),
V(i - 1),
X(i),
V(i), biasKey, accum)
149 initialEstimate.insert(
V(i), n_velocity)
150 accum.resetIntegration()
153 isam.update(graph, initialEstimate)
154 result = isam.calculateEstimate()
155 plot.plot_incremental_trajectory(0, result,
156 start=i, scale=3, time_interval=0.01)
160 initialEstimate.clear()
165 if __name__ ==
'__main__':
def preintegration_parameters()
static shared_ptr Variance(size_t dim, double variance, bool smart=true)
The most common 5DOF 3D->2D calibration.
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Double_ range(const Point2_ &p, const Point2_ &q)
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
static std::shared_ptr< PreintegrationParams > MakeSharedU(double g=9.81)
def get_scenario(radius, pose_0, angular_velocity, delta_t)
static shared_ptr Sigma(size_t dim, double sigma, bool smart=true)