serialization.cpp
Go to the documentation of this file.
1 
8 #include <gtsam/base/deprecated/LieMatrix_Deprecated.h>
9 #include <gtsam/base/deprecated/LieVector_Deprecated.h>
10 #include <gtsam/slam/serialization.h>
12 
13 //#include <gtsam/slam/AntiFactor.h>
16 //#include <gtsam/slam/BoundingConstraint.h>
20 #include <gtsam/sam/RangeFactor.h>
23 #include <gtsam/inference/Symbol.h>
25 #include <gtsam/linear/GaussianMultifrontalSolver.h>
26 #include <gtsam/geometry/Pose2.h>
27 #include <gtsam/geometry/Pose3.h>
28 #include <gtsam/geometry/Cal3DS2.h>
29 //#include <gtsam/geometry/Cal3_S2Stereo.h>
30 
31 using namespace gtsam;
32 
33 // Creating as many permutations of factors as possible
48 
57 
72 
81 
84 
87 
90 
92 
94 
95 
96 /* Create GUIDs for Noisemodels */
97 /* ************************************************************************* */
98 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained");
99 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal");
100 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian");
101 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit");
102 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic");
103 
104 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Base , "gtsam_noiseModel_mEstimator_Base");
105 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Null , "gtsam_noiseModel_mEstimator_Null");
106 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Fair , "gtsam_noiseModel_mEstimator_Fair");
107 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Huber, "gtsam_noiseModel_mEstimator_Huber");
108 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Tukey, "gtsam_noiseModel_mEstimator_Tukey");
109 
110 BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel");
111 BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal");
112 
113 /* Create GUIDs for geometry */
114 /* ************************************************************************* */
130 
131 /* Create GUIDs for factors */
132 /* ************************************************************************* */
133 BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactor, "gtsam::JacobianFactor");
134 BOOST_CLASS_EXPORT_GUID(gtsam::HessianFactor , "gtsam::HessianFactor");
135 
136 BOOST_CLASS_EXPORT_GUID(PriorFactorLieVector, "gtsam::PriorFactorLieVector");
137 BOOST_CLASS_EXPORT_GUID(PriorFactorLieMatrix, "gtsam::PriorFactorLieMatrix");
138 BOOST_CLASS_EXPORT_GUID(PriorFactorPoint2, "gtsam::PriorFactorPoint2");
139 BOOST_CLASS_EXPORT_GUID(PriorFactorStereoPoint2, "gtsam::PriorFactorStereoPoint2");
140 BOOST_CLASS_EXPORT_GUID(PriorFactorPoint3, "gtsam::PriorFactorPoint3");
141 BOOST_CLASS_EXPORT_GUID(PriorFactorRot2, "gtsam::PriorFactorRot2");
142 BOOST_CLASS_EXPORT_GUID(PriorFactorRot3, "gtsam::PriorFactorRot3");
143 BOOST_CLASS_EXPORT_GUID(PriorFactorPose2, "gtsam::PriorFactorPose2");
144 BOOST_CLASS_EXPORT_GUID(PriorFactorPose3, "gtsam::PriorFactorPose3");
145 BOOST_CLASS_EXPORT_GUID(PriorFactorCal3_S2, "gtsam::PriorFactorCal3_S2");
146 BOOST_CLASS_EXPORT_GUID(PriorFactorCal3DS2, "gtsam::PriorFactorCal3DS2");
147 BOOST_CLASS_EXPORT_GUID(PriorFactorCalibratedCamera, "gtsam::PriorFactorCalibratedCamera");
148 BOOST_CLASS_EXPORT_GUID(PriorFactorStereoCamera, "gtsam::PriorFactorStereoCamera");
149 
150 BOOST_CLASS_EXPORT_GUID(BetweenFactorLieVector, "gtsam::BetweenFactorLieVector");
151 BOOST_CLASS_EXPORT_GUID(BetweenFactorLieMatrix, "gtsam::BetweenFactorLieMatrix");
152 BOOST_CLASS_EXPORT_GUID(BetweenFactorPoint2, "gtsam::BetweenFactorPoint2");
153 BOOST_CLASS_EXPORT_GUID(BetweenFactorPoint3, "gtsam::BetweenFactorPoint3");
154 BOOST_CLASS_EXPORT_GUID(BetweenFactorRot2, "gtsam::BetweenFactorRot2");
155 BOOST_CLASS_EXPORT_GUID(BetweenFactorRot3, "gtsam::BetweenFactorRot3");
156 BOOST_CLASS_EXPORT_GUID(BetweenFactorPose2, "gtsam::BetweenFactorPose2");
157 BOOST_CLASS_EXPORT_GUID(BetweenFactorPose3, "gtsam::BetweenFactorPose3");
158 
159 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityLieVector, "gtsam::NonlinearEqualityLieVector");
160 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityLieMatrix, "gtsam::NonlinearEqualityLieMatrix");
161 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPoint2, "gtsam::NonlinearEqualityPoint2");
162 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityStereoPoint2, "gtsam::NonlinearEqualityStereoPoint2");
163 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPoint3, "gtsam::NonlinearEqualityPoint3");
164 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityRot2, "gtsam::NonlinearEqualityRot2");
165 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityRot3, "gtsam::NonlinearEqualityRot3");
166 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPose2, "gtsam::NonlinearEqualityPose2");
167 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPose3, "gtsam::NonlinearEqualityPose3");
168 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCal3_S2, "gtsam::NonlinearEqualityCal3_S2");
169 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCal3DS2, "gtsam::NonlinearEqualityCal3DS2");
170 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCalibratedCamera, "gtsam::NonlinearEqualityCalibratedCamera");
171 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityStereoCamera, "gtsam::NonlinearEqualityStereoCamera");
172 
173 BOOST_CLASS_EXPORT_GUID(RangeFactor2D, "gtsam::RangeFactor2D");
174 BOOST_CLASS_EXPORT_GUID(RangeFactor3D, "gtsam::RangeFactor3D");
175 BOOST_CLASS_EXPORT_GUID(RangeFactorPose2, "gtsam::RangeFactorPose2");
176 BOOST_CLASS_EXPORT_GUID(RangeFactorPose3, "gtsam::RangeFactorPose3");
177 BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCameraPoint, "gtsam::RangeFactorCalibratedCameraPoint");
178 BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCamera, "gtsam::RangeFactorCalibratedCamera");
179 
180 BOOST_CLASS_EXPORT_GUID(BearingRangeFactor2D, "gtsam::BearingRangeFactor2D");
181 
182 BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3_S2, "gtsam::GenericProjectionFactorCal3_S2");
183 BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3DS2, "gtsam::GenericProjectionFactorCal3DS2");
184 
185 BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3_S2, "gtsam::GeneralSFMFactorCal3_S2");
186 BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3DS2, "gtsam::GeneralSFMFactorCal3DS2");
187 
188 BOOST_CLASS_EXPORT_GUID(GeneralSFMFactor2Cal3_S2, "gtsam::GeneralSFMFactor2Cal3_S2");
189 
190 BOOST_CLASS_EXPORT_GUID(GenericStereoFactor3D, "gtsam::GenericStereoFactor3D");
191 
192 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41
193 
194 typedef PriorFactor<SimpleCamera> PriorFactorSimpleCamera;
195 typedef NonlinearEquality<SimpleCamera> NonlinearEqualitySimpleCamera;
196 typedef RangeFactor<SimpleCamera, Point3> RangeFactorSimpleCameraPoint;
197 typedef RangeFactor<SimpleCamera, SimpleCamera> RangeFactorSimpleCamera;
198 
199 GTSAM_VALUE_EXPORT(gtsam::SimpleCamera);
200 BOOST_CLASS_EXPORT_GUID(PriorFactorSimpleCamera, "gtsam::PriorFactorSimpleCamera");
201 BOOST_CLASS_EXPORT_GUID(NonlinearEqualitySimpleCamera, "gtsam::NonlinearEqualitySimpleCamera");
202 BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCameraPoint, "gtsam::RangeFactorSimpleCameraPoint");
203 BOOST_CLASS_EXPORT_GUID(RangeFactorSimpleCamera, "gtsam::RangeFactorSimpleCamera");
204 
205 #endif
206 
207 
208 /* ************************************************************************* */
209 // Actual implementations of functions
210 /* ************************************************************************* */
212  return serialize<NonlinearFactorGraph>(graph);
213 }
214 
215 /* ************************************************************************* */
216 NonlinearFactorGraph::shared_ptr gtsam::deserializeGraph(const std::string& serialized_graph) {
218  deserialize<NonlinearFactorGraph>(serialized_graph, *result);
219  return result;
220 }
221 
222 /* ************************************************************************* */
223 std::string gtsam::serializeGraphXML(const NonlinearFactorGraph& graph, const std::string& name) {
224  return serializeXML<NonlinearFactorGraph>(graph, name);
225 }
226 
227 /* ************************************************************************* */
229  const std::string& name) {
231  deserializeXML<NonlinearFactorGraph>(serialized_graph, *result, name);
232  return result;
233 }
234 
235 /* ************************************************************************* */
236 std::string gtsam::serializeValues(const Values& values) {
237  return serialize<Values>(values);
238 }
239 
240 /* ************************************************************************* */
241 Values::shared_ptr gtsam::deserializeValues(const std::string& serialized_values) {
243  deserialize<Values>(serialized_values, *result);
244  return result;
245 }
246 
247 /* ************************************************************************* */
248 std::string gtsam::serializeValuesXML(const Values& values, const std::string& name) {
249  return serializeXML<Values>(values, name);
250 }
251 
252 /* ************************************************************************* */
253 Values::shared_ptr gtsam::deserializeValuesXML(const std::string& serialized_values,
254  const std::string& name) {
256  deserializeXML<Values>(serialized_values, *result, name);
257  return result;
258 }
259 
260 /* ************************************************************************* */
261 bool gtsam::serializeGraphToFile(const NonlinearFactorGraph& graph, const std::string& fname) {
262  return serializeToFile<NonlinearFactorGraph>(graph, fname);
263 }
264 
265 /* ************************************************************************* */
267  const std::string& fname, const std::string& name) {
268  return serializeToXMLFile<NonlinearFactorGraph>(graph, fname, name);
269 }
270 
271 /* ************************************************************************* */
272 bool gtsam::serializeValuesToFile(const Values& values, const std::string& fname) {
273  return serializeToFile<Values>(values, fname);
274 }
275 
276 /* ************************************************************************* */
278  const std::string& fname, const std::string& name) {
279  return serializeToXMLFile<Values>(values, fname, name);
280 }
281 
282 /* ************************************************************************* */
285  if (!deserializeFromFile<NonlinearFactorGraph>(fname, *result))
286  throw std::invalid_argument("Failed to open file" + fname);
287  return result;
288 }
289 
290 /* ************************************************************************* */
292  const std::string& name) {
294  if (!deserializeFromXMLFile<NonlinearFactorGraph>(fname, *result, name))
295  throw std::invalid_argument("Failed to open file" + fname);
296  return result;
297 }
298 
299 /* ************************************************************************* */
302  if (!deserializeFromFile<Values>(fname, *result))
303  throw std::invalid_argument("Failed to open file" + fname);
304  return result;
305 }
306 
307 /* ************************************************************************* */
309  const std::string& name) {
311  if (!deserializeFromXMLFile<Values>(fname, *result, name))
312  throw std::invalid_argument("Failed to open file" + fname);
313  return result;
314 }
315 
316 /* ************************************************************************* */
317 
318 
GenericProjectionFactor< Pose3, Point3, Cal3_S2 > GenericProjectionFactorCal3_S2
NonlinearEquality< Point2 > NonlinearEqualityPoint2
NonlinearFactorGraph::shared_ptr deserializeGraphFromXMLFile(const std::string &fname, const std::string &name="graph")
NonlinearEquality< CalibratedCamera > NonlinearEqualityCalibratedCamera
RangeFactor< CalibratedCamera, Point3 > RangeFactorCalibratedCameraPoint
Values::shared_ptr deserializeValuesFromXMLFile(const std::string &fname, const std::string &name="values")
NonlinearEquality< PinholeCameraCal3_S2 > NonlinearEqualityPinholeCameraCal3_S2
BearingRangeFactor< Pose3, Point3 > BearingRangeFactor3D
NonlinearEquality< Pose3 > NonlinearEqualityPose3
NonlinearEquality< StereoPoint2 > NonlinearEqualityStereoPoint2
NonlinearEquality< StereoCamera > NonlinearEqualityStereoCamera
gtsam::GeneralSFMFactor< gtsam::PinholeCameraCal3_S2, gtsam::Point3 > GeneralSFMFactorCal3_S2
NonlinearFactorGraph::shared_ptr deserializeGraph(const std::string &serialized_graph)
PriorFactor< Pose2 > PriorFactorPose2
RangeFactor< Pose2, Pose2 > RangeFactorPose2
Vector2 Point2
Definition: Point2.h:27
NonlinearEquality< LieVector > NonlinearEqualityLieVector
gtsam::GeneralSFMFactor< gtsam::PinholeCameraCal3DS2, gtsam::Point3 > GeneralSFMFactorCal3DS2
PriorFactor< Rot3 > PriorFactorRot3
leaf::MyValues values
Tukey implements the "Tukey" robust error model (Zhang97ivc)
BearingRangeFactor< Pose2, Point2 > BearingRangeFactor2D
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
NonlinearEquality< Point3 > NonlinearEqualityPoint3
Huber implements the "Huber" robust error model (Zhang97ivc)
Values::shared_ptr deserializeValues(const std::string &serialized_values)
GenericProjectionFactor< Pose3, Point3, Cal3DS2 > GenericProjectionFactorCal3DS2
NonlinearFactorGraph graph
PriorFactor< Point2 > PriorFactorPoint2
bool serializeGraphToFile(const NonlinearFactorGraph &graph, const std::string &fname)
PriorFactor< Cal3DS2 > PriorFactorCal3DS2
PriorFactor< Rot2 > PriorFactorRot2
PriorFactor< LieMatrix > PriorFactorLieMatrix
Fair implements the "Fair" robust error model (Zhang97ivc)
RangeFactor< Pose3, Point3 > RangeFactor3D
RangeFactor< CalibratedCamera, CalibratedCamera > RangeFactorCalibratedCamera
Null class should behave as Gaussian.
bool serializeGraphToXMLFile(const NonlinearFactorGraph &graph, const std::string &fname, const std::string &name="graph")
BetweenFactor< Pose3 > BetweenFactorPose3
RangeFactor< Pose2, Point2 > RangeFactor2D
PriorFactor< PinholeCameraCal3_S2 > PriorFactorPinholeCameraCal3_S2
Values::shared_ptr deserializeValuesXML(const std::string &serialized_values, const std::string &name="values")
boost::shared_ptr< This > shared_ptr
Values::shared_ptr deserializeValuesFromFile(const std::string &fname)
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained,"gtsam_noiseModel_Constrained")
BetweenFactor< LieVector > BetweenFactorLieVector
Values result
boost::shared_ptr< Values > shared_ptr
A shared_ptr to this class.
Definition: Values.h:96
RangeFactor< PinholeCameraCal3_S2, Point3 > RangeFactorPinholeCameraCal3_S2Point
NonlinearEquality< Pose2 > NonlinearEqualityPose2
RangeFactor< Pose3, Pose3 > RangeFactorPose3
BetweenFactor< Pose2 > BetweenFactorPose2
PriorFactor< StereoPoint2 > PriorFactorStereoPoint2
std::string serializeGraph(const NonlinearFactorGraph &graph)
BetweenFactor< Rot2 > BetweenFactorRot2
Basic bearing factor from 2D measurement.
NonlinearEquality< LieMatrix > NonlinearEqualityLieMatrix
BetweenFactor< LieMatrix > BetweenFactorLieMatrix
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
NonlinearEquality< Cal3_S2 > NonlinearEqualityCal3_S2
std::string serializeGraphXML(const NonlinearFactorGraph &graph, const std::string &name="graph")
std::vector< float > Values
NonlinearFactorGraph::shared_ptr deserializeGraphXML(const std::string &serialized_graph, const std::string &name="graph")
GTSAM_VALUE_EXPORT(gtsam::LieVector)
PriorFactor< CalibratedCamera > PriorFactorCalibratedCamera
NonlinearEquality< Rot3 > NonlinearEqualityRot3
BetweenFactor< Rot3 > BetweenFactorRot3
NonlinearFactorGraph::shared_ptr deserializeGraphFromFile(const std::string &fname)
std::string serializeValues(const Values &values)
A Gaussian factor using the canonical parameters (information form)
PriorFactor< Pose3 > PriorFactorPose3
std::string serializeValuesXML(const Values &values, const std::string &name="values")
Annotation for function names.
Definition: attr.h:36
NonlinearEquality< Cal3DS2 > NonlinearEqualityCal3DS2
Vector3 Point3
Definition: Point3.h:35
PriorFactor< StereoCamera > PriorFactorStereoCamera
2D Pose
NonlinearEquality< Rot2 > NonlinearEqualityRot2
a general SFM factor with an unknown calibration
PriorFactor< LieVector > PriorFactorLieVector
gtsam::GeneralSFMFactor2< gtsam::Cal3_S2 > GeneralSFMFactor2Cal3_S2
3D Pose
gtsam::GenericStereoFactor< gtsam::Pose3, gtsam::Point3 > GenericStereoFactor3D
PriorFactor< Point3 > PriorFactorPoint3
PriorFactor< Cal3_S2 > PriorFactorCal3_S2
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:734
bool serializeValuesToXMLFile(const Values &values, const std::string &fname, const std::string &name="values")
bool serializeValuesToFile(const Values &values, const std::string &fname)
RangeFactor< PinholeCameraCal3_S2, PinholeCameraCal3_S2 > RangeFactorPinholeCameraCal3_S2
BetweenFactor< Point3 > BetweenFactorPoint3
BetweenFactor< Point2 > BetweenFactorPoint2


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:44:01