8 #include <gtsam/base/deprecated/LieMatrix_Deprecated.h> 9 #include <gtsam/base/deprecated/LieVector_Deprecated.h> 10 #include <gtsam/slam/serialization.h> 25 #include <gtsam/linear/GaussianMultifrontalSolver.h> 31 using namespace gtsam;
192 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V41 212 return serialize<NonlinearFactorGraph>(
graph);
218 deserialize<NonlinearFactorGraph>(serialized_graph, *
result);
224 return serializeXML<NonlinearFactorGraph>(
graph,
name);
229 const std::string&
name) {
231 deserializeXML<NonlinearFactorGraph>(serialized_graph, *
result,
name);
237 return serialize<Values>(
values);
243 deserialize<Values>(serialized_values, *
result);
254 const std::string&
name) {
256 deserializeXML<Values>(serialized_values, *
result,
name);
262 return serializeToFile<NonlinearFactorGraph>(
graph, fname);
267 const std::string& fname,
const std::string&
name) {
268 return serializeToXMLFile<NonlinearFactorGraph>(
graph, fname,
name);
273 return serializeToFile<Values>(
values, fname);
278 const std::string& fname,
const std::string&
name) {
279 return serializeToXMLFile<Values>(
values, fname,
name);
285 if (!deserializeFromFile<NonlinearFactorGraph>(fname, *result))
286 throw std::invalid_argument(
"Failed to open file" + fname);
292 const std::string&
name) {
294 if (!deserializeFromXMLFile<NonlinearFactorGraph>(fname, *result, name))
295 throw std::invalid_argument(
"Failed to open file" + fname);
302 if (!deserializeFromFile<Values>(fname, *result))
303 throw std::invalid_argument(
"Failed to open file" + fname);
309 const std::string&
name) {
311 if (!deserializeFromXMLFile<Values>(fname, *result, name))
312 throw std::invalid_argument(
"Failed to open file" + fname);
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
NonlinearEquality< LieVector > NonlinearEqualityLieVector
gtsam::GeneralSFMFactor< gtsam::PinholeCameraCal3DS2, gtsam::Point3 > GeneralSFMFactorCal3DS2
PriorFactor< Rot3 > PriorFactorRot3
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
boost::shared_ptr< Values > shared_ptr
A shared_ptr to this class.
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
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.
NonlinearEquality< Cal3DS2 > NonlinearEqualityCal3DS2
PriorFactor< StereoCamera > PriorFactorStereoCamera
NonlinearEquality< Rot2 > NonlinearEqualityRot2
a general SFM factor with an unknown calibration
PriorFactor< LieVector > PriorFactorLieVector
gtsam::GeneralSFMFactor2< gtsam::Cal3_S2 > GeneralSFMFactor2Cal3_S2
gtsam::GenericStereoFactor< gtsam::Pose3, gtsam::Point3 > GenericStereoFactor3D
PriorFactor< Point3 > PriorFactorPoint3
PriorFactor< Cal3_S2 > PriorFactorCal3_S2
noiseModel::Base::shared_ptr SharedNoiseModel
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