2 from gtsam
import symbol
6 """ Options for visual isam example. """ 19 if options.alwaysRelinearize:
20 params.relinearizeSkip = 1
30 if options.hardConstraint:
32 gtsam.NonlinearEqualityPose3(ii, truth.cameras[0].
pose()))
35 gtsam.PriorFactorPose3(ii, truth.cameras[i].
pose(),
36 data.noiseModels.posePrior))
37 initialEstimates.insert(ii, truth.cameras[i].
pose())
49 gtsam.GenericProjectionFactorCal3_S2(data.Z[i][
50 k], data.noiseModels.measurement, ii, jj, data.K))
52 if not initialEstimates.exists(jj):
53 initialEstimates.insert(jj, truth.points[j])
54 if options.pointPriors:
56 gtsam.PriorFactorPoint3(jj, truth.points[j],
57 data.noiseModels.pointPrior))
61 gtsam.BetweenFactorPose3(
63 symbol(
'x', 1), data.odometry[1], data.noiseModels.odometry))
66 if options.batchInitialization:
69 fullyOptimized = batchOptimizer.optimize()
70 isam.update(newFactors, fullyOptimized)
72 isam.update(newFactors, initialEstimates)
76 result = isam.calculateEstimate()
79 return isam, result, nextPoseIndex
82 def step(data, isam, result, truth, currPoseIndex):
84 Do one step isam update 85 @param[in] data: measurement data (odometry and visual measurements and their noiseModels) 86 @param[in/out] isam: current isam object, will be updated 87 @param[in/out] result: current result object, will be updated 88 @param[in] truth: ground truth data, used to initialize new variables 89 @param[currPoseIndex]: index of the current pose 97 prevPoseIndex = currPoseIndex - 1
98 odometry = data.odometry[prevPoseIndex]
100 gtsam.BetweenFactorPose3(
101 symbol(
'x', prevPoseIndex),
102 symbol(
'x', currPoseIndex), odometry,
103 data.noiseModels.odometry))
106 for k
in range(
len(data.Z[currPoseIndex])):
107 zij = data.Z[currPoseIndex][k]
108 j = data.J[currPoseIndex][k]
111 gtsam.GenericProjectionFactorCal3_S2(
112 zij, data.noiseModels.measurement,
113 symbol(
'x', currPoseIndex), jj, data.K))
115 if not result.exists(jj)
and not initialEstimates.exists(jj):
116 lmInit = truth.points[j]
117 initialEstimates.insert(jj, lmInit)
120 prevPose = result.atPose3(
symbol(
'x', prevPoseIndex))
121 initialEstimates.insert(
122 symbol(
'x', currPoseIndex), prevPose.compose(odometry))
126 isam.update(newFactors, initialEstimates)
128 newResult = isam.calculateEstimate()
131 return isam, newResult
def step(data, isam, result, truth, currPoseIndex)
def initialize(data, truth, options)
Key symbol(unsigned char c, std::uint64_t j)
static const Pose3 pose(Rot3(Vector3(1, -1, -1).asDiagonal()), Point3(0, 0, 0.5))
Double_ range(const Point2_ &p, const Point2_ &q)
size_t len(handle h)
Get the length of a Python object.