serialization.cpp
Go to the documentation of this file.
1 
8 #include <gtsam/slam/serialization.h>
10 
11 //#include <gtsam/slam/AntiFactor.h>
14 //#include <gtsam/slam/BoundingConstraint.h>
18 #include <gtsam/sam/RangeFactor.h>
21 #include <gtsam/inference/Symbol.h>
23 #include <gtsam/linear/GaussianMultifrontalSolver.h>
24 #include <gtsam/geometry/Pose2.h>
25 #include <gtsam/geometry/Pose3.h>
26 #include <gtsam/geometry/Cal3DS2.h>
27 //#include <gtsam/geometry/Cal3_S2Stereo.h>
28 
29 using namespace gtsam;
30 
31 // Creating as many permutations of factors as possible
44 
51 
64 
73 
76 
79 
82 
84 
86 
87 
88 /* Create GUIDs for Noisemodels */
89 /* ************************************************************************* */
90 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained");
91 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Diagonal, "gtsam_noiseModel_Diagonal");
92 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Gaussian, "gtsam_noiseModel_Gaussian");
93 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Unit, "gtsam_noiseModel_Unit");
94 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Isotropic, "gtsam_noiseModel_Isotropic");
95 
96 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Base , "gtsam_noiseModel_mEstimator_Base");
97 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Null , "gtsam_noiseModel_mEstimator_Null");
98 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Fair , "gtsam_noiseModel_mEstimator_Fair");
99 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Huber, "gtsam_noiseModel_mEstimator_Huber");
100 BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::mEstimator::Tukey, "gtsam_noiseModel_mEstimator_Tukey");
101 
102 BOOST_CLASS_EXPORT_GUID(gtsam::SharedNoiseModel, "gtsam_SharedNoiseModel");
103 BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal");
104 
105 /* Create GUIDs for geometry */
106 /* ************************************************************************* */
120 
121 /* Create GUIDs for factors */
122 /* ************************************************************************* */
123 BOOST_CLASS_EXPORT_GUID(gtsam::JacobianFactor, "gtsam::JacobianFactor");
124 BOOST_CLASS_EXPORT_GUID(gtsam::HessianFactor , "gtsam::HessianFactor");
125 
126 BOOST_CLASS_EXPORT_GUID(PriorFactorPoint2, "gtsam::PriorFactorPoint2");
127 BOOST_CLASS_EXPORT_GUID(PriorFactorStereoPoint2, "gtsam::PriorFactorStereoPoint2");
128 BOOST_CLASS_EXPORT_GUID(PriorFactorPoint3, "gtsam::PriorFactorPoint3");
129 BOOST_CLASS_EXPORT_GUID(PriorFactorRot2, "gtsam::PriorFactorRot2");
130 BOOST_CLASS_EXPORT_GUID(PriorFactorRot3, "gtsam::PriorFactorRot3");
131 BOOST_CLASS_EXPORT_GUID(PriorFactorPose2, "gtsam::PriorFactorPose2");
132 BOOST_CLASS_EXPORT_GUID(PriorFactorPose3, "gtsam::PriorFactorPose3");
133 BOOST_CLASS_EXPORT_GUID(PriorFactorCal3_S2, "gtsam::PriorFactorCal3_S2");
134 BOOST_CLASS_EXPORT_GUID(PriorFactorCal3DS2, "gtsam::PriorFactorCal3DS2");
135 BOOST_CLASS_EXPORT_GUID(PriorFactorCalibratedCamera, "gtsam::PriorFactorCalibratedCamera");
136 BOOST_CLASS_EXPORT_GUID(PriorFactorStereoCamera, "gtsam::PriorFactorStereoCamera");
137 
138 BOOST_CLASS_EXPORT_GUID(BetweenFactorPoint2, "gtsam::BetweenFactorPoint2");
139 BOOST_CLASS_EXPORT_GUID(BetweenFactorPoint3, "gtsam::BetweenFactorPoint3");
140 BOOST_CLASS_EXPORT_GUID(BetweenFactorRot2, "gtsam::BetweenFactorRot2");
141 BOOST_CLASS_EXPORT_GUID(BetweenFactorRot3, "gtsam::BetweenFactorRot3");
142 BOOST_CLASS_EXPORT_GUID(BetweenFactorPose2, "gtsam::BetweenFactorPose2");
143 BOOST_CLASS_EXPORT_GUID(BetweenFactorPose3, "gtsam::BetweenFactorPose3");
144 
145 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPoint2, "gtsam::NonlinearEqualityPoint2");
146 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityStereoPoint2, "gtsam::NonlinearEqualityStereoPoint2");
147 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPoint3, "gtsam::NonlinearEqualityPoint3");
148 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityRot2, "gtsam::NonlinearEqualityRot2");
149 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityRot3, "gtsam::NonlinearEqualityRot3");
150 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPose2, "gtsam::NonlinearEqualityPose2");
151 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityPose3, "gtsam::NonlinearEqualityPose3");
152 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCal3_S2, "gtsam::NonlinearEqualityCal3_S2");
153 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCal3DS2, "gtsam::NonlinearEqualityCal3DS2");
154 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityCalibratedCamera, "gtsam::NonlinearEqualityCalibratedCamera");
155 BOOST_CLASS_EXPORT_GUID(NonlinearEqualityStereoCamera, "gtsam::NonlinearEqualityStereoCamera");
156 
157 BOOST_CLASS_EXPORT_GUID(RangeFactor2D, "gtsam::RangeFactor2D");
158 BOOST_CLASS_EXPORT_GUID(RangeFactor3D, "gtsam::RangeFactor3D");
159 BOOST_CLASS_EXPORT_GUID(RangeFactorPose2, "gtsam::RangeFactorPose2");
160 BOOST_CLASS_EXPORT_GUID(RangeFactorPose3, "gtsam::RangeFactorPose3");
161 BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCameraPoint, "gtsam::RangeFactorCalibratedCameraPoint");
162 BOOST_CLASS_EXPORT_GUID(RangeFactorCalibratedCamera, "gtsam::RangeFactorCalibratedCamera");
163 
164 BOOST_CLASS_EXPORT_GUID(BearingRangeFactor2D, "gtsam::BearingRangeFactor2D");
165 
166 BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3_S2, "gtsam::GenericProjectionFactorCal3_S2");
167 BOOST_CLASS_EXPORT_GUID(GenericProjectionFactorCal3DS2, "gtsam::GenericProjectionFactorCal3DS2");
168 
169 BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3_S2, "gtsam::GeneralSFMFactorCal3_S2");
170 BOOST_CLASS_EXPORT_GUID(GeneralSFMFactorCal3DS2, "gtsam::GeneralSFMFactorCal3DS2");
171 
172 BOOST_CLASS_EXPORT_GUID(GeneralSFMFactor2Cal3_S2, "gtsam::GeneralSFMFactor2Cal3_S2");
173 
174 BOOST_CLASS_EXPORT_GUID(GenericStereoFactor3D, "gtsam::GenericStereoFactor3D");
175 
176 /* ************************************************************************* */
177 // Actual implementations of functions
178 /* ************************************************************************* */
180  return serialize<NonlinearFactorGraph>(graph);
181 }
182 
183 /* ************************************************************************* */
184 NonlinearFactorGraph::shared_ptr gtsam::deserializeGraph(const std::string& serialized_graph) {
186  deserialize<NonlinearFactorGraph>(serialized_graph, *result);
187  return result;
188 }
189 
190 /* ************************************************************************* */
191 std::string gtsam::serializeGraphXML(const NonlinearFactorGraph& graph, const std::string& name) {
192  return serializeXML<NonlinearFactorGraph>(graph, name);
193 }
194 
195 /* ************************************************************************* */
197  const std::string& name) {
199  deserializeXML<NonlinearFactorGraph>(serialized_graph, *result, name);
200  return result;
201 }
202 
203 /* ************************************************************************* */
204 std::string gtsam::serializeValues(const Values& values) {
205  return serialize<Values>(values);
206 }
207 
208 /* ************************************************************************* */
209 Values::shared_ptr gtsam::deserializeValues(const std::string& serialized_values) {
211  deserialize<Values>(serialized_values, *result);
212  return result;
213 }
214 
215 /* ************************************************************************* */
216 std::string gtsam::serializeValuesXML(const Values& values, const std::string& name) {
217  return serializeXML<Values>(values, name);
218 }
219 
220 /* ************************************************************************* */
221 Values::shared_ptr gtsam::deserializeValuesXML(const std::string& serialized_values,
222  const std::string& name) {
224  deserializeXML<Values>(serialized_values, *result, name);
225  return result;
226 }
227 
228 /* ************************************************************************* */
229 bool gtsam::serializeGraphToFile(const NonlinearFactorGraph& graph, const std::string& fname) {
230  return serializeToFile<NonlinearFactorGraph>(graph, fname);
231 }
232 
233 /* ************************************************************************* */
235  const std::string& fname, const std::string& name) {
236  return serializeToXMLFile<NonlinearFactorGraph>(graph, fname, name);
237 }
238 
239 /* ************************************************************************* */
240 bool gtsam::serializeValuesToFile(const Values& values, const std::string& fname) {
241  return serializeToFile<Values>(values, fname);
242 }
243 
244 /* ************************************************************************* */
246  const std::string& fname, const std::string& name) {
247  return serializeToXMLFile<Values>(values, fname, name);
248 }
249 
250 /* ************************************************************************* */
253  if (!deserializeFromFile<NonlinearFactorGraph>(fname, *result))
254  throw std::invalid_argument("Failed to open file" + fname);
255  return result;
256 }
257 
258 /* ************************************************************************* */
260  const std::string& name) {
262  if (!deserializeFromXMLFile<NonlinearFactorGraph>(fname, *result, name))
263  throw std::invalid_argument("Failed to open file" + fname);
264  return result;
265 }
266 
267 /* ************************************************************************* */
270  if (!deserializeFromFile<Values>(fname, *result))
271  throw std::invalid_argument("Failed to open file" + fname);
272  return result;
273 }
274 
275 /* ************************************************************************* */
277  const std::string& name) {
279  if (!deserializeFromXMLFile<Values>(fname, *result, name))
280  throw std::invalid_argument("Failed to open file" + fname);
281  return result;
282 }
283 
284 /* ************************************************************************* */
285 
286 
Pose2.h
2D Pose
name
Annotation for function names.
Definition: attr.h:51
ProjectionFactor.h
Reprojection of a LANDMARK to a 2D point.
gtsam::RangeFactor
Definition: sam/RangeFactor.h:35
NonlinearEqualityPose3
NonlinearEquality< Pose3 > NonlinearEqualityPose3
Definition: serialization.cpp:58
PriorFactorPoint2
PriorFactor< Point2 > PriorFactorPoint2
Definition: serialization.cpp:32
NonlinearEqualityPinholeCameraCal3_S2
NonlinearEquality< PinholeCameraCal3_S2 > NonlinearEqualityPinholeCameraCal3_S2
Definition: serialization.cpp:62
gtsam::HessianFactor
A Gaussian factor using the canonical parameters (information form)
Definition: HessianFactor.h:100
gtsam::noiseModel::mEstimator::Tukey
Definition: LossFunctions.h:293
gtsam::Cal3DS2
Calibration of a camera with radial distortion that also supports Lie-group behaviors for optimizatio...
Definition: Cal3DS2.h:35
RangeFactorPinholeCameraCal3_S2
RangeFactor< PinholeCameraCal3_S2, PinholeCameraCal3_S2 > RangeFactorPinholeCameraCal3_S2
Definition: serialization.cpp:72
gtsam::GeneralSFMFactor2
Definition: GeneralSFMFactor.h:208
NonlinearEqualityRot3
NonlinearEquality< Rot3 > NonlinearEqualityRot3
Definition: serialization.cpp:56
BetweenFactorRot3
BetweenFactor< Rot3 > BetweenFactorRot3
Definition: serialization.cpp:48
gtsam::noiseModel::Unit
Definition: NoiseModel.h:614
gtsam::noiseModel::Diagonal
Definition: NoiseModel.h:301
PriorFactorCal3_S2
PriorFactor< Cal3_S2 > PriorFactorCal3_S2
Definition: serialization.cpp:39
RangeFactor.h
Serializable factor induced by a range measurement.
gtsam::JacobianFactor
Definition: JacobianFactor.h:91
gtsam::Values::shared_ptr
std::shared_ptr< Values > shared_ptr
A shared_ptr to this class.
Definition: Values.h:84
gtsam::PriorFactor
Definition: nonlinear/PriorFactor.h:30
gtsam::noiseModel::Gaussian
Definition: NoiseModel.h:168
NonlinearEqualityPoint3
NonlinearEquality< Point3 > NonlinearEqualityPoint3
Definition: serialization.cpp:54
PriorFactorRot3
PriorFactor< Rot3 > PriorFactorRot3
Definition: serialization.cpp:36
gtsam::noiseModel::mEstimator::Fair
Definition: LossFunctions.h:182
GenericProjectionFactorCal3_S2
GenericProjectionFactor< Pose3, Point3, Cal3_S2 > GenericProjectionFactorCal3_S2
Definition: serialization.cpp:77
different_sigmas::values
HybridValues values
Definition: testHybridBayesNet.cpp:245
GeneralSFMFactor.h
a general SFM factor with an unknown calibration
gtsam::GenericStereoFactor
Definition: StereoFactor.h:32
GTSAM_VALUE_EXPORT
GTSAM_VALUE_EXPORT(gtsam::Point2)
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::NonlinearEquality
Definition: NonlinearEquality.h:43
gtsam::noiseModel::mEstimator::Huber
Definition: LossFunctions.h:217
gtsam::noiseModel::Constrained
Definition: NoiseModel.h:404
RangeFactorPose3
RangeFactor< Pose3, Pose3 > RangeFactorPose3
Definition: serialization.cpp:68
PriorFactorPose2
PriorFactor< Pose2 > PriorFactorPose2
Definition: serialization.cpp:37
BOOST_CLASS_EXPORT_GUID
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained")
RangeFactor2D
RangeFactor< Pose2, Point2 > RangeFactor2D
Definition: serialization.cpp:65
gtsam::noiseModel::mEstimator::Null
Definition: LossFunctions.h:151
RangeFactorCalibratedCamera
RangeFactor< CalibratedCamera, CalibratedCamera > RangeFactorCalibratedCamera
Definition: serialization.cpp:71
PriorFactor.h
BetweenFactorPoint3
BetweenFactor< Point3 > BetweenFactorPoint3
Definition: serialization.cpp:46
BetweenFactorPoint2
BetweenFactor< Point2 > BetweenFactorPoint2
Definition: serialization.cpp:45
NonlinearEqualityCal3_S2
NonlinearEquality< Cal3_S2 > NonlinearEqualityCal3_S2
Definition: serialization.cpp:59
GeneralSFMFactorCal3DS2
gtsam::GeneralSFMFactor< gtsam::PinholeCameraCal3DS2, gtsam::Point3 > GeneralSFMFactorCal3DS2
Definition: serialization.cpp:81
gtsam::serializeGraph
std::string serializeGraph(const NonlinearFactorGraph &graph)
Definition: serialization.cpp:179
NonlinearEqualityCalibratedCamera
NonlinearEquality< CalibratedCamera > NonlinearEqualityCalibratedCamera
Definition: serialization.cpp:61
BetweenFactor.h
gtsam::noiseModel::Isotropic
Definition: NoiseModel.h:541
gtsam::Rot3
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
Definition: Rot3.h:58
gtsam::BearingRangeFactor
Definition: sam/BearingRangeFactor.h:34
gtsam::Pose3
Definition: Pose3.h:37
gtsam::deserializeGraphXML
NonlinearFactorGraph::shared_ptr deserializeGraphXML(const std::string &serialized_graph, const std::string &name="graph")
Definition: serialization.cpp:196
StereoFactor.h
A non-linear factor for stereo measurements.
gtsam::deserializeGraphFromFile
NonlinearFactorGraph::shared_ptr deserializeGraphFromFile(const std::string &fname)
Definition: serialization.cpp:251
gtsam::PinholeCamera
Definition: PinholeCamera.h:33
GenericProjectionFactorCal3DS2
GenericProjectionFactor< Pose3, Point3, Cal3DS2 > GenericProjectionFactorCal3DS2
Definition: serialization.cpp:78
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
GeneralSFMFactor2Cal3_S2
gtsam::GeneralSFMFactor2< gtsam::Cal3_S2 > GeneralSFMFactor2Cal3_S2
Definition: serialization.cpp:83
PriorFactorCalibratedCamera
PriorFactor< CalibratedCamera > PriorFactorCalibratedCamera
Definition: serialization.cpp:41
gtsam::SharedDiagonal
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:764
gtsam::GenericProjectionFactor
Definition: ProjectionFactor.h:40
gtsam::serializeValuesXML
std::string serializeValuesXML(const Values &values, const std::string &name="values")
Definition: serialization.cpp:216
BetweenFactorPose2
BetweenFactor< Pose2 > BetweenFactorPose2
Definition: serialization.cpp:49
Symbol.h
gtsam::Point2
Vector2 Point2
Definition: Point2.h:32
gtsam::SharedNoiseModel
noiseModel::Base::shared_ptr SharedNoiseModel
Definition: NoiseModel.h:762
NonlinearEquality.h
PriorFactorStereoPoint2
PriorFactor< StereoPoint2 > PriorFactorStereoPoint2
Definition: serialization.cpp:33
gtsam::CalibratedCamera
Definition: CalibratedCamera.h:251
serialization.h
Convenience functions for serializing data structures via boost.serialization.
BetweenFactorPose3
BetweenFactor< Pose3 > BetweenFactorPose3
Definition: serialization.cpp:50
gtsam::deserializeValues
Values::shared_ptr deserializeValues(const std::string &serialized_values)
Definition: serialization.cpp:209
gtsam::deserializeValuesFromFile
Values::shared_ptr deserializeValuesFromFile(const std::string &fname)
Definition: serialization.cpp:268
gtsam::deserializeGraph
NonlinearFactorGraph::shared_ptr deserializeGraph(const std::string &serialized_graph)
Definition: serialization.cpp:184
gtsam::Rot2
Definition: Rot2.h:35
NonlinearEqualityCal3DS2
NonlinearEquality< Cal3DS2 > NonlinearEqualityCal3DS2
Definition: serialization.cpp:60
NonlinearEqualityPose2
NonlinearEquality< Pose2 > NonlinearEqualityPose2
Definition: serialization.cpp:57
Values
std::vector< float > Values
Definition: sparse_setter.cpp:45
gtsam
traits
Definition: SFMdata.h:40
gtsam::Cal3_S2Stereo
The most common 5DOF 3D->2D calibration, stereo version.
Definition: Cal3_S2Stereo.h:30
gtsam::deserializeGraphFromXMLFile
NonlinearFactorGraph::shared_ptr deserializeGraphFromXMLFile(const std::string &fname, const std::string &name="graph")
Definition: serialization.cpp:259
NonlinearEqualityStereoPoint2
NonlinearEquality< StereoPoint2 > NonlinearEqualityStereoPoint2
Definition: serialization.cpp:53
NonlinearEqualityStereoCamera
NonlinearEquality< StereoCamera > NonlinearEqualityStereoCamera
Definition: serialization.cpp:63
gtsam::Values
Definition: Values.h:65
Cal3DS2.h
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
gtsam::StereoPoint2
Definition: StereoPoint2.h:34
RangeFactorPose2
RangeFactor< Pose2, Pose2 > RangeFactorPose2
Definition: serialization.cpp:67
RangeFactor3D
RangeFactor< Pose3, Point3 > RangeFactor3D
Definition: serialization.cpp:66
gtsam::GeneralSFMFactor
Definition: GeneralSFMFactor.h:59
PriorFactorPose3
PriorFactor< Pose3 > PriorFactorPose3
Definition: serialization.cpp:38
gtsam::StereoCamera
Definition: StereoCamera.h:47
gtsam::Cal3_S2
The most common 5DOF 3D->2D calibration.
Definition: Cal3_S2.h:34
gtsam::Point3
Vector3 Point3
Definition: Point3.h:38
BetweenFactorRot2
BetweenFactor< Rot2 > BetweenFactorRot2
Definition: serialization.cpp:47
gtsam::serializeGraphToXMLFile
bool serializeGraphToXMLFile(const NonlinearFactorGraph &graph, const std::string &fname, const std::string &name="graph")
Definition: serialization.cpp:234
RangeFactorCalibratedCameraPoint
RangeFactor< CalibratedCamera, Point3 > RangeFactorCalibratedCameraPoint
Definition: serialization.cpp:69
gtsam::serializeGraphXML
std::string serializeGraphXML(const NonlinearFactorGraph &graph, const std::string &name="graph")
Definition: serialization.cpp:191
BearingRangeFactor2D
BearingRangeFactor< Pose2, Point2 > BearingRangeFactor2D
Definition: serialization.cpp:74
gtsam::serializeGraphToFile
bool serializeGraphToFile(const NonlinearFactorGraph &graph, const std::string &fname)
Definition: serialization.cpp:229
GaussianISAM.h
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
BearingRangeFactor3D
BearingRangeFactor< Pose3, Point3 > BearingRangeFactor3D
Definition: serialization.cpp:75
GenericStereoFactor3D
gtsam::GenericStereoFactor< gtsam::Pose3, gtsam::Point3 > GenericStereoFactor3D
Definition: serialization.cpp:85
gtsam::noiseModel::mEstimator::Base
Definition: LossFunctions.h:66
PriorFactorStereoCamera
PriorFactor< StereoCamera > PriorFactorStereoCamera
Definition: serialization.cpp:43
NonlinearEqualityRot2
NonlinearEquality< Rot2 > NonlinearEqualityRot2
Definition: serialization.cpp:55
PriorFactorCal3DS2
PriorFactor< Cal3DS2 > PriorFactorCal3DS2
Definition: serialization.cpp:40
PriorFactorPoint3
PriorFactor< Point3 > PriorFactorPoint3
Definition: serialization.cpp:34
RangeFactorPinholeCameraCal3_S2Point
RangeFactor< PinholeCameraCal3_S2, Point3 > RangeFactorPinholeCameraCal3_S2Point
Definition: serialization.cpp:70
gtsam::deserializeValuesXML
Values::shared_ptr deserializeValuesXML(const std::string &serialized_values, const std::string &name="values")
Definition: serialization.cpp:221
PriorFactorRot2
PriorFactor< Rot2 > PriorFactorRot2
Definition: serialization.cpp:35
gtsam::deserializeValuesFromXMLFile
Values::shared_ptr deserializeValuesFromXMLFile(const std::string &fname, const std::string &name="values")
Definition: serialization.cpp:276
Pose3.h
3D Pose
gtsam::serializeValues
std::string serializeValues(const Values &values)
Definition: serialization.cpp:204
PriorFactorPinholeCameraCal3_S2
PriorFactor< PinholeCameraCal3_S2 > PriorFactorPinholeCameraCal3_S2
Definition: serialization.cpp:42
gtsam::Pose2
Definition: Pose2.h:39
NonlinearEqualityPoint2
NonlinearEquality< Point2 > NonlinearEqualityPoint2
Definition: serialization.cpp:52
BearingRangeFactor.h
a single factor contains both the bearing and the range to prevent handle to pair bearing and range f...
gtsam::serializeValuesToFile
bool serializeValuesToFile(const Values &values, const std::string &fname)
Definition: serialization.cpp:240
gtsam::BetweenFactor
Definition: BetweenFactor.h:40
GeneralSFMFactorCal3_S2
gtsam::GeneralSFMFactor< gtsam::PinholeCameraCal3_S2, gtsam::Point3 > GeneralSFMFactorCal3_S2
Definition: serialization.cpp:80
gtsam::NonlinearFactorGraph::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: NonlinearFactorGraph.h:61
gtsam::serializeValuesToXMLFile
bool serializeValuesToXMLFile(const Values &values, const std::string &fname, const std::string &name="values")
Definition: serialization.cpp:245


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:04:11