Go to the documentation of this file.
32 using namespace gtsam;
33 using namespace gtsam::serializationTestHelpers;
71 template<
class T>
struct pack {
83 static Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0);
87 static Cal3DS2 cal2(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0);
90 TEST (Serialization, TemplatedValues) {
120 TEST(Serialization, NoiseModelFactor1_backwards_compatibility) {
123 noiseModel::Unit::Create(6));
127 roundtrip(factor, factor_deserialized_str_2);
130 #if !defined(GTSAM_USE_QUATERNIONS) && !defined(GTSAM_USE_TBB)
132 std::string serialized_str =
133 "22 serialization::archive 15 1 0\n"
134 "0 0 0 0 0 0 0 1 0 12345 0 1 6 21 gtsam_noiseModel_Unit 1 0\n"
137 "3 0 0 0 0 6 0 1 0 0 0 6 1.00000000000000000e+00 1.00000000000000000e+00 "
138 "1.00000000000000000e+00 1.00000000000000000e+00 1.00000000000000000e+00 "
139 "1.00000000000000000e+00 6 1.00000000000000000e+00 "
140 "1.00000000000000000e+00 1.00000000000000000e+00 1.00000000000000000e+00 "
141 "1.00000000000000000e+00 1.00000000000000000e+00 1.00000000000000000e+00 "
142 "1.00000000000000000e+00 0 0 0 0 4.11982245665682978e-01 "
143 "-8.33737651774156818e-01 -3.67630462924899259e-01 "
144 "-5.87266449276209815e-02 -4.26917621276207360e-01 "
145 "9.02381585483330806e-01 -9.09297426825681709e-01 "
146 "-3.50175488374014632e-01 -2.24845095366152908e-01 0 0 "
147 "4.00000000000000000e+00 5.00000000000000000e+00 "
148 "6.00000000000000000e+00\n";
151 deserializeFromString(serialized_str, factor_deserialized_str);
156 deserializeFromXMLFile(GTSAM_SOURCE_TREE_DATASET_DIR
157 "/../../gtsam/nonlinear/tests/priorFactor.xml",
158 factor_deserialized_xml);
168 initialValues.
clear();
170 gtsam::Vector6 temp6;
171 for (
int i = 0;
i < 6; ++
i) {
184 std::string binaryPath =
"saved_solver.dat";
186 std::ofstream outputStream(binaryPath,
std::ios::out | std::ios::binary);
187 boost::archive::binary_oarchive outputArchive(outputStream);
195 std::ifstream ifs(binaryPath, std::ios::in | std::ios::binary);
196 boost::archive::binary_iarchive inputArchive(ifs);
197 inputArchive >> solverFromDisk;
205 }
catch(std::exception &
e) {
211 }
catch(std::exception &
e) {
static int runAllTests(TestResult &result)
A Gaussian factor using the canonical parameters (information form)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
#define EXPECT(condition)
The most common 5DOF 3D->2D calibration.
Calibration of a camera with radial distortion that also supports Lie-group behaviors for optimizatio...
BOOST_CLASS_EXPORT_GUID(DecisionTreeFactor, "gtsam_DecisionTreeFactor")
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
PinholeCamera< Cal3_S2 > PinholeCal3S2
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
static Point3 pt3(1.0, 2.0, 3.0)
static Pose3 pose3(rt3, pt3)
#define GTSAM_VALUE_EXPORT(Type)
use this macro instead of BOOST_CLASS_EXPORT for GenericValues
BiCGSTAB< SparseMatrix< double > > solver
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
static ConjugateGradientParameters parameters
noiseModel::Diagonal::shared_ptr SharedDiagonal
PinholeCamera< Cal3Bundler > PinholeCal3Bundler
Base class for all pinhole cameras.
Calibration used by Bundler.
void insert(Key j, const Vector &value)
noiseModel::Base::shared_ptr SharedNoiseModel
static Cal3_S2 cal1(1.0, 2.0, 0.3, 0.1, 0.5)
int RealScalar int RealScalar int RealScalar * pc
std::ofstream out("Result.txt")
Values calculateEstimate() const
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
std::shared_ptr< Diagonal > shared_ptr
void insert(Key j, const Value &val)
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
The most common 5DOF 3D->2D calibration.
IsDerived< DERIVEDFACTOR > add(std::shared_ptr< DERIVEDFACTOR > factor)
add is a synonym for push_back.
NonlinearFactorGraph graph
TEST(Serialization, TemplatedValues)
static Cal3DS2 cal2(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0)
Calibration used by Bundler.
A non-templated config holding any types of Manifold-group elements.
PinholeCamera< Cal3DS2 > PinholeCal3DS2
static Cal3Bundler cal3(1.0, 2.0, 3.0)
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:08:31