Removed EXPORT (Chris?)
parent
6b47b914b8
commit
02223e66fd
|
@ -72,22 +72,22 @@ typedef NoiseModelFactor1<Pose> NM1;
|
||||||
typedef NoiseModelFactor2<Pose,Pose> NM2;
|
typedef NoiseModelFactor2<Pose,Pose> NM2;
|
||||||
typedef BearingRangeFactor<Pose,Point2> BR;
|
typedef BearingRangeFactor<Pose,Point2> BR;
|
||||||
|
|
||||||
GTSAM_VALUE_EXPORT(Value);
|
//GTSAM_VALUE_EXPORT(Value);
|
||||||
GTSAM_VALUE_EXPORT(Pose);
|
//GTSAM_VALUE_EXPORT(Pose);
|
||||||
GTSAM_VALUE_EXPORT(Rot2);
|
//GTSAM_VALUE_EXPORT(Rot2);
|
||||||
GTSAM_VALUE_EXPORT(Point2);
|
//GTSAM_VALUE_EXPORT(Point2);
|
||||||
GTSAM_VALUE_EXPORT(NonlinearFactor);
|
//GTSAM_VALUE_EXPORT(NonlinearFactor);
|
||||||
GTSAM_VALUE_EXPORT(NoiseModelFactor);
|
//GTSAM_VALUE_EXPORT(NoiseModelFactor);
|
||||||
GTSAM_VALUE_EXPORT(NM1);
|
//GTSAM_VALUE_EXPORT(NM1);
|
||||||
GTSAM_VALUE_EXPORT(NM2);
|
//GTSAM_VALUE_EXPORT(NM2);
|
||||||
GTSAM_VALUE_EXPORT(BetweenFactor<Pose>);
|
//GTSAM_VALUE_EXPORT(BetweenFactor<Pose>);
|
||||||
GTSAM_VALUE_EXPORT(PriorFactor<Pose>);
|
//GTSAM_VALUE_EXPORT(PriorFactor<Pose>);
|
||||||
GTSAM_VALUE_EXPORT(BR);
|
//GTSAM_VALUE_EXPORT(BR);
|
||||||
GTSAM_VALUE_EXPORT(noiseModel::Base);
|
//GTSAM_VALUE_EXPORT(noiseModel::Base);
|
||||||
GTSAM_VALUE_EXPORT(noiseModel::Isotropic);
|
//GTSAM_VALUE_EXPORT(noiseModel::Isotropic);
|
||||||
GTSAM_VALUE_EXPORT(noiseModel::Gaussian);
|
//GTSAM_VALUE_EXPORT(noiseModel::Gaussian);
|
||||||
GTSAM_VALUE_EXPORT(noiseModel::Diagonal);
|
//GTSAM_VALUE_EXPORT(noiseModel::Diagonal);
|
||||||
GTSAM_VALUE_EXPORT(noiseModel::Unit);
|
//GTSAM_VALUE_EXPORT(noiseModel::Unit);
|
||||||
|
|
||||||
double chi2_red(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& config) {
|
double chi2_red(const gtsam::NonlinearFactorGraph& graph, const gtsam::Values& config) {
|
||||||
// Compute degrees of freedom (observations - variables)
|
// Compute degrees of freedom (observations - variables)
|
||||||
|
@ -295,7 +295,7 @@ void runIncremental()
|
||||||
NonlinearFactorGraph newFactors;
|
NonlinearFactorGraph newFactors;
|
||||||
Values newVariables;
|
Values newVariables;
|
||||||
|
|
||||||
newFactors.push_back(boost::make_shared<PriorFactor<Pose> >(firstPose, Pose(), noiseModel::Unit::Create(Pose::Dim())));
|
newFactors.push_back(boost::make_shared<PriorFactor<Pose> >(firstPose, Pose(), noiseModel::Unit::Create(3)));
|
||||||
newVariables.insert(firstPose, Pose());
|
newVariables.insert(firstPose, Pose());
|
||||||
|
|
||||||
isam2.update(newFactors, newVariables);
|
isam2.update(newFactors, newVariables);
|
||||||
|
@ -474,7 +474,7 @@ void runBatch()
|
||||||
cout << "Creating batch optimizer..." << endl;
|
cout << "Creating batch optimizer..." << endl;
|
||||||
|
|
||||||
NonlinearFactorGraph measurements = datasetMeasurements;
|
NonlinearFactorGraph measurements = datasetMeasurements;
|
||||||
measurements.push_back(boost::make_shared<PriorFactor<Pose> >(0, Pose(), noiseModel::Unit::Create(Pose::Dim())));
|
measurements.push_back(boost::make_shared<PriorFactor<Pose> >(0, Pose(), noiseModel::Unit::Create(3)));
|
||||||
|
|
||||||
gttic_(Create_optimizer);
|
gttic_(Create_optimizer);
|
||||||
GaussNewtonParams params;
|
GaussNewtonParams params;
|
||||||
|
|
Loading…
Reference in New Issue