22 using namespace gtsam;
30 auto gaussian = noiseModel::Diagonal::Sigmas(
31 (
Vector(6) << Vector3::Constant(5.0
e-2), Vector3::Constant(5.0
e-3))
33 auto huber = noiseModel::Robust::Create(
34 noiseModel::mEstimator::Huber::Create(1.345), gaussian);
36 biasNoiseModel = huber;
40 auto gaussian = noiseModel::Isotropic::Sigma(3, 0.01);
41 auto huber = noiseModel::Robust::Create(
42 noiseModel::mEstimator::Huber::Create(1.345), gaussian);
44 velocityNoiseModel = huber;
48 auto p = boost::make_shared<PreintegratedCombinedMeasurements::Params>(
51 p->accelerometerCovariance =
52 I_3x3 *
pow(0.0565, 2.0);
53 p->integrationCovariance =
55 p->gyroscopeCovariance =
56 I_3x3 *
pow(4.0e-5, 2.0);
57 p->biasAccCovariance = I_3x3 *
pow(0.00002, 2.0);
58 p->biasOmegaCovariance =
59 I_3x3 *
pow(0.001, 2.0);
60 p->biasAccOmegaInt = Matrix::Identity(6, 6) * 1e-5;
63 Rot3 iRb(0.036129, -0.998727, 0.035207,
64 0.045417, -0.033553, -0.998404,
65 0.998315, 0.037670, 0.044147);
68 Point3 iTb(0.03, -0.025, -0.06);
71 p->body_P_sensor =
Pose3(iRb, iTb);
76 Vector3 acc_bias(0.0, -0.0942015, 0.0);
77 Vector3 gyro_bias(-0.00527483, -0.00757152, -0.00469968);
82 propState = prevState;
83 prevBias = priorImuBias;
97 int main(
int argc,
char* argv[]) {
99 cout <<
"./ISAM2_SmartFactorStereo_IMU [data.txt]\n";
103 ifstream in(argv[1]);
106 cerr <<
"error opening: " << argv[1] <<
"\n";
124 std::map<size_t, SmartStereoProjectionPoseFactor::shared_ptr> smartFactors;
130 auto priorPoseNoise = noiseModel::Diagonal::Sigmas(
131 (
Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.1)).finished());
132 graph.
addPrior(
X(1), Pose3::identity(), priorPoseNoise);
133 initialEstimate.
insert(
X(0), Pose3::identity());
150 in.getline(line,
sizeof(line));
151 stringstream
ss(line);
157 if (frame != lastFrame || in.eof()) {
158 cout <<
"Running iSAM for frame: " << lastFrame <<
"\n";
160 initialEstimate.
insert(
X(lastFrame), Pose3::identity());
165 X(lastFrame),
V(lastFrame),
B(lastFrame - 1),
168 graph.
add(imuFactor);
170 isam.
update(graph, initialEstimate);
181 initialEstimate.
clear();
191 double dt = 1 / 800.0;
205 }
else if (type ==
's') {
214 if (smartFactors.count(landmark) == 0) {
215 auto gaussian = noiseModel::Isotropic::Sigma(3, 1.0);
226 throw runtime_error(
"unexpected data type: " +
string(1, type));
void insert(Key j, const Value &val)
imuBias::ConstantBias prevBias
boost::shared_ptr< Robust > shared_ptr
void integrateMeasurement(const Vector3 &measuredAcc, const Vector3 &measuredOmega, const double dt) override
static Cal3_S2 K(500, 500, 0.1, 640/2, 480/2)
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
IsDerived< DERIVEDFACTOR > add(boost::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
NonlinearFactorGraph graph
Matrix< SCALARB, Dynamic, Dynamic > B
Smart stereo factor on poses, assuming camera calibration is fixed.
static Point3 landmark(0, 0, 5)
NavState predict(const NavState &state_i, const imuBias::ConstantBias &bias_i, OptionalJacobian< 9, 9 > H1=boost::none, OptionalJacobian< 9, 6 > H2=boost::none) const
Predict state at time j.
void addPrior(Key key, const T &prior, const SharedNoiseModel &model=nullptr)
noiseModel::Robust::shared_ptr biasNoiseModel
Values calculateEstimate() const
boost::shared_ptr< Cal3_S2Stereo > shared_ptr
const ValueType at(Key j) const
void resetIntegrationAndSetBias(const Bias &biasHat)
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
NonlinearISAM isam(relinearizeInterval)
static SmartStereoProjectionParams params
static ConjugateGradientParameters parameters
static std::stringstream ss
RelinearizationThreshold relinearizeThreshold
PreintegratedCombinedMeasurements * preintegrated
boost::shared_ptr< This > shared_ptr
shorthand for a smart pointer to a factor
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const boost::optional< FastMap< Key, int > > &constrainedKeys=boost::none, const boost::optional< FastList< Key > > &noRelinKeys=boost::none, const boost::optional< FastList< Key > > &extraReelimKeys=boost::none, bool force_relinearize=false)
imuBias::ConstantBias priorImuBias
Jet< T, N > pow(const Jet< T, N > &f, double g)
int main(int argc, char *argv[])
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
noiseModel::Robust::shared_ptr velocityNoiseModel