Added missing dll export tags to new functions
parent
8f4688fd5b
commit
5ae4f21517
|
|
@ -190,7 +190,7 @@ public:
|
||||||
/// @}
|
/// @}
|
||||||
|
|
||||||
/// Streaming
|
/// Streaming
|
||||||
friend std::ostream &operator<<(std::ostream &os, const Point2& p);
|
GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Point2& p);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -204,7 +204,7 @@ namespace gtsam {
|
||||||
/// @}
|
/// @}
|
||||||
|
|
||||||
/// Output stream operator
|
/// Output stream operator
|
||||||
friend std::ostream &operator<<(std::ostream &os, const Point3& p);
|
GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Point3& p);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
|
|
||||||
|
|
|
||||||
|
|
@ -291,7 +291,7 @@ namespace gtsam {
|
||||||
static std::pair<size_t, size_t> rotationInterval() { return std::make_pair(0, 2); }
|
static std::pair<size_t, size_t> rotationInterval() { return std::make_pair(0, 2); }
|
||||||
|
|
||||||
/// Output stream operator
|
/// Output stream operator
|
||||||
friend std::ostream &operator<<(std::ostream &os, const Pose3& p);
|
GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Pose3& p);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
/** Serialization function */
|
/** Serialization function */
|
||||||
|
|
|
||||||
|
|
@ -356,7 +356,7 @@ namespace gtsam {
|
||||||
Vector quaternion() const;
|
Vector quaternion() const;
|
||||||
|
|
||||||
/// Output stream operator
|
/// Output stream operator
|
||||||
friend std::ostream &operator<<(std::ostream &os, const Rot3& p);
|
GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Rot3& p);
|
||||||
|
|
||||||
private:
|
private:
|
||||||
/** Serialization function */
|
/** Serialization function */
|
||||||
|
|
|
||||||
|
|
@ -111,7 +111,7 @@ public:
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
|
|
||||||
friend void synchronize(ConcurrentFilter& filter, ConcurrentSmoother& smoother);
|
GTSAM_UNSTABLE_EXPORT friend void synchronize(ConcurrentFilter& filter, ConcurrentSmoother& smoother);
|
||||||
|
|
||||||
/** Default constructor */
|
/** Default constructor */
|
||||||
ConcurrentSmoother() {};
|
ConcurrentSmoother() {};
|
||||||
|
|
|
||||||
|
|
@ -14,25 +14,25 @@
|
||||||
namespace gtsam {
|
namespace gtsam {
|
||||||
|
|
||||||
// Serialize/Deserialize a NonlinearFactorGraph
|
// Serialize/Deserialize a NonlinearFactorGraph
|
||||||
std::string serializeGraph(const NonlinearFactorGraph& graph);
|
GTSAM_EXPORT std::string serializeGraph(const NonlinearFactorGraph& graph);
|
||||||
|
|
||||||
NonlinearFactorGraph::shared_ptr deserializeGraph(const std::string& serialized_graph);
|
GTSAM_EXPORT NonlinearFactorGraph::shared_ptr deserializeGraph(const std::string& serialized_graph);
|
||||||
|
|
||||||
std::string serializeGraphXML(const NonlinearFactorGraph& graph,
|
GTSAM_EXPORT std::string serializeGraphXML(const NonlinearFactorGraph& graph,
|
||||||
const std::string& name = "graph");
|
const std::string& name = "graph");
|
||||||
|
|
||||||
NonlinearFactorGraph::shared_ptr deserializeGraphXML(const std::string& serialized_graph,
|
GTSAM_EXPORT NonlinearFactorGraph::shared_ptr deserializeGraphXML(const std::string& serialized_graph,
|
||||||
const std::string& name = "graph");
|
const std::string& name = "graph");
|
||||||
|
|
||||||
|
|
||||||
// Serialize/Deserialize a Values
|
// Serialize/Deserialize a Values
|
||||||
std::string serializeValues(const Values& values);
|
GTSAM_EXPORT std::string serializeValues(const Values& values);
|
||||||
|
|
||||||
Values::shared_ptr deserializeValues(const std::string& serialized_values);
|
GTSAM_EXPORT Values::shared_ptr deserializeValues(const std::string& serialized_values);
|
||||||
|
|
||||||
std::string serializeValuesXML(const Values& values, const std::string& name = "values");
|
GTSAM_EXPORT std::string serializeValuesXML(const Values& values, const std::string& name = "values");
|
||||||
|
|
||||||
Values::shared_ptr deserializeValuesXML(const std::string& serialized_values,
|
GTSAM_EXPORT Values::shared_ptr deserializeValuesXML(const std::string& serialized_values,
|
||||||
const std::string& name = "values");
|
const std::string& name = "values");
|
||||||
|
|
||||||
// Serialize to/from files
|
// Serialize to/from files
|
||||||
|
|
@ -40,21 +40,21 @@ Values::shared_ptr deserializeValuesXML(const std::string& serialized_values,
|
||||||
// Filename arguments include path
|
// Filename arguments include path
|
||||||
|
|
||||||
// Serialize
|
// Serialize
|
||||||
bool serializeGraphToFile(const NonlinearFactorGraph& graph, const std::string& fname);
|
GTSAM_EXPORT bool serializeGraphToFile(const NonlinearFactorGraph& graph, const std::string& fname);
|
||||||
bool serializeGraphToXMLFile(const NonlinearFactorGraph& graph,
|
GTSAM_EXPORT bool serializeGraphToXMLFile(const NonlinearFactorGraph& graph,
|
||||||
const std::string& fname, const std::string& name = "graph");
|
const std::string& fname, const std::string& name = "graph");
|
||||||
|
|
||||||
bool serializeValuesToFile(const Values& values, const std::string& fname);
|
GTSAM_EXPORT bool serializeValuesToFile(const Values& values, const std::string& fname);
|
||||||
bool serializeValuesToXMLFile(const Values& values,
|
GTSAM_EXPORT bool serializeValuesToXMLFile(const Values& values,
|
||||||
const std::string& fname, const std::string& name = "values");
|
const std::string& fname, const std::string& name = "values");
|
||||||
|
|
||||||
// Deserialize
|
// Deserialize
|
||||||
NonlinearFactorGraph::shared_ptr deserializeGraphFromFile(const std::string& fname);
|
GTSAM_EXPORT NonlinearFactorGraph::shared_ptr deserializeGraphFromFile(const std::string& fname);
|
||||||
NonlinearFactorGraph::shared_ptr deserializeGraphFromXMLFile(const std::string& fname,
|
GTSAM_EXPORT NonlinearFactorGraph::shared_ptr deserializeGraphFromXMLFile(const std::string& fname,
|
||||||
const std::string& name = "graph");
|
const std::string& name = "graph");
|
||||||
|
|
||||||
Values::shared_ptr deserializeValuesFromFile(const std::string& fname);
|
GTSAM_EXPORT Values::shared_ptr deserializeValuesFromFile(const std::string& fname);
|
||||||
Values::shared_ptr deserializeValuesFromXMLFile(const std::string& fname,
|
GTSAM_EXPORT Values::shared_ptr deserializeValuesFromXMLFile(const std::string& fname,
|
||||||
const std::string& name = "values");
|
const std::string& name = "values");
|
||||||
|
|
||||||
} // \namespace gtsam
|
} // \namespace gtsam
|
||||||
|
|
|
||||||
Loading…
Reference in New Issue