8 #include <gtsam/slam/serialization.h> 23 #include <gtsam/linear/GaussianMultifrontalSolver.h> 29 using namespace gtsam;
180 return serialize<NonlinearFactorGraph>(
graph);
186 deserialize<NonlinearFactorGraph>(serialized_graph, *
result);
192 return serializeXML<NonlinearFactorGraph>(
graph,
name);
197 const std::string&
name) {
199 deserializeXML<NonlinearFactorGraph>(serialized_graph, *
result,
name);
205 return serialize<Values>(
values);
211 deserialize<Values>(serialized_values, *
result);
222 const std::string&
name) {
224 deserializeXML<Values>(serialized_values, *
result,
name);
230 return serializeToFile<NonlinearFactorGraph>(
graph, fname);
235 const std::string& fname,
const std::string&
name) {
236 return serializeToXMLFile<NonlinearFactorGraph>(
graph, fname,
name);
241 return serializeToFile<Values>(
values, fname);
246 const std::string& fname,
const std::string&
name) {
247 return serializeToXMLFile<Values>(
values, fname,
name);
253 if (!deserializeFromFile<NonlinearFactorGraph>(fname, *result))
254 throw std::invalid_argument(
"Failed to open file" + fname);
260 const std::string&
name) {
262 if (!deserializeFromXMLFile<NonlinearFactorGraph>(fname, *result, name))
263 throw std::invalid_argument(
"Failed to open file" + fname);
270 if (!deserializeFromFile<Values>(fname, *result))
271 throw std::invalid_argument(
"Failed to open file" + fname);
277 const std::string&
name) {
279 if (!deserializeFromXMLFile<Values>(fname, *result, name))
280 throw std::invalid_argument(
"Failed to open file" + fname);
GenericProjectionFactor< Pose3, Point3, Cal3_S2 > GenericProjectionFactorCal3_S2
NonlinearEquality< Point2 > NonlinearEqualityPoint2
std::string serializeGraph(const NonlinearFactorGraph &graph)
NonlinearEquality< CalibratedCamera > NonlinearEqualityCalibratedCamera
RangeFactor< CalibratedCamera, Point3 > RangeFactorCalibratedCameraPoint
NonlinearEquality< PinholeCameraCal3_S2 > NonlinearEqualityPinholeCameraCal3_S2
NonlinearFactorGraph::shared_ptr deserializeGraph(const std::string &serialized_graph)
BearingRangeFactor< Pose3, Point3 > BearingRangeFactor3D
NonlinearEquality< Pose3 > NonlinearEqualityPose3
NonlinearEquality< StereoPoint2 > NonlinearEqualityStereoPoint2
NonlinearEquality< StereoCamera > NonlinearEqualityStereoCamera
gtsam::GeneralSFMFactor< gtsam::PinholeCameraCal3_S2, gtsam::Point3 > GeneralSFMFactorCal3_S2
PriorFactor< Pose2 > PriorFactorPose2
RangeFactor< Pose2, Pose2 > RangeFactorPose2
gtsam::GeneralSFMFactor< gtsam::PinholeCameraCal3DS2, gtsam::Point3 > GeneralSFMFactorCal3DS2
PriorFactor< Rot3 > PriorFactorRot3
Values::shared_ptr deserializeValuesFromFile(const std::string &fname)
BearingRangeFactor< Pose2, Point2 > BearingRangeFactor2D
Calibration of a camera with radial distortion, calculations in base class Cal3DS2_Base.
NonlinearEquality< Point3 > NonlinearEqualityPoint3
GenericProjectionFactor< Pose3, Point3, Cal3DS2 > GenericProjectionFactorCal3DS2
NonlinearFactorGraph::shared_ptr deserializeGraphFromXMLFile(const std::string &fname, const std::string &name="graph")
NonlinearFactorGraph graph
Rot3 is a 3D rotation represented as a rotation matrix if the preprocessor symbol GTSAM_USE_QUATERNIO...
PriorFactor< Point2 > PriorFactorPoint2
PriorFactor< Cal3DS2 > PriorFactorCal3DS2
PriorFactor< Rot2 > PriorFactorRot2
RangeFactor< Pose3, Point3 > RangeFactor3D
RangeFactor< CalibratedCamera, CalibratedCamera > RangeFactorCalibratedCamera
std::string serializeValuesXML(const Values &values, const std::string &name="values")
BOOST_CLASS_EXPORT_GUID(gtsam::noiseModel::Constrained, "gtsam_noiseModel_Constrained")
BetweenFactor< Pose3 > BetweenFactorPose3
RangeFactor< Pose2, Point2 > RangeFactor2D
PriorFactor< PinholeCameraCal3_S2 > PriorFactorPinholeCameraCal3_S2
The most common 5DOF 3D->2D calibration, stereo version.
RangeFactor< PinholeCameraCal3_S2, Point3 > RangeFactorPinholeCameraCal3_S2Point
NonlinearEquality< Pose2 > NonlinearEqualityPose2
RangeFactor< Pose3, Pose3 > RangeFactorPose3
Values::shared_ptr deserializeValuesXML(const std::string &serialized_values, const std::string &name="values")
BetweenFactor< Pose2 > BetweenFactorPose2
The most common 5DOF 3D->2D calibration.
PriorFactor< StereoPoint2 > PriorFactorStereoPoint2
Values::shared_ptr deserializeValues(const std::string &serialized_values)
Calibration of a camera with radial distortion that also supports Lie-group behaviors for optimizatio...
BetweenFactor< Rot2 > BetweenFactorRot2
Reprojection of a LANDMARK to a 2D point.
NonlinearFactorGraph::shared_ptr deserializeGraphFromFile(const std::string &fname)
A non-linear factor for stereo measurements.
noiseModel::Diagonal::shared_ptr SharedDiagonal
NonlinearEquality< Cal3_S2 > NonlinearEqualityCal3_S2
bool serializeGraphToXMLFile(const NonlinearFactorGraph &graph, const std::string &fname, const std::string &name="graph")
std::string serializeGraphXML(const NonlinearFactorGraph &graph, const std::string &name="graph")
std::vector< float > Values
bool serializeGraphToFile(const NonlinearFactorGraph &graph, const std::string &fname)
PriorFactor< CalibratedCamera > PriorFactorCalibratedCamera
NonlinearEquality< Rot3 > NonlinearEqualityRot3
BetweenFactor< Rot3 > BetweenFactorRot3
std::shared_ptr< This > shared_ptr
A Gaussian factor using the canonical parameters (information form)
Values::shared_ptr deserializeValuesFromXMLFile(const std::string &fname, const std::string &name="values")
std::string serializeValues(const Values &values)
PriorFactor< Pose3 > PriorFactorPose3
bool serializeValuesToFile(const Values &values, const std::string &fname)
GTSAM_VALUE_EXPORT(gtsam::Point2)
Annotation for function names.
NonlinearEquality< Cal3DS2 > NonlinearEqualityCal3DS2
PriorFactor< StereoCamera > PriorFactorStereoCamera
NonlinearFactorGraph::shared_ptr deserializeGraphXML(const std::string &serialized_graph, const std::string &name="graph")
NonlinearEquality< Rot2 > NonlinearEqualityRot2
a general SFM factor with an unknown calibration
gtsam::GeneralSFMFactor2< gtsam::Cal3_S2 > GeneralSFMFactor2Cal3_S2
std::shared_ptr< Values > shared_ptr
A shared_ptr to this class.
gtsam::GenericStereoFactor< gtsam::Pose3, gtsam::Point3 > GenericStereoFactor3D
PriorFactor< Point3 > PriorFactorPoint3
PriorFactor< Cal3_S2 > PriorFactorCal3_S2
bool serializeValuesToXMLFile(const Values &values, const std::string &fname, const std::string &name="values")
noiseModel::Base::shared_ptr SharedNoiseModel
RangeFactor< PinholeCameraCal3_S2, PinholeCameraCal3_S2 > RangeFactorPinholeCameraCal3_S2
BetweenFactor< Point3 > BetweenFactorPoint3
BetweenFactor< Point2 > BetweenFactorPoint2