Added dll export tags and updated cmake scripts so that GTSAM can build as a shared library on windows

release/4.3a0
Richard Roberts 2013-03-13 18:56:21 +00:00
parent 9223da18c9
commit a54d177202
110 changed files with 542 additions and 446 deletions

View File

@ -51,12 +51,8 @@ option(GTSAM_BUILD_EXAMPLES "Enable/Disable building of examples"
if(GTSAM_UNSTABLE_AVAILABLE)
option(GTSAM_BUILD_UNSTABLE "Enable/Disable libgtsam_unstable" ON)
endif()
if(NOT MSVC)
option(GTSAM_BUILD_SHARED_LIBRARY "Enable/Disable building of a shared version of gtsam" ON)
option(GTSAM_BUILD_STATIC_LIBRARY "Enable/Disable building of a static version of gtsam" OFF)
else()
set(GTSAM_BUILD_STATIC_LIBRARY ON)
endif()
option(GTSAM_USE_QUATERNIONS "Enable/Disable using an internal Quaternion representation for rotations instead of rotation matrices" OFF)
if(NOT MSVC)
option(GTSAM_BUILD_CONVENIENCE_LIBRARIES "Enable/Disable use of convenience libraries for faster development rebuilds, but slower install" OFF)

View File

@ -91,6 +91,9 @@ if (GTSAM_BUILD_STATIC_LIBRARY)
CLEAN_DIRECT_OUTPUT 1
VERSION ${gtsam_version}
SOVERSION ${gtsam_soversion})
if(WIN32) # Add 'lib' prefix to static library to avoid filename collision with shared library
set_target_properties(gtsam-static PROPERTIES PREFIX "lib")
endif()
install(TARGETS gtsam-static EXPORT GTSAM-exports ARCHIVE DESTINATION lib)
list(APPEND GTSAM_EXPORTED_TARGETS gtsam-static)
set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE)
@ -105,6 +108,13 @@ if (GTSAM_BUILD_SHARED_LIBRARY)
CLEAN_DIRECT_OUTPUT 1
VERSION ${gtsam_version}
SOVERSION ${gtsam_soversion})
if(WIN32)
set_target_properties(gtsam-shared PROPERTIES
PREFIX ""
DEFINE_SYMBOL GTSAM_EXPORTS
RUNTIME_OUTPUT_DIRECTORY "${PROJECT_BINARY_DIR}/bin")
add_definitions(/wd4251 /wd4275) # Disable non-DLL-exported base class warnings
endif()
install(TARGETS gtsam-shared EXPORT GTSAM-exports LIBRARY DESTINATION lib ARCHIVE DESTINATION lib RUNTIME DESTINATION bin)
list(APPEND GTSAM_EXPORTED_TARGETS gtsam-shared)
set(GTSAM_EXPORTED_TARGETS "${GTSAM_EXPORTED_TARGETS}" PARENT_SCOPE)

View File

@ -23,13 +23,15 @@
#include <set>
#include <boost/shared_ptr.hpp>
#include <gtsam/base/types.h>
namespace gtsam {
/**
* A fast implementation of disjoint set forests that uses vector as underly data structure.
* @addtogroup base
*/
class DSFVector {
class GTSAM_EXPORT DSFVector {
public:
typedef std::vector<size_t> V; ///< Vector of ints

View File

@ -49,7 +49,7 @@ struct LieMatrix : public Matrix, public DerivedValue<LieMatrix> {
Matrix(Eigen::Map<const Matrix>(data, m, n)) {}
/** Specify arguments directly, as in Matrix_() - always force these to be doubles */
LieMatrix(size_t m, size_t n, ...);
GTSAM_EXPORT LieMatrix(size_t m, size_t n, ...);
/// @}
/// @name Testable interface

View File

@ -42,10 +42,10 @@ struct LieVector : public Vector, public DerivedValue<LieVector> {
LieVector(double d) : Vector(Vector_(1, d)) {}
/** constructor with size and initial data, row order ! */
LieVector(size_t m, const double* const data);
GTSAM_EXPORT LieVector(size_t m, const double* const data);
/** Specify arguments directly, as in Vector_() - always force these to be doubles */
LieVector(size_t m, ...);
GTSAM_EXPORT LieVector(size_t m, ...);
/** get the underlying vector */
inline Vector vector() const {

View File

@ -49,12 +49,12 @@ typedef Eigen::Block<const Matrix> ConstSubMatrix;
/**
* constructor with size and initial data, row order !
*/
Matrix Matrix_(size_t m, size_t n, const double* const data);
GTSAM_EXPORT Matrix Matrix_(size_t m, size_t n, const double* const data);
/**
* constructor with size and vector data, column order !!!
*/
Matrix Matrix_(size_t m, size_t n, const Vector& v);
GTSAM_EXPORT Matrix Matrix_(size_t m, size_t n, const Vector& v);
/**
* constructor from Vector yielding v.size()*1 vector
@ -65,7 +65,7 @@ inline Matrix Matrix_(const Vector& v) { return Matrix_(v.size(),1,v);}
* nice constructor, dangerous as number of arguments must be exactly right
* and you have to pass doubles !!! always use 0.0 never 0
*/
Matrix Matrix_(size_t m, size_t n, ...);
GTSAM_EXPORT Matrix Matrix_(size_t m, size_t n, ...);
// Matlab-like syntax
@ -75,7 +75,7 @@ Matrix Matrix_(size_t m, size_t n, ...);
* Note: if assigning a block (created from an Eigen block() function) of a matrix to zeros,
* don't use this function, instead use ".setZero(m,n)" to avoid an Eigen error.
*/
Matrix zeros(size_t m, size_t n);
GTSAM_EXPORT Matrix zeros(size_t m, size_t n);
/**
* Creates an identity matrix, with matlab-like syntax
@ -83,7 +83,7 @@ Matrix zeros(size_t m, size_t n);
* Note: if assigning a block (created from an Eigen block() function) of a matrix to identity,
* don't use this function, instead use ".setIdentity(m,n)" to avoid an Eigen error.
*/
Matrix eye(size_t m, size_t n);
GTSAM_EXPORT Matrix eye(size_t m, size_t n);
/**
* Creates a square identity matrix, with matlab-like syntax
@ -92,7 +92,7 @@ Matrix eye(size_t m, size_t n);
* don't use this function, instead use ".setIdentity(m)" to avoid an Eigen error.
*/
inline Matrix eye( size_t m ) { return eye(m,m); }
Matrix diag(const Vector& v);
GTSAM_EXPORT Matrix diag(const Vector& v);
/**
* equals with an tolerance
@ -132,53 +132,53 @@ inline bool operator!=(const Matrix& A, const Matrix& B) {
/**
* equals with an tolerance, prints out message if unequal
*/
bool assert_equal(const Matrix& A, const Matrix& B, double tol = 1e-9);
GTSAM_EXPORT bool assert_equal(const Matrix& A, const Matrix& B, double tol = 1e-9);
/**
* equals with an tolerance, prints out message if unequal
*/
bool assert_equal(const std::list<Matrix>& As, const std::list<Matrix>& Bs, double tol = 1e-9);
GTSAM_EXPORT bool assert_equal(const std::list<Matrix>& As, const std::list<Matrix>& Bs, double tol = 1e-9);
/**
* check whether the rows of two matrices are linear independent
*/
bool linear_independent(const Matrix& A, const Matrix& B, double tol = 1e-9);
GTSAM_EXPORT bool linear_independent(const Matrix& A, const Matrix& B, double tol = 1e-9);
/**
* check whether the rows of two matrices are linear dependent
*/
bool linear_dependent(const Matrix& A, const Matrix& B, double tol = 1e-9);
GTSAM_EXPORT bool linear_dependent(const Matrix& A, const Matrix& B, double tol = 1e-9);
/**
* BLAS Level-2 style e <- e + alpha*A*x
*/
void multiplyAdd(double alpha, const Matrix& A, const Vector& x, Vector& e);
GTSAM_EXPORT void multiplyAdd(double alpha, const Matrix& A, const Vector& x, Vector& e);
/**
* BLAS Level-2 style e <- e + A*x
*/
void multiplyAdd(const Matrix& A, const Vector& x, Vector& e);
GTSAM_EXPORT void multiplyAdd(const Matrix& A, const Vector& x, Vector& e);
/**
* overload ^ for trans(A)*v
* We transpose the vectors for speed.
*/
Vector operator^(const Matrix& A, const Vector & v);
GTSAM_EXPORT Vector operator^(const Matrix& A, const Vector & v);
/**
* BLAS Level-2 style x <- x + alpha*A'*e
*/
void transposeMultiplyAdd(double alpha, const Matrix& A, const Vector& e, Vector& x);
GTSAM_EXPORT void transposeMultiplyAdd(double alpha, const Matrix& A, const Vector& e, Vector& x);
/**
* BLAS Level-2 style x <- x + A'*e
*/
void transposeMultiplyAdd(const Matrix& A, const Vector& e, Vector& x);
GTSAM_EXPORT void transposeMultiplyAdd(const Matrix& A, const Vector& e, Vector& x);
/**
* BLAS Level-2 style x <- x + alpha*A'*e
*/
void transposeMultiplyAdd(double alpha, const Matrix& A, const Vector& e, SubVector x);
GTSAM_EXPORT void transposeMultiplyAdd(double alpha, const Matrix& A, const Vector& e, SubVector x);
/** products using old-style format to improve compatibility */
template<class MATRIX>
@ -190,24 +190,24 @@ inline MATRIX prod(const MATRIX& A, const MATRIX&B) {
/**
* convert to column vector, column order !!!
*/
Vector Vector_(const Matrix& A);
GTSAM_EXPORT Vector Vector_(const Matrix& A);
/**
* print a matrix
*/
void print(const Matrix& A, const std::string& s = "", std::ostream& stream = std::cout);
GTSAM_EXPORT void print(const Matrix& A, const std::string& s = "", std::ostream& stream = std::cout);
/**
* save a matrix to file, which can be loaded by matlab
*/
void save(const Matrix& A, const std::string &s, const std::string& filename);
GTSAM_EXPORT void save(const Matrix& A, const std::string &s, const std::string& filename);
/**
* Read a matrix from an input stream, such as a file. Entries can be either
* tab-, space-, or comma-separated, similar to the format read by the MATLAB
* dlmread command.
*/
std::istream& operator>>(std::istream& inputStream, Matrix& destinationMatrix);
GTSAM_EXPORT std::istream& operator>>(std::istream& inputStream, Matrix& destinationMatrix);
/**
* extract submatrix, slice semantics, i.e. range = [i1,i2[ excluding i2
@ -232,7 +232,7 @@ Eigen::Block<const MATRIX> sub(const MATRIX& A, size_t i1, size_t i2, size_t j1,
* @param i is the row of the upper left corner insert location
* @param j is the column of the upper left corner insert location
*/
void insertSub(Matrix& fullMatrix, const Matrix& subMatrix, size_t i, size_t j);
GTSAM_EXPORT void insertSub(Matrix& fullMatrix, const Matrix& subMatrix, size_t i, size_t j);
/**
* Extracts a column view from a matrix that avoids a copy
@ -264,10 +264,10 @@ const typename MATRIX::ConstRowXpr row(const MATRIX& A, size_t j) {
* @param col is the vector to be inserted
* @param j is the index to insert the column
*/
void insertColumn(Matrix& A, const Vector& col, size_t j);
void insertColumn(Matrix& A, const Vector& col, size_t i, size_t j);
GTSAM_EXPORT void insertColumn(Matrix& A, const Vector& col, size_t j);
GTSAM_EXPORT void insertColumn(Matrix& A, const Vector& col, size_t i, size_t j);
Vector columnNormSquare(const Matrix &A);
GTSAM_EXPORT Vector columnNormSquare(const Matrix &A);
/**
* Zeros all of the elements below the diagonal of a matrix, in place
@ -291,12 +291,12 @@ inline Matrix trans(const Matrix& A) { return A.transpose(); }
* solve AX=B via in-place Lu factorization and backsubstitution
* After calling, A contains LU, B the solved RHS vectors
*/
void solve(Matrix& A, Matrix& B);
GTSAM_EXPORT void solve(Matrix& A, Matrix& B);
/**
* invert A
*/
Matrix inverse(const Matrix& A);
GTSAM_EXPORT Matrix inverse(const Matrix& A);
/**
* QR factorization, inefficient, best use imperative householder below
@ -304,7 +304,7 @@ Matrix inverse(const Matrix& A);
* @param A a matrix
* @return <Q,R> rotation matrix Q, upper triangular R
*/
std::pair<Matrix,Matrix> qr(const Matrix& A);
GTSAM_EXPORT std::pair<Matrix,Matrix> qr(const Matrix& A);
/**
* QR factorization using Eigen's internal block QR algorithm
@ -335,7 +335,7 @@ void inplace_QR(MATRIX& A) {
* @param sigmas is a vector of the measurement standard deviation
* @return list of r vectors, d and sigma
*/
std::list<boost::tuple<Vector, double, double> >
GTSAM_EXPORT std::list<boost::tuple<Vector, double, double> >
weighted_eliminate(Matrix& A, Vector& b, const Vector& sigmas);
/**
@ -345,7 +345,7 @@ weighted_eliminate(Matrix& A, Vector& b, const Vector& sigmas);
* @param copy_vectors - true to copy Householder vectors below diagonal
* @return nothing: in place !!!
*/
void householder_(Matrix& A, size_t k, bool copy_vectors=true);
GTSAM_EXPORT void householder_(Matrix& A, size_t k, bool copy_vectors=true);
/**
* Householder tranformation, zeros below diagonal
@ -353,7 +353,7 @@ void householder_(Matrix& A, size_t k, bool copy_vectors=true);
* @param A matrix
* @return nothing: in place !!!
*/
void householder(Matrix& A, size_t k);
GTSAM_EXPORT void householder(Matrix& A, size_t k);
/**
* backSubstitute U*x=b
@ -362,7 +362,7 @@ void householder(Matrix& A, size_t k);
* @param unit, set true if unit triangular
* @return the solution x of U*x=b
*/
Vector backSubstituteUpper(const Matrix& U, const Vector& b, bool unit=false);
GTSAM_EXPORT Vector backSubstituteUpper(const Matrix& U, const Vector& b, bool unit=false);
/**
* backSubstitute x'*U=b'
@ -372,7 +372,7 @@ Vector backSubstituteUpper(const Matrix& U, const Vector& b, bool unit=false);
* @return the solution x of x'*U=b'
*/
//TODO: is this function necessary? it isn't used
Vector backSubstituteUpper(const Vector& b, const Matrix& U, bool unit=false);
GTSAM_EXPORT Vector backSubstituteUpper(const Vector& b, const Matrix& U, bool unit=false);
/**
* backSubstitute L*x=b
@ -381,7 +381,7 @@ Vector backSubstituteUpper(const Vector& b, const Matrix& U, bool unit=false);
* @param unit, set true if unit triangular
* @return the solution x of L*x=b
*/
Vector backSubstituteLower(const Matrix& L, const Vector& b, bool unit=false);
GTSAM_EXPORT Vector backSubstituteLower(const Matrix& L, const Vector& b, bool unit=false);
/**
* create a matrix by stacking other matrices
@ -389,7 +389,7 @@ Vector backSubstituteLower(const Matrix& L, const Vector& b, bool unit=false);
* @param ... pointers to matrices to be stacked
* @return combined matrix [A1; A2; A3]
*/
Matrix stack(size_t nrMatrices, ...);
GTSAM_EXPORT Matrix stack(size_t nrMatrices, ...);
/**
* create a matrix by concatenating
@ -401,8 +401,8 @@ Matrix stack(size_t nrMatrices, ...);
* @param n is the number of columns of a single matrix
* @return combined matrix [A1 A2 A3]
*/
Matrix collect(const std::vector<const Matrix *>& matrices, size_t m = 0, size_t n = 0);
Matrix collect(size_t nrMatrices, ...);
GTSAM_EXPORT Matrix collect(const std::vector<const Matrix *>& matrices, size_t m = 0, size_t n = 0);
GTSAM_EXPORT Matrix collect(size_t nrMatrices, ...);
/**
* scales a matrix row or column by the values in a vector
@ -410,9 +410,9 @@ Matrix collect(size_t nrMatrices, ...);
* (Vector, Matrix) scales the rows
* @param inf_mask when true, will not scale with a NaN or inf value
*/
void vector_scale_inplace(const Vector& v, Matrix& A, bool inf_mask = false); // row
Matrix vector_scale(const Vector& v, const Matrix& A, bool inf_mask = false); // row
Matrix vector_scale(const Matrix& A, const Vector& v, bool inf_mask = false); // column
GTSAM_EXPORT void vector_scale_inplace(const Vector& v, Matrix& A, bool inf_mask = false); // row
GTSAM_EXPORT Matrix vector_scale(const Vector& v, const Matrix& A, bool inf_mask = false); // row
GTSAM_EXPORT Matrix vector_scale(const Matrix& A, const Vector& v, bool inf_mask = false); // column
/**
* skew symmetric matrix returns this:
@ -424,21 +424,21 @@ Matrix vector_scale(const Matrix& A, const Vector& v, bool inf_mask = false); //
* @param wz
* @return a 3*3 skew symmetric matrix
*/
Matrix3 skewSymmetric(double wx, double wy, double wz);
GTSAM_EXPORT Matrix3 skewSymmetric(double wx, double wy, double wz);
template<class Derived>
inline Matrix3 skewSymmetric(const Eigen::MatrixBase<Derived>& w) { return skewSymmetric(w(0),w(1),w(2));}
/** Use SVD to calculate inverse square root of a matrix */
Matrix inverse_square_root(const Matrix& A);
GTSAM_EXPORT Matrix inverse_square_root(const Matrix& A);
/** Calculate the LL^t decomposition of a S.P.D matrix */
Matrix LLt(const Matrix& A);
GTSAM_EXPORT Matrix LLt(const Matrix& A);
/** Calculate the R^tR decomposition of a S.P.D matrix */
Matrix RtR(const Matrix& A);
GTSAM_EXPORT Matrix RtR(const Matrix& A);
/** Return the inverse of a S.P.D. matrix. Inversion is done via Cholesky decomposition. */
Matrix cholesky_inverse(const Matrix &A);
GTSAM_EXPORT Matrix cholesky_inverse(const Matrix &A);
/**
* SVD computes economy SVD A=U*S*V'
@ -452,7 +452,7 @@ Matrix cholesky_inverse(const Matrix &A);
* U is a basis in R^m, V is a basis in R^n
* You can just pass empty matrices U,V, and vector S, they will be re-allocated.
*/
void svd(const Matrix& A, Matrix& U, Vector& S, Matrix& V);
GTSAM_EXPORT void svd(const Matrix& A, Matrix& U, Vector& S, Matrix& V);
/**
* Direct linear transform algorithm that calls svd
@ -461,7 +461,7 @@ void svd(const Matrix& A, Matrix& U, Vector& S, Matrix& V);
* Returns rank of A, minimum error (singular value),
* and corresponding eigenvector (column of V, with A=U*S*V')
*/
boost::tuple<int, double, Vector>
GTSAM_EXPORT boost::tuple<int, double, Vector>
DLT(const Matrix& A, double rank_tol = 1e-9);
/**
@ -469,10 +469,10 @@ DLT(const Matrix& A, double rank_tol = 1e-9);
* @param A matrix to exponentiate
* @param K number of iterations
*/
Matrix expm(const Matrix& A, size_t K=7);
GTSAM_EXPORT Matrix expm(const Matrix& A, size_t K=7);
/// Cayley transform
Matrix Cayley(const Matrix& A);
GTSAM_EXPORT Matrix Cayley(const Matrix& A);
/// Implementation of Cayley transform using fixed size matrices to let
/// Eigen do more optimization

View File

@ -98,7 +98,7 @@ namespace gtsam {
};
\endcode
*/
class Value {
class GTSAM_EXPORT Value {
public:
/** Clone this value in a special memory pool, must be deleted with Value::deallocate_, *not* with the 'delete' operator. */

View File

@ -43,30 +43,30 @@ typedef Eigen::VectorBlock<const Vector> ConstSubVector;
/**
* An auxiliary function to printf for Win32 compatibility, added by Kai
*/
void odprintf(const char *format, ...);
GTSAM_EXPORT void odprintf(const char *format, ...);
/**
* constructor with size and initial data, row order !
*/
Vector Vector_( size_t m, const double* const data);
GTSAM_EXPORT Vector Vector_( size_t m, const double* const data);
/**
* nice constructor, dangerous as number of arguments must be exactly right
* and you have to pass doubles !!! always use 0.0 never 0
*/
Vector Vector_(size_t m, ...);
GTSAM_EXPORT Vector Vector_(size_t m, ...);
/**
* Create a numeric vector from an STL vector of doubles
*/
Vector Vector_(const std::vector<double>& data);
GTSAM_EXPORT Vector Vector_(const std::vector<double>& data);
/**
* Create vector initialized to a constant value
* @param n is the size of the vector
* @param value is a constant value to insert into the vector
*/
Vector repeat(size_t n, double value);
GTSAM_EXPORT Vector repeat(size_t n, double value);
/**
* Create basis vector of dimension n,
@ -76,7 +76,7 @@ Vector repeat(size_t n, double value);
* @param value is the value to insert into the vector
* @return delta vector
*/
Vector delta(size_t n, size_t i, double value);
GTSAM_EXPORT Vector delta(size_t n, size_t i, double value);
/**
* Create basis vector of dimension n,
@ -102,7 +102,7 @@ inline Vector ones(size_t n) { return Vector::Ones(n); }
/**
* check if all zero
*/
bool zero(const Vector& v);
GTSAM_EXPORT bool zero(const Vector& v);
/**
* dimensionality == size
@ -112,30 +112,30 @@ inline size_t dim(const Vector& v) { return v.size(); }
/**
* print with optional string
*/
void print(const Vector& v, const std::string& s = "", std::ostream& stream = std::cout);
GTSAM_EXPORT void print(const Vector& v, const std::string& s = "", std::ostream& stream = std::cout);
/**
* save a vector to file, which can be loaded by matlab
*/
void save(const Vector& A, const std::string &s, const std::string& filename);
GTSAM_EXPORT void save(const Vector& A, const std::string &s, const std::string& filename);
/**
* operator==()
*/
bool operator==(const Vector& vec1,const Vector& vec2);
GTSAM_EXPORT bool operator==(const Vector& vec1,const Vector& vec2);
/**
* Greater than or equal to operation
* returns true if all elements in v1
* are greater than corresponding elements in v2
*/
bool greaterThanOrEqual(const Vector& v1, const Vector& v2);
GTSAM_EXPORT bool greaterThanOrEqual(const Vector& v1, const Vector& v2);
/**
* VecA == VecB up to tolerance
*/
bool equal_with_abs_tol(const Vector& vec1, const Vector& vec2, double tol=1e-9);
bool equal_with_abs_tol(const SubVector& vec1, const SubVector& vec2, double tol=1e-9);
GTSAM_EXPORT bool equal_with_abs_tol(const Vector& vec1, const Vector& vec2, double tol=1e-9);
GTSAM_EXPORT bool equal_with_abs_tol(const SubVector& vec1, const SubVector& vec2, double tol=1e-9);
/**
* Override of equal in Lie.h
@ -158,7 +158,7 @@ inline bool equal(const Vector& vec1, const Vector& vec2) {
* @param tol 1e-9
* @return bool
*/
bool assert_equal(const Vector& vec1, const Vector& vec2, double tol=1e-9);
GTSAM_EXPORT bool assert_equal(const Vector& vec1, const Vector& vec2, double tol=1e-9);
/**
* Not the same, prints if error
@ -167,7 +167,7 @@ bool assert_equal(const Vector& vec1, const Vector& vec2, double tol=1e-9);
* @param tol 1e-9
* @return bool
*/
bool assert_inequal(const Vector& vec1, const Vector& vec2, double tol=1e-9);
GTSAM_EXPORT bool assert_inequal(const Vector& vec1, const Vector& vec2, double tol=1e-9);
/**
* Same, prints if error
@ -176,8 +176,8 @@ bool assert_inequal(const Vector& vec1, const Vector& vec2, double tol=1e-9);
* @param tol 1e-9
* @return bool
*/
bool assert_equal(const SubVector& vec1, const SubVector& vec2, double tol=1e-9);
bool assert_equal(const ConstSubVector& vec1, const ConstSubVector& vec2, double tol=1e-9);
GTSAM_EXPORT bool assert_equal(const SubVector& vec1, const SubVector& vec2, double tol=1e-9);
GTSAM_EXPORT bool assert_equal(const ConstSubVector& vec1, const ConstSubVector& vec2, double tol=1e-9);
/**
* check whether two vectors are linearly dependent
@ -186,7 +186,7 @@ bool assert_equal(const ConstSubVector& vec1, const ConstSubVector& vec2, double
* @param tol 1e-9
* @return bool
*/
bool linear_dependent(const Vector& vec1, const Vector& vec2, double tol=1e-9);
GTSAM_EXPORT bool linear_dependent(const Vector& vec1, const Vector& vec2, double tol=1e-9);
/**
* extract subvector, slice semantics, i.e. range = [i1,i2[ excluding i2
@ -195,7 +195,7 @@ bool linear_dependent(const Vector& vec1, const Vector& vec2, double tol=1e-9);
* @param i2 last row index + 1
* @return subvector v(i1:i2)
*/
ConstSubVector sub(const Vector &v, size_t i1, size_t i2);
GTSAM_EXPORT ConstSubVector sub(const Vector &v, size_t i1, size_t i2);
/**
* Inserts a subvector into a vector IN PLACE
@ -203,7 +203,7 @@ ConstSubVector sub(const Vector &v, size_t i1, size_t i2);
* @param subVector is the vector to insert
* @param i is the index where the subvector should be inserted
*/
void subInsert(Vector& fullVector, const Vector& subVector, size_t i);
GTSAM_EXPORT void subInsert(Vector& fullVector, const Vector& subVector, size_t i);
/**
* elementwise multiplication
@ -211,7 +211,7 @@ void subInsert(Vector& fullVector, const Vector& subVector, size_t i);
* @param b second vector
* @return vector [a(i)*b(i)]
*/
Vector emul(const Vector &a, const Vector &b);
GTSAM_EXPORT Vector emul(const Vector &a, const Vector &b);
/**
* elementwise division
@ -219,7 +219,7 @@ Vector emul(const Vector &a, const Vector &b);
* @param b second vector
* @return vector [a(i)/b(i)]
*/
Vector ediv(const Vector &a, const Vector &b);
GTSAM_EXPORT Vector ediv(const Vector &a, const Vector &b);
/**
* elementwise division, but 0/0 = 0, not inf
@ -227,14 +227,14 @@ Vector ediv(const Vector &a, const Vector &b);
* @param b second vector
* @return vector [a(i)/b(i)]
*/
Vector ediv_(const Vector &a, const Vector &b);
GTSAM_EXPORT Vector ediv_(const Vector &a, const Vector &b);
/**
* sum vector elements
* @param a vector
* @return sum_i a(i)
*/
double sum(const Vector &a);
GTSAM_EXPORT double sum(const Vector &a);
/**
* Calculates L2 norm for a vector
@ -242,35 +242,35 @@ double sum(const Vector &a);
* @param v vector
* @return the L2 norm
*/
double norm_2(const Vector& v);
GTSAM_EXPORT double norm_2(const Vector& v);
/**
* Elementwise reciprocal of vector elements
* @param a vector
* @return [1/a(i)]
*/
Vector reciprocal(const Vector &a);
GTSAM_EXPORT Vector reciprocal(const Vector &a);
/**
* Elementwise sqrt of vector elements
* @param v is a vector
* @return [sqrt(a(i))]
*/
Vector esqrt(const Vector& v);
GTSAM_EXPORT Vector esqrt(const Vector& v);
/**
* Absolute values of vector elements
* @param v is a vector
* @return [abs(a(i))]
*/
Vector abs(const Vector& v);
GTSAM_EXPORT Vector abs(const Vector& v);
/**
* Return the max element of a vector
* @param a is a vector
* @return max(a)
*/
double max(const Vector &a);
GTSAM_EXPORT double max(const Vector &a);
/**
* Dot product
@ -313,10 +313,10 @@ inline void axpy(double alpha, const Vector& x, SubVector y) {
* from x, such that the corresponding Householder reflection zeroes out
* all but x.(j), j is base 0. Golub & Van Loan p 210.
*/
std::pair<double,Vector> house(const Vector &x);
GTSAM_EXPORT std::pair<double,Vector> house(const Vector &x);
/** beta = house(x) computes the HouseHolder vector in place */
double houseInPlace(Vector &x);
GTSAM_EXPORT double houseInPlace(Vector &x);
/**
* Weighted Householder solution vector,
@ -328,7 +328,7 @@ double houseInPlace(Vector &x);
* @param weights is a vector of weights/precisions where w=1/(s*s)
* @return a pair of the pseudoinverse of v and the associated precision/weight
*/
std::pair<Vector, double>
GTSAM_EXPORT std::pair<Vector, double>
weightedPseudoinverse(const Vector& v, const Vector& weights);
/*
@ -336,17 +336,17 @@ weightedPseudoinverse(const Vector& v, const Vector& weights);
* Pass in initialized vector pseudo of size(weights) or will crash !
* @return the precision, pseudoinverse in third argument
*/
double weightedPseudoinverse(const Vector& a, const Vector& weights, Vector& pseudo);
GTSAM_EXPORT double weightedPseudoinverse(const Vector& a, const Vector& weights, Vector& pseudo);
/**
* concatenate Vectors
*/
Vector concatVectors(const std::list<Vector>& vs);
GTSAM_EXPORT Vector concatVectors(const std::list<Vector>& vs);
/**
* concatenate Vectors
*/
Vector concatVectors(size_t nrVectors, ...);
GTSAM_EXPORT Vector concatVectors(size_t nrVectors, ...);
} // namespace gtsam

View File

@ -45,7 +45,7 @@ namespace gtsam {
*
*
*/
std::pair<size_t,bool> choleskyCareful(Matrix& ATA, int order = -1);
GTSAM_EXPORT std::pair<size_t,bool> choleskyCareful(Matrix& ATA, int order = -1);
/**
* Partial Cholesky computes a factor [R S such that [R' 0 [R S = [A B
@ -58,7 +58,7 @@ std::pair<size_t,bool> choleskyCareful(Matrix& ATA, int order = -1);
* @return \c true if the decomposition is successful, \c false if \c A was
* not positive-definite.
*/
bool choleskyPartial(Matrix& ABC, size_t nFrontal);
GTSAM_EXPORT bool choleskyPartial(Matrix& ABC, size_t nFrontal);
}

View File

@ -20,6 +20,6 @@
namespace gtsam {
FastMap<std::string, ValueWithDefault<bool,false> > debugFlags;
GTSAM_EXPORT FastMap<std::string, ValueWithDefault<bool,false> > debugFlags;
}

View File

@ -42,7 +42,7 @@
#endif
namespace gtsam {
extern FastMap<std::string, ValueWithDefault<bool,false> > debugFlags;
GTSAM_EXTERN_EXPORT FastMap<std::string, ValueWithDefault<bool,false> > debugFlags;
}
#undef ISDEBUG

36
gtsam/base/dllexport.h Normal file
View File

@ -0,0 +1,36 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file dllexport.h
* @brief Symbols for exporting classes and methods from DLLs
* @author Richard Roberts
* @date Mar 9, 2013
*/
#ifdef _WIN32
# ifdef GTSAM_EXPORTS
# define GTSAM_EXPORT __declspec(dllexport)
# define GTSAM_EXTERN_EXPORT __declspec(dllexport) extern
# else
# ifndef GTSAM_IMPORT_STATIC
# define GTSAM_EXPORT __declspec(dllimport)
# define GTSAM_EXTERN_EXPORT __declspec(dllimport)
# else /* GTSAM_IMPORT_STATIC */
# define GTSAM_EXPORT
# define GTSAM_EXTERN_EXPORT extern
# endif /* GTSAM_IMPORT_STATIC */
# endif /* GTSAM_EXPORTS */
#else /* _WIN32 */
# define GTSAM_EXPORT
# define GTSAM_EXTERN_EXPORT extern
#endif

View File

@ -33,8 +33,8 @@ namespace gtsam {
/* ************************************************************************* */
namespace internal {
boost::shared_ptr<TimingOutline> timingRoot(new TimingOutline("Total", getTicTocID("Total")));
boost::weak_ptr<TimingOutline> timingCurrent(timingRoot);
GTSAM_EXPORT boost::shared_ptr<TimingOutline> timingRoot(new TimingOutline("Total", getTicTocID("Total")));
GTSAM_EXPORT boost::weak_ptr<TimingOutline> timingCurrent(timingRoot);
/* ************************************************************************* */
// Implementation of TimingOutline

View File

@ -40,11 +40,11 @@
namespace gtsam {
namespace internal {
size_t getTicTocID(const char *description);
void ticInternal(size_t id, const char *label);
void tocInternal(size_t id, const char *label);
GTSAM_EXPORT size_t getTicTocID(const char *description);
GTSAM_EXPORT void ticInternal(size_t id, const char *label);
GTSAM_EXPORT void tocInternal(size_t id, const char *label);
class TimingOutline {
class GTSAM_EXPORT TimingOutline {
protected:
size_t myId_;
size_t t_;
@ -76,8 +76,7 @@ namespace gtsam {
void tocInternal();
void finishedIteration();
friend void tocInternal(size_t id);
friend void tocInternal(size_t id, const char *label);
GTSAM_EXPORT friend void tocInternal(size_t id, const char *label);
}; // \TimingOutline
class AutoTicToc {
@ -91,8 +90,8 @@ namespace gtsam {
~AutoTicToc() { if(isSet_) stop(); }
};
extern boost::shared_ptr<TimingOutline> timingRoot;
extern boost::weak_ptr<TimingOutline> timingCurrent;
GTSAM_EXTERN_EXPORT boost::shared_ptr<TimingOutline> timingRoot;
GTSAM_EXTERN_EXPORT boost::weak_ptr<TimingOutline> timingCurrent;
}
// Tic and toc functions that are always active (whether or not ENABLE_TIMING is defined)

View File

@ -19,6 +19,8 @@
#pragma once
#include <gtsam/base/dllexport.h>
#include <cstddef>
#include <string>
@ -33,7 +35,7 @@ namespace gtsam {
* to a nonlinear key and then to a Symbol. */
typedef boost::function<std::string(Index)> IndexFormatter;
std::string _defaultIndexFormatter(Index j);
GTSAM_EXPORT std::string _defaultIndexFormatter(Index j);
/** The default IndexFormatter outputs the index */
static const IndexFormatter DefaultIndexFormatter = &_defaultIndexFormatter;

View File

@ -35,7 +35,7 @@ namespace gtsam {
/**
* A discrete probabilistic factor
*/
class DecisionTreeFactor: public DiscreteFactor, public Potentials {
class GTSAM_EXPORT DecisionTreeFactor: public DiscreteFactor, public Potentials {
public:

View File

@ -28,19 +28,19 @@ namespace gtsam {
typedef BayesNet<DiscreteConditional> DiscreteBayesNet;
/** Add a DiscreteCondtional */
void add(DiscreteBayesNet&, const Signature& s);
GTSAM_EXPORT void add(DiscreteBayesNet&, const Signature& s);
/** Add a DiscreteCondtional in front, when listing parents first*/
void add_front(DiscreteBayesNet&, const Signature& s);
GTSAM_EXPORT void add_front(DiscreteBayesNet&, const Signature& s);
//** evaluate for given Values */
double evaluate(const DiscreteBayesNet& bn, const DiscreteConditional::Values & values);
GTSAM_EXPORT double evaluate(const DiscreteBayesNet& bn, const DiscreteConditional::Values & values);
/** Optimize function for back-substitution. */
DiscreteFactor::sharedValues optimize(const DiscreteBayesNet& bn);
GTSAM_EXPORT DiscreteFactor::sharedValues optimize(const DiscreteBayesNet& bn);
/** Do ancestral sampling */
DiscreteFactor::sharedValues sample(const DiscreteBayesNet& bn);
GTSAM_EXPORT DiscreteFactor::sharedValues sample(const DiscreteBayesNet& bn);
} // namespace

View File

@ -30,7 +30,7 @@ namespace gtsam {
* Discrete Conditional Density
* Derives from DecisionTreeFactor
*/
class DiscreteConditional: public IndexConditional, public Potentials {
class GTSAM_EXPORT DiscreteConditional: public IndexConditional, public Potentials {
public:
// typedefs needed to play nice with gtsam

View File

@ -30,7 +30,7 @@ namespace gtsam {
* Base class for discrete probabilistic factors
* The most general one is the derived DecisionTreeFactor
*/
class DiscreteFactor: public IndexFactor {
class GTSAM_EXPORT DiscreteFactor: public IndexFactor {
public:

View File

@ -35,7 +35,7 @@ public:
typedef boost::shared_ptr<Values> sharedValues;
/** Construct empty factor graph */
DiscreteFactorGraph();
GTSAM_EXPORT DiscreteFactorGraph();
/** Constructor from a factor graph of GaussianFactor or a derived type */
template<class DERIVEDFACTOR>
@ -44,7 +44,7 @@ public:
}
/** construct from a BayesNet */
DiscreteFactorGraph(const BayesNet<DiscreteConditional>& bayesNet);
GTSAM_EXPORT DiscreteFactorGraph(const BayesNet<DiscreteConditional>& bayesNet);
template<class SOURCE>
void add(const DiscreteKey& j, SOURCE table) {
@ -68,28 +68,28 @@ public:
}
/** Return the set of variables involved in the factors (set union) */
FastSet<Index> keys() const;
GTSAM_EXPORT FastSet<Index> keys() const;
/** return product of all factors as a single factor */
DecisionTreeFactor product() const;
GTSAM_EXPORT DecisionTreeFactor product() const;
/** Evaluates the factor graph given values, returns the joint probability of the factor graph given specific instantiation of values*/
double operator()(const DiscreteFactor::Values & values) const;
GTSAM_EXPORT double operator()(const DiscreteFactor::Values & values) const;
/// print
void print(const std::string& s = "DiscreteFactorGraph",
GTSAM_EXPORT void print(const std::string& s = "DiscreteFactorGraph",
const IndexFormatter& formatter =DefaultIndexFormatter) const;
/** Permute the variables in the factors */
void permuteWithInverse(const Permutation& inversePermutation);
GTSAM_EXPORT void permuteWithInverse(const Permutation& inversePermutation);
/** Apply a reduction, which is a remapping of variable indices. */
void reduceWithInverse(const internal::Reduction& inverseReduction);
GTSAM_EXPORT void reduceWithInverse(const internal::Reduction& inverseReduction);
};
// DiscreteFactorGraph
/** Main elimination function for DiscreteFactorGraph */
std::pair<boost::shared_ptr<DiscreteConditional>, DecisionTreeFactor::shared_ptr>
GTSAM_EXPORT std::pair<boost::shared_ptr<DiscreteConditional>, DecisionTreeFactor::shared_ptr>
EliminateDiscrete(const FactorGraph<DiscreteFactor>& factors,
size_t nrFrontals = 1);

View File

@ -50,13 +50,13 @@ namespace gtsam {
}
/// Construct from cardinalities with default names
DiscreteKeys(const std::vector<int>& cs);
GTSAM_EXPORT DiscreteKeys(const std::vector<int>& cs);
/// Return a vector of indices
std::vector<Index> indices() const;
GTSAM_EXPORT std::vector<Index> indices() const;
/// Return a map from index to cardinality
std::map<Index,size_t> cardinalities() const;
GTSAM_EXPORT std::map<Index,size_t> cardinalities() const;
/// Add a key (non-const!)
DiscreteKeys& operator&(const DiscreteKey& key) {
@ -66,5 +66,5 @@ namespace gtsam {
}; // DiscreteKeys
/// Create a list from two keys
DiscreteKeys operator&(const DiscreteKey& key1, const DiscreteKey& key2);
GTSAM_EXPORT DiscreteKeys operator&(const DiscreteKey& key1, const DiscreteKey& key2);
}

View File

@ -99,14 +99,14 @@ namespace gtsam {
* all of the other variables. This function returns the result as a
* Vector of the probability values.
*/
Vector marginalProbabilities(const DiscreteKey& key) const;
GTSAM_EXPORT Vector marginalProbabilities(const DiscreteKey& key) const;
/**
* Compute the MPE solution of the DiscreteFactorGraph. This
* eliminates to create a BayesNet and then back-substitutes this BayesNet to
* obtain the solution.
*/
DiscreteFactor::sharedValues optimize() const;
GTSAM_EXPORT DiscreteFactor::sharedValues optimize() const;
};

View File

@ -47,7 +47,7 @@ namespace gtsam {
}
// Safe division for probabilities
static double safe_div(const double& a, const double& b);
GTSAM_EXPORT static double safe_div(const double& a, const double& b);
// Apply either a permutation or a reduction
template<class P>
@ -56,10 +56,10 @@ namespace gtsam {
public:
/** Default constructor for I/O */
Potentials();
GTSAM_EXPORT Potentials();
/** Constructor from Indices and ADT */
Potentials(const DiscreteKeys& keys, const ADT& decisionTree);
GTSAM_EXPORT Potentials(const DiscreteKeys& keys, const ADT& decisionTree);
/** Constructor from Indices and (string or doubles) */
template<class SOURCE>
@ -68,8 +68,8 @@ namespace gtsam {
}
// Testable
bool equals(const Potentials& other, double tol = 1e-9) const;
void print(const std::string& s = "Potentials: ",
GTSAM_EXPORT bool equals(const Potentials& other, double tol = 1e-9) const;
GTSAM_EXPORT void print(const std::string& s = "Potentials: ",
const IndexFormatter& formatter = DefaultIndexFormatter) const;
size_t cardinality(Index j) const { return cardinalities_.at(j);}
@ -81,12 +81,12 @@ namespace gtsam {
* This is virtual so that derived types e.g. DecisionTreeFactor can
* re-implement it.
*/
virtual void permuteWithInverse(const Permutation& inversePermutation);
GTSAM_EXPORT virtual void permuteWithInverse(const Permutation& inversePermutation);
/**
* Apply a reduction, which is a remapping of variable indices.
*/
virtual void reduceWithInverse(const internal::Reduction& inverseReduction);
GTSAM_EXPORT virtual void reduceWithInverse(const internal::Reduction& inverseReduction);
}; // Potentials

View File

@ -49,7 +49,7 @@ namespace gtsam {
* X|E = "95/5 2/98"
* D|E,B = "9/1 2/8 3/7 1/9"
*/
class Signature {
class GTSAM_EXPORT Signature {
public:
@ -110,26 +110,26 @@ namespace gtsam {
Signature& operator=(const Table& table);
/** provide streaming */
friend std::ostream& operator <<(std::ostream &os, const Signature &s);
GTSAM_EXPORT friend std::ostream& operator <<(std::ostream &os, const Signature &s);
};
/**
* Helper function to create Signature objects
* example: Signature s = D | E;
*/
Signature operator|(const DiscreteKey& key, const DiscreteKey& parent);
GTSAM_EXPORT Signature operator|(const DiscreteKey& key, const DiscreteKey& parent);
/**
* Helper function to create Signature objects
* example: Signature s(D % "99/1");
* Uses string parser, which requires BOOST 1.42 or higher
*/
Signature operator%(const DiscreteKey& key, const std::string& parent);
GTSAM_EXPORT Signature operator%(const DiscreteKey& key, const std::string& parent);
/**
* Helper function to create Signature objects, using table construction directly
* example: Signature s(D % table);
*/
Signature operator%(const DiscreteKey& key, const Signature::Table& parent);
GTSAM_EXPORT Signature operator%(const DiscreteKey& key, const Signature::Table& parent);
}

View File

@ -40,9 +40,6 @@ using namespace gtsam;
/* ******************************************************************************** */
typedef AlgebraicDecisionTree<Index> ADT;
template class DecisionTree<Index,double>;
template class AlgebraicDecisionTree<Index>;
#define DISABLE_DOT
template<typename T>

View File

@ -28,7 +28,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class Cal3Bundler : public DerivedValue<Cal3Bundler> {
class GTSAM_EXPORT Cal3Bundler : public DerivedValue<Cal3Bundler> {
private:
double f_, k1_, k2_ ;

View File

@ -28,7 +28,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class Cal3DS2 : public DerivedValue<Cal3DS2> {
class GTSAM_EXPORT Cal3DS2 : public DerivedValue<Cal3DS2> {
private:

View File

@ -31,7 +31,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class Cal3_S2 : public DerivedValue<Cal3_S2> {
class GTSAM_EXPORT Cal3_S2 : public DerivedValue<Cal3_S2> {
private:
double fx_, fy_, s_, u0_, v0_;

View File

@ -24,7 +24,7 @@
namespace gtsam {
class CheiralityException: public std::runtime_error {
class GTSAM_EXPORT CheiralityException: public std::runtime_error {
public:
CheiralityException() : std::runtime_error("Cheirality Exception") {}
};
@ -36,7 +36,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class CalibratedCamera : public DerivedValue<CalibratedCamera> {
class GTSAM_EXPORT CalibratedCamera : public DerivedValue<CalibratedCamera> {
private:
Pose3 pose_; // 6DOF pose

View File

@ -32,7 +32,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class Point2 : public DerivedValue<Point2> {
class GTSAM_EXPORT Point2 : public DerivedValue<Point2> {
public:
/// dimension of the variable - used to autodetect sizes
static const size_t dimension = 2;

View File

@ -35,7 +35,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class Point3 : public DerivedValue<Point3> {
class GTSAM_EXPORT Point3 : public DerivedValue<Point3> {
public:
/// dimension of the variable - used to autodetect sizes
static const size_t dimension = 3;

View File

@ -33,7 +33,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class Pose2 : public DerivedValue<Pose2> {
class GTSAM_EXPORT Pose2 : public DerivedValue<Pose2> {
public:
static const size_t dimension = 3;
@ -301,7 +301,7 @@ inline Matrix wedge<Pose2>(const Vector& xi) {
* where q = Pose2::transform_from(p) = t + R*p
*/
typedef std::pair<Point2,Point2> Point2Pair;
boost::optional<Pose2> align(const std::vector<Point2Pair>& pairs);
GTSAM_EXPORT boost::optional<Pose2> align(const std::vector<Point2Pair>& pairs);
/// @}

View File

@ -35,7 +35,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class Pose3 : public DerivedValue<Pose3> {
class GTSAM_EXPORT Pose3 : public DerivedValue<Pose3> {
public:
static const size_t dimension = 6;

View File

@ -31,7 +31,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class Rot2 : public DerivedValue<Rot2> {
class GTSAM_EXPORT Rot2 : public DerivedValue<Rot2> {
public:
/** get the dimension by the type */

View File

@ -51,7 +51,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class Rot3 : public DerivedValue<Rot3> {
class GTSAM_EXPORT Rot3 : public DerivedValue<Rot3> {
public:
static const size_t dimension = 3;
@ -384,5 +384,5 @@ namespace gtsam {
* @return an upper triangular matrix R
* @return a vector [thetax, thetay, thetaz] in radians.
*/
std::pair<Matrix3,Vector3> RQ(const Matrix3& A);
GTSAM_EXPORT std::pair<Matrix3,Vector3> RQ(const Matrix3& A);
}

View File

@ -27,5 +27,5 @@ namespace gtsam {
typedef PinholeCamera<Cal3_S2> SimpleCamera;
/// Recover camera from 3*4 camera matrix
SimpleCamera simpleCamera(const Matrix& P);
GTSAM_EXPORT SimpleCamera simpleCamera(const Matrix& P);
}

View File

@ -26,7 +26,7 @@
namespace gtsam {
class StereoCheiralityException: public std::runtime_error {
class GTSAM_EXPORT StereoCheiralityException: public std::runtime_error {
public:
StereoCheiralityException() : std::runtime_error("Stereo Cheirality Exception") {}
};
@ -36,7 +36,7 @@ public:
* A stereo camera class, parameterize by left camera pose and stereo calibration
* @addtogroup geometry
*/
class StereoCamera : public DerivedValue<StereoCamera> {
class GTSAM_EXPORT StereoCamera : public DerivedValue<StereoCamera> {
private:
Pose3 leftCamPose_;

View File

@ -28,7 +28,7 @@ namespace gtsam {
* @addtogroup geometry
* \nosubgrouping
*/
class StereoPoint2 : public DerivedValue<StereoPoint2> {
class GTSAM_EXPORT StereoPoint2 : public DerivedValue<StereoPoint2> {
public:
static const size_t dimension = 3;
private:

View File

@ -333,7 +333,7 @@ namespace gtsam {
std::list<sharedClique> childRoots;
typedef BayesTree<CONDITIONAL,CLIQUE> Tree;
BOOST_FOREACH(const Tree& subtree, subtrees) {
nodes_.insert(subtree.nodes_.begin(), subtree.nodes_.end());
nodes_.assign(subtree.nodes_.begin(), subtree.nodes_.end());
childRoots.push_back(subtree.root());
}

View File

@ -228,3 +228,5 @@ private:
};
}
#include <gtsam/inference/Factor-inl.h>

View File

@ -27,8 +27,6 @@ namespace gtsam {
using namespace std;
using namespace boost::lambda;
template class Conditional<Index>;
/* ************************************************************************* */
void IndexConditional::assertInvariants() const {
// Checks for uniqueness of keys

View File

@ -38,7 +38,7 @@ namespace gtsam {
protected:
// Checks that frontal indices are sorted and lower than parent indices
void assertInvariants() const;
GTSAM_EXPORT void assertInvariants() const;
public:
@ -112,13 +112,13 @@ namespace gtsam {
* Returns true if any reordered variables appeared in the separator and
* false if not.
*/
bool reduceSeparatorWithInverse(const internal::Reduction& inverseReduction);
GTSAM_EXPORT bool reduceSeparatorWithInverse(const internal::Reduction& inverseReduction);
/**
* Permutes the Conditional, but for efficiency requires the permutation
* to already be inverted.
*/
void permuteWithInverse(const Permutation& inversePermutation);
GTSAM_EXPORT void permuteWithInverse(const Permutation& inversePermutation);
private:
/** Serialization function */

View File

@ -16,15 +16,13 @@
*/
#include <gtsam/inference/IndexFactor.h>
#include <gtsam/inference/Factor-inl.h>
#include <gtsam/inference/Factor.h>
#include <gtsam/inference/IndexConditional.h>
using namespace std;
namespace gtsam {
template class Factor<Index> ;
/* ************************************************************************* */
void IndexFactor::assertInvariants() const {
Base::assertInvariants();

View File

@ -42,7 +42,7 @@ namespace gtsam {
/// @{
/// Internal function for checking class invariants (unique keys for this factor)
void assertInvariants() const;
GTSAM_EXPORT void assertInvariants() const;
/// @}
@ -67,7 +67,7 @@ namespace gtsam {
}
/** Construct from derived type */
IndexFactor(const IndexConditional& c);
GTSAM_EXPORT IndexFactor(const IndexConditional& c);
/** Default constructor for I/O */
IndexFactor() {
@ -140,10 +140,10 @@ namespace gtsam {
* eliminate the first variable involved in this factor
* @return a conditional on the eliminated variable
*/
boost::shared_ptr<ConditionalType> eliminateFirst();
GTSAM_EXPORT boost::shared_ptr<ConditionalType> eliminateFirst();
/** eliminate the first nrFrontals frontal variables.*/
boost::shared_ptr<BayesNet<ConditionalType> > eliminate(size_t nrFrontals =
GTSAM_EXPORT boost::shared_ptr<BayesNet<ConditionalType> > eliminate(size_t nrFrontals =
1);
#endif
@ -154,12 +154,12 @@ namespace gtsam {
* Permutes the factor, but for efficiency requires the permutation
* to already be inverted.
*/
void permuteWithInverse(const Permutation& inversePermutation);
GTSAM_EXPORT void permuteWithInverse(const Permutation& inversePermutation);
/**
* Apply a reduction, which is a remapping of variable indices.
*/
void reduceWithInverse(const internal::Reduction& inverseReduction);
GTSAM_EXPORT void reduceWithInverse(const internal::Reduction& inverseReduction);
virtual ~IndexFactor() {
}

View File

@ -54,7 +54,7 @@ namespace gtsam {
* in order to create new indexing for a structure.
* \nosubgrouping
*/
class Permutation {
class GTSAM_EXPORT Permutation {
protected:
std::vector<Index> rangeIndices_;
@ -196,20 +196,20 @@ namespace internal {
public:
typedef gtsam::FastMap<Index,Index> Base;
static Reduction CreateAsInverse(const Permutation& p);
static Reduction CreateFromPartialPermutation(const Permutation& selector, const Permutation& p);
void applyInverse(std::vector<Index>& js) const;
Permutation inverse() const;
const Index& operator[](const Index& j);
const Index& operator[](const Index& j) const;
GTSAM_EXPORT static Reduction CreateAsInverse(const Permutation& p);
GTSAM_EXPORT static Reduction CreateFromPartialPermutation(const Permutation& selector, const Permutation& p);
GTSAM_EXPORT void applyInverse(std::vector<Index>& js) const;
GTSAM_EXPORT Permutation inverse() const;
GTSAM_EXPORT const Index& operator[](const Index& j);
GTSAM_EXPORT const Index& operator[](const Index& j) const;
void print(const std::string& s="") const;
bool equals(const Reduction& other, double tol = 1e-9) const;
GTSAM_EXPORT void print(const std::string& s="") const;
GTSAM_EXPORT bool equals(const Reduction& other, double tol = 1e-9) const;
};
/**
* Reduce the variable indices so that those in the set are mapped to start at zero
*/
Permutation createReducingPermutation(const std::set<Index>& indices);
GTSAM_EXPORT Permutation createReducingPermutation(const std::set<Index>& indices);
} // \namespace internal
} // \namespace gtsam

View File

@ -47,10 +47,10 @@ namespace gtsam {
}
/** Construct from a BayesNet */
SymbolicFactorGraph(const SymbolicBayesNet& bayesNet);
GTSAM_EXPORT SymbolicFactorGraph(const SymbolicBayesNet& bayesNet);
/** Construct from a BayesTree */
SymbolicFactorGraph(const SymbolicBayesTree& bayesTree);
GTSAM_EXPORT SymbolicFactorGraph(const SymbolicBayesTree& bayesTree);
/**
* Construct from a factor graph of any type
@ -65,7 +65,7 @@ namespace gtsam {
* FactorGraph<IndexFactor>::eliminateFrontals with EliminateSymbolic
* as the eliminate function argument.
*/
std::pair<sharedConditional, SymbolicFactorGraph> eliminateFrontals(size_t nFrontals) const;
GTSAM_EXPORT std::pair<sharedConditional, SymbolicFactorGraph> eliminateFrontals(size_t nFrontals) const;
/** Factor the factor graph into a conditional and a remaining factor graph.
* Given the factor graph \f$ f(X) \f$, and \c variables to factorize out
@ -83,10 +83,10 @@ namespace gtsam {
* FactorGraph<GaussianFactor>::eliminate with EliminateSymbolic as the eliminate
* function argument.
*/
std::pair<sharedConditional, SymbolicFactorGraph> eliminate(const std::vector<Index>& variables) const;
GTSAM_EXPORT std::pair<sharedConditional, SymbolicFactorGraph> eliminate(const std::vector<Index>& variables) const;
/** Eliminate a single variable, by calling SymbolicFactorGraph::eliminate. */
std::pair<sharedConditional, SymbolicFactorGraph> eliminateOne(Index variable) const;
GTSAM_EXPORT std::pair<sharedConditional, SymbolicFactorGraph> eliminateOne(Index variable) const;
/// @}
/// @name Standard Interface
@ -96,34 +96,34 @@ namespace gtsam {
* Return the set of variables involved in the factors (computes a set
* union).
*/
FastSet<Index> keys() const;
GTSAM_EXPORT FastSet<Index> keys() const;
/// @}
/// @name Advanced Interface
/// @{
/** Push back unary factor */
void push_factor(Index key);
GTSAM_EXPORT void push_factor(Index key);
/** Push back binary factor */
void push_factor(Index key1, Index key2);
GTSAM_EXPORT void push_factor(Index key1, Index key2);
/** Push back ternary factor */
void push_factor(Index key1, Index key2, Index key3);
GTSAM_EXPORT void push_factor(Index key1, Index key2, Index key3);
/** Push back 4-way factor */
void push_factor(Index key1, Index key2, Index key3, Index key4);
GTSAM_EXPORT void push_factor(Index key1, Index key2, Index key3, Index key4);
/** Permute the variables in the factors */
void permuteWithInverse(const Permutation& inversePermutation);
GTSAM_EXPORT void permuteWithInverse(const Permutation& inversePermutation);
/** Apply a reduction, which is a remapping of variable indices. */
void reduceWithInverse(const internal::Reduction& inverseReduction);
GTSAM_EXPORT void reduceWithInverse(const internal::Reduction& inverseReduction);
};
/** Create a combined joint factor (new style for EliminationTree). */
IndexFactor::shared_ptr CombineSymbolic(const FactorGraph<IndexFactor>& factors,
GTSAM_EXPORT IndexFactor::shared_ptr CombineSymbolic(const FactorGraph<IndexFactor>& factors,
const FastMap<Index, std::vector<Index> >& variableSlots);
/**
@ -131,7 +131,7 @@ namespace gtsam {
* Combine and eliminate can also be called separately, but for this and
* derived classes calling them separately generally does extra work.
*/
std::pair<boost::shared_ptr<IndexConditional>, boost::shared_ptr<IndexFactor> >
GTSAM_EXPORT std::pair<boost::shared_ptr<IndexConditional>, boost::shared_ptr<IndexFactor> >
EliminateSymbolic(const FactorGraph<IndexFactor>&, size_t nrFrontals = 1);
/// @}

View File

@ -20,6 +20,6 @@
namespace gtsam {
template class GenericMultifrontalSolver<IndexFactor, JunctionTree<FactorGraph<IndexFactor> > >;
//template class GenericMultifrontalSolver<IndexFactor, JunctionTree<FactorGraph<IndexFactor> > >;
}

View File

@ -21,6 +21,6 @@
namespace gtsam {
// An explicit instantiation to be compiled into the library
template class GenericSequentialSolver<IndexFactor>;
//template class GenericSequentialSolver<IndexFactor>;
}

View File

@ -39,7 +39,7 @@ namespace gtsam {
* lists of factor indices.
* \nosubgrouping
*/
class VariableIndex {
class GTSAM_EXPORT VariableIndex {
public:
typedef boost::shared_ptr<VariableIndex> shared_ptr;

View File

@ -73,10 +73,10 @@ public:
/// @{
/** print */
void print(const std::string& str = "VariableSlots: ") const;
GTSAM_EXPORT void print(const std::string& str = "VariableSlots: ") const;
/** equals */
bool equals(const VariableSlots& rhs, double tol = 0.0) const;
GTSAM_EXPORT bool equals(const VariableSlots& rhs, double tol = 0.0) const;
/// @}

View File

@ -34,7 +34,7 @@ namespace gtsam {
/**
* Compute a permutation (variable ordering) using colamd
*/
Permutation::shared_ptr PermutationCOLAMD(
GTSAM_EXPORT Permutation::shared_ptr PermutationCOLAMD(
const VariableIndex& variableIndex);
/**
@ -72,7 +72,7 @@ namespace gtsam {
*
* AGC: does cmember change?
*/
Permutation::shared_ptr PermutationCOLAMD_(
GTSAM_EXPORT Permutation::shared_ptr PermutationCOLAMD_(
const VariableIndex& variableIndex, std::vector<int>& cmember);
} // \namespace inference

View File

@ -28,40 +28,40 @@ namespace gtsam {
public:
Errors() ;
GTSAM_EXPORT Errors() ;
/** break V into pieces according to its start indices */
Errors(const VectorValues &V) ;
GTSAM_EXPORT Errors(const VectorValues &V) ;
/** print */
void print(const std::string& s = "Errors") const;
GTSAM_EXPORT void print(const std::string& s = "Errors") const;
/** equals, for unit testing */
bool equals(const Errors& expected, double tol=1e-9) const;
GTSAM_EXPORT bool equals(const Errors& expected, double tol=1e-9) const;
/** Addition */
Errors operator+(const Errors& b) const;
GTSAM_EXPORT Errors operator+(const Errors& b) const;
/** subtraction */
Errors operator-(const Errors& b) const;
GTSAM_EXPORT Errors operator-(const Errors& b) const;
/** negation */
Errors operator-() const ;
GTSAM_EXPORT Errors operator-() const ;
}; // Errors
/**
* dot product
*/
double dot(const Errors& a, const Errors& b);
GTSAM_EXPORT double dot(const Errors& a, const Errors& b);
/**
* BLAS level 2 style
*/
template <>
void axpy<Errors,Errors>(double alpha, const Errors& x, Errors& y);
GTSAM_EXPORT void axpy<Errors,Errors>(double alpha, const Errors& x, Errors& y);
/** print with optional string */
void print(const Errors& a, const std::string& s = "Error");
GTSAM_EXPORT void print(const Errors& a, const std::string& s = "Error");
} // gtsam

View File

@ -30,35 +30,35 @@ namespace gtsam {
typedef BayesNet<GaussianConditional> GaussianBayesNet;
/** Create a scalar Gaussian */
GaussianBayesNet scalarGaussian(Index key, double mu=0.0, double sigma=1.0);
GTSAM_EXPORT GaussianBayesNet scalarGaussian(Index key, double mu=0.0, double sigma=1.0);
/** Create a simple Gaussian on a single multivariate variable */
GaussianBayesNet simpleGaussian(Index key, const Vector& mu, double sigma=1.0);
GTSAM_EXPORT GaussianBayesNet simpleGaussian(Index key, const Vector& mu, double sigma=1.0);
/**
* Add a conditional node with one parent
* |Rx+Sy-d|
*/
void push_front(GaussianBayesNet& bn, Index key, Vector d, Matrix R,
GTSAM_EXPORT void push_front(GaussianBayesNet& bn, Index key, Vector d, Matrix R,
Index name1, Matrix S, Vector sigmas);
/**
* Add a conditional node with two parents
* |Rx+Sy+Tz-d|
*/
void push_front(GaussianBayesNet& bn, Index key, Vector d, Matrix R,
GTSAM_EXPORT void push_front(GaussianBayesNet& bn, Index key, Vector d, Matrix R,
Index name1, Matrix S, Index name2, Matrix T, Vector sigmas);
/**
* Allocate a VectorValues for the variables in a BayesNet
*/
boost::shared_ptr<VectorValues> allocateVectorValues(const GaussianBayesNet& bn);
GTSAM_EXPORT boost::shared_ptr<VectorValues> allocateVectorValues(const GaussianBayesNet& bn);
/**
* Solve the GaussianBayesNet, i.e. return \f$ x = R^{-1}*d \f$, computed by
* back-substitution.
*/
VectorValues optimize(const GaussianBayesNet& bn);
GTSAM_EXPORT VectorValues optimize(const GaussianBayesNet& bn);
/**
* Solve the GaussianBayesNet, i.e. return \f$ x = R^{-1}*d \f$, computed by
@ -67,7 +67,7 @@ namespace gtsam {
* allocate it. See also optimize(const GaussianBayesNet&), which does not
* require pre-allocation.
*/
void optimizeInPlace(const GaussianBayesNet& bn, VectorValues& x);
GTSAM_EXPORT void optimizeInPlace(const GaussianBayesNet& bn, VectorValues& x);
/**
* Optimize along the gradient direction, with a closed-form computation to
@ -97,20 +97,20 @@ namespace gtsam {
* @param bn The GaussianBayesNet on which to perform this computation
* @return The resulting \f$ \delta x \f$ as described above
*/
VectorValues optimizeGradientSearch(const GaussianBayesNet& bn);
GTSAM_EXPORT VectorValues optimizeGradientSearch(const GaussianBayesNet& bn);
/** In-place version of optimizeGradientSearch(const GaussianBayesNet&) requiring pre-allocated VectorValues \c grad
*
* @param bn The GaussianBayesNet on which to perform this computation
* @param [out] grad The resulting \f$ \delta x \f$ as described in optimizeGradientSearch(const GaussianBayesNet&)
* */
void optimizeGradientSearchInPlace(const GaussianBayesNet& bn, VectorValues& grad);
GTSAM_EXPORT void optimizeGradientSearchInPlace(const GaussianBayesNet& bn, VectorValues& grad);
/**
* Backsubstitute
* gy=inv(R*inv(Sigma))*gx
*/
VectorValues backSubstitute(const GaussianBayesNet& bn, const VectorValues& gx);
GTSAM_EXPORT VectorValues backSubstitute(const GaussianBayesNet& bn, const VectorValues& gx);
/**
* Transpose Backsubstitute
@ -118,12 +118,12 @@ namespace gtsam {
* gy=inv(R'*inv(Sigma))*gx
* gz'*R'=gx', gy = gz.*sigmas
*/
VectorValues backSubstituteTranspose(const GaussianBayesNet& bn, const VectorValues& gx);
GTSAM_EXPORT VectorValues backSubstituteTranspose(const GaussianBayesNet& bn, const VectorValues& gx);
/**
* Return (dense) upper-triangular matrix representation
*/
std::pair<Matrix, Vector> matrix(const GaussianBayesNet&);
GTSAM_EXPORT std::pair<Matrix, Vector> matrix(const GaussianBayesNet&);
/**
* Computes the determinant of a GassianBayesNet
@ -134,7 +134,7 @@ namespace gtsam {
* @param bayesNet The input GaussianBayesNet
* @return The determinant
*/
double determinant(const GaussianBayesNet& bayesNet);
GTSAM_EXPORT double determinant(const GaussianBayesNet& bayesNet);
/**
* Compute the gradient of the energy function,
@ -145,7 +145,7 @@ namespace gtsam {
* @param x0 The center about which to compute the gradient
* @return The gradient as a VectorValues
*/
VectorValues gradient(const GaussianBayesNet& bayesNet, const VectorValues& x0);
GTSAM_EXPORT VectorValues gradient(const GaussianBayesNet& bayesNet, const VectorValues& x0);
/**
* Compute the gradient of the energy function,
@ -156,6 +156,6 @@ namespace gtsam {
* @param [output] g A VectorValues to store the gradient, which must be preallocated, see allocateVectorValues
* @return The gradient as a VectorValues
*/
void gradientAtZero(const GaussianBayesNet& bayesNet, VectorValues& g);
GTSAM_EXPORT void gradientAtZero(const GaussianBayesNet& bayesNet, VectorValues& g);
} /// namespace gtsam

View File

@ -26,13 +26,13 @@
namespace gtsam {
/// A Bayes Tree representing a Gaussian density
typedef BayesTree<GaussianConditional> GaussianBayesTree;
GTSAM_EXPORT typedef BayesTree<GaussianConditional> GaussianBayesTree;
/// optimize the BayesTree, starting from the root
VectorValues optimize(const GaussianBayesTree& bayesTree);
GTSAM_EXPORT VectorValues optimize(const GaussianBayesTree& bayesTree);
/// recursively optimize this conditional and all subtrees
void optimizeInPlace(const GaussianBayesTree& bayesTree, VectorValues& result);
GTSAM_EXPORT void optimizeInPlace(const GaussianBayesTree& bayesTree, VectorValues& result);
namespace internal {
template<class BAYESTREE>
@ -64,10 +64,10 @@ void optimizeInPlace(const typename BAYESTREE::sharedClique& clique, VectorValue
*
* \f[ \delta x = \hat\alpha g = \frac{-g^T g}{(R g)^T(R g)} \f]
*/
VectorValues optimizeGradientSearch(const GaussianBayesTree& bayesTree);
GTSAM_EXPORT VectorValues optimizeGradientSearch(const GaussianBayesTree& bayesTree);
/** In-place version of optimizeGradientSearch requiring pre-allocated VectorValues \c x */
void optimizeGradientSearchInPlace(const GaussianBayesTree& bayesTree, VectorValues& grad);
GTSAM_EXPORT void optimizeGradientSearchInPlace(const GaussianBayesTree& bayesTree, VectorValues& grad);
/**
* Compute the gradient of the energy function,
@ -78,7 +78,7 @@ void optimizeGradientSearchInPlace(const GaussianBayesTree& bayesTree, VectorVal
* @param x0 The center about which to compute the gradient
* @return The gradient as a VectorValues
*/
VectorValues gradient(const GaussianBayesTree& bayesTree, const VectorValues& x0);
GTSAM_EXPORT VectorValues gradient(const GaussianBayesTree& bayesTree, const VectorValues& x0);
/**
* Compute the gradient of the energy function,
@ -89,7 +89,7 @@ VectorValues gradient(const GaussianBayesTree& bayesTree, const VectorValues& x0
* @param [output] g A VectorValues to store the gradient, which must be preallocated, see allocateVectorValues
* @return The gradient as a VectorValues
*/
void gradientAtZero(const GaussianBayesTree& bayesTree, VectorValues& g);
GTSAM_EXPORT void gradientAtZero(const GaussianBayesTree& bayesTree, VectorValues& g);
/**
* Computes the determinant of a GassianBayesTree
@ -100,7 +100,7 @@ void gradientAtZero(const GaussianBayesTree& bayesTree, VectorValues& g);
* @param bayesTree The input GassianBayesTree
* @return The determinant
*/
double determinant(const GaussianBayesTree& bayesTree);
GTSAM_EXPORT double determinant(const GaussianBayesTree& bayesTree);
namespace internal {

View File

@ -45,7 +45,7 @@ class JacobianFactor;
* It has a set of parents y,z, etc. and implements a probability density on x.
* The negative log-probability is given by \f$ \frac{1}{2} |Rx - (d - Sy - Tz - ...)|^2 \f$
*/
class GaussianConditional : public IndexConditional {
class GTSAM_EXPORT GaussianConditional : public IndexConditional {
public:
typedef GaussianFactor FactorType;

View File

@ -30,7 +30,7 @@ namespace gtsam {
* The negative log-probability is given by \f$ |Rx - d|^2 \f$
* with \f$ \Lambda = \Sigma^{-1} = R^T R \f$ and \f$ \mu = R^{-1} d \f$
*/
class GaussianDensity: public GaussianConditional {
class GTSAM_EXPORT GaussianDensity: public GaussianConditional {
public:

View File

@ -42,7 +42,7 @@ namespace gtsam {
* GaussianFactor is non-mutable (all methods const!).
* The factor value is exp(-0.5*||Ax-b||^2)
*/
class GaussianFactor: public IndexFactor {
class GTSAM_EXPORT GaussianFactor: public IndexFactor {
protected:

View File

@ -32,7 +32,7 @@
namespace gtsam {
// Forward declaration to use as default argument, documented declaration below.
FactorGraph<GaussianFactor>::EliminationResult
GTSAM_EXPORT FactorGraph<GaussianFactor>::EliminationResult
EliminateQR(const FactorGraph<GaussianFactor>& factors, size_t nrFrontals);
/**
@ -55,7 +55,7 @@ namespace gtsam {
/**
* Constructor that receives a Chordal Bayes Net and returns a GaussianFactorGraph
*/
GaussianFactorGraph(const GaussianBayesNet& CBN);
GTSAM_EXPORT GaussianFactorGraph(const GaussianBayesNet& CBN);
/**
* Constructor that receives a BayesTree and returns a GaussianFactorGraph
@ -116,7 +116,7 @@ namespace gtsam {
* union).
*/
typedef FastSet<Index> Keys;
Keys keys() const;
GTSAM_EXPORT Keys keys() const;
/** Eliminate the first \c n frontal variables, returning the resulting
@ -153,10 +153,10 @@ namespace gtsam {
return Base::eliminateOne(variable, function); }
/** Permute the variables in the factors */
void permuteWithInverse(const Permutation& inversePermutation);
GTSAM_EXPORT void permuteWithInverse(const Permutation& inversePermutation);
/** Apply a reduction, which is a remapping of variable indices. */
void reduceWithInverse(const internal::Reduction& inverseReduction);
GTSAM_EXPORT void reduceWithInverse(const internal::Reduction& inverseReduction);
/** unnormalized error */
double error(const VectorValues& x) const {
@ -177,28 +177,28 @@ namespace gtsam {
* @param lfg2 Linear factor graph
* @return a new combined factor graph
*/
static GaussianFactorGraph combine2(const GaussianFactorGraph& lfg1,
GTSAM_EXPORT static GaussianFactorGraph combine2(const GaussianFactorGraph& lfg1,
const GaussianFactorGraph& lfg2);
/**
* combine two factor graphs
* @param *lfg Linear factor graph
*/
void combine(const GaussianFactorGraph &lfg);
GTSAM_EXPORT void combine(const GaussianFactorGraph &lfg);
/**
* Return vector of i, j, and s to generate an m-by-n sparse Jacobian matrix,
* where i(k) and j(k) are the base 0 row and column indices, s(k) a double.
* The standard deviations are baked into A and b
*/
std::vector<boost::tuple<size_t, size_t, double> > sparseJacobian() const;
GTSAM_EXPORT std::vector<boost::tuple<size_t, size_t, double> > sparseJacobian() const;
/**
* Matrix version of sparseJacobian: generates a 3*m matrix with [i,j,s] entries
* such that S(i(k),j(k)) = s(k), which can be given to MATLAB's sparse.
* The standard deviations are baked into A and b
*/
Matrix sparseJacobian_() const;
GTSAM_EXPORT Matrix sparseJacobian_() const;
/**
* Return a dense \f$ [ \;A\;b\; ] \in \mathbb{R}^{m \times n+1} \f$
@ -207,7 +207,7 @@ namespace gtsam {
* \f$ \frac{1}{2} \Vert Ax-b \Vert^2 \f$. See also
* GaussianFactorGraph::jacobian and GaussianFactorGraph::sparseJacobian.
*/
Matrix augmentedJacobian() const;
GTSAM_EXPORT Matrix augmentedJacobian() const;
/**
* Return the dense Jacobian \f$ A \f$ and right-hand-side \f$ b \f$,
@ -216,7 +216,7 @@ namespace gtsam {
* GaussianFactorGraph::augmentedJacobian and
* GaussianFactorGraph::sparseJacobian.
*/
std::pair<Matrix,Vector> jacobian() const;
GTSAM_EXPORT std::pair<Matrix,Vector> jacobian() const;
/**
* Return a dense \f$ \Lambda \in \mathbb{R}^{n+1 \times n+1} \f$ Hessian
@ -229,7 +229,7 @@ namespace gtsam {
and the negative log-likelihood is
\f$ \frac{1}{2} x^T \Lambda x + \eta^T x + c \f$.
*/
Matrix augmentedHessian() const;
GTSAM_EXPORT Matrix augmentedHessian() const;
/**
* Return the dense Hessian \f$ \Lambda \f$ and information vector
@ -237,7 +237,7 @@ namespace gtsam {
* is \frac{1}{2} x^T \Lambda x + \eta^T x + c. See also
* GaussianFactorGraph::augmentedHessian.
*/
std::pair<Matrix,Vector> hessian() const;
GTSAM_EXPORT std::pair<Matrix,Vector> hessian() const;
private:
/** Serialization function */
@ -253,7 +253,7 @@ namespace gtsam {
* Combine and eliminate several factors.
* \addtogroup LinearSolving
*/
JacobianFactor::shared_ptr CombineJacobians(
GTSAM_EXPORT JacobianFactor::shared_ptr CombineJacobians(
const FactorGraph<JacobianFactor>& factors,
const VariableSlots& variableSlots);
@ -261,7 +261,7 @@ namespace gtsam {
* Evaluates whether linear factors have any constrained noise models
* @return true if any factor is constrained.
*/
bool hasConstraints(const FactorGraph<GaussianFactor>& factors);
GTSAM_EXPORT bool hasConstraints(const FactorGraph<GaussianFactor>& factors);
/**
* Densely combine and partially eliminate JacobianFactors to produce a
@ -274,7 +274,7 @@ namespace gtsam {
* \addtogroup LinearSolving
*/
GaussianFactorGraph::EliminationResult EliminateJacobians(const FactorGraph<
GTSAM_EXPORT GaussianFactorGraph::EliminationResult EliminateJacobians(const FactorGraph<
JacobianFactor>& factors, size_t nrFrontals = 1);
/**
@ -289,7 +289,7 @@ namespace gtsam {
* \addtogroup LinearSolving
*/
GaussianFactorGraph::EliminationResult EliminateQR(const FactorGraph<
GTSAM_EXPORT GaussianFactorGraph::EliminationResult EliminateQR(const FactorGraph<
GaussianFactor>& factors, size_t nrFrontals = 1);
/**
@ -311,7 +311,7 @@ namespace gtsam {
* \addtogroup LinearSolving
*/
GaussianFactorGraph::EliminationResult EliminatePreferCholesky(const FactorGraph<
GTSAM_EXPORT GaussianFactorGraph::EliminationResult EliminatePreferCholesky(const FactorGraph<
GaussianFactor>& factors, size_t nrFrontals = 1);
/**
@ -332,22 +332,22 @@ namespace gtsam {
* \addtogroup LinearSolving
*/
GaussianFactorGraph::EliminationResult EliminateCholesky(const FactorGraph<
GTSAM_EXPORT GaussianFactorGraph::EliminationResult EliminateCholesky(const FactorGraph<
GaussianFactor>& factors, size_t nrFrontals = 1);
/****** Linear Algebra Opeations ******/
/** return A*x */
Errors operator*(const GaussianFactorGraph& fg, const VectorValues& x);
GTSAM_EXPORT Errors operator*(const GaussianFactorGraph& fg, const VectorValues& x);
/** In-place version e <- A*x that overwrites e. */
void multiplyInPlace(const GaussianFactorGraph& fg, const VectorValues& x, Errors& e);
GTSAM_EXPORT void multiplyInPlace(const GaussianFactorGraph& fg, const VectorValues& x, Errors& e);
/** In-place version e <- A*x that takes an iterator. */
void multiplyInPlace(const GaussianFactorGraph& fg, const VectorValues& x, const Errors::iterator& e);
GTSAM_EXPORT void multiplyInPlace(const GaussianFactorGraph& fg, const VectorValues& x, const Errors::iterator& e);
/** x += alpha*A'*e */
void transposeMultiplyAdd(const GaussianFactorGraph& fg, double alpha, const Errors& e, VectorValues& x);
GTSAM_EXPORT void transposeMultiplyAdd(const GaussianFactorGraph& fg, double alpha, const Errors& e, VectorValues& x);
/**
* Compute the gradient of the energy function,
@ -358,7 +358,7 @@ namespace gtsam {
* @param x0 The center about which to compute the gradient
* @return The gradient as a VectorValues
*/
VectorValues gradient(const GaussianFactorGraph& fg, const VectorValues& x0);
GTSAM_EXPORT VectorValues gradient(const GaussianFactorGraph& fg, const VectorValues& x0);
/**
* Compute the gradient of the energy function,
@ -369,16 +369,16 @@ namespace gtsam {
* @param [output] g A VectorValues to store the gradient, which must be preallocated, see allocateVectorValues
* @return The gradient as a VectorValues
*/
void gradientAtZero(const GaussianFactorGraph& fg, VectorValues& g);
GTSAM_EXPORT void gradientAtZero(const GaussianFactorGraph& fg, VectorValues& g);
/* matrix-vector operations */
void residual(const GaussianFactorGraph& fg, const VectorValues &x, VectorValues &r);
void multiply(const GaussianFactorGraph& fg, const VectorValues &x, VectorValues &r);
void transposeMultiply(const GaussianFactorGraph& fg, const VectorValues &r, VectorValues &x);
GTSAM_EXPORT void residual(const GaussianFactorGraph& fg, const VectorValues &x, VectorValues &r);
GTSAM_EXPORT void multiply(const GaussianFactorGraph& fg, const VectorValues &x, VectorValues &r);
GTSAM_EXPORT void transposeMultiply(const GaussianFactorGraph& fg, const VectorValues &r, VectorValues &x);
/** shared pointer version
* \todo Make this a member function - affects SubgraphPreconditioner */
boost::shared_ptr<Errors> gaussianErrors_(const GaussianFactorGraph& fg, const VectorValues& x);
GTSAM_EXPORT boost::shared_ptr<Errors> gaussianErrors_(const GaussianFactorGraph& fg, const VectorValues& x);
/** return A*x-b
* \todo Make this a member function - affects SubgraphPreconditioner */

View File

@ -81,22 +81,22 @@ public:
const Dims& dims() const { return dims_; } ///< Const access to dimensions structure
Dims& dims() { return dims_; } ///< non-const access to dimensions structure (advanced interface)
friend VectorValues optimize(const GaussianISAM&);
GTSAM_EXPORT friend VectorValues optimize(const GaussianISAM&);
/** return marginal on any variable as a factor, Bayes net, or mean/cov */
GaussianFactor::shared_ptr marginalFactor(Index j) const;
BayesNet<GaussianConditional>::shared_ptr marginalBayesNet(Index key) const;
Matrix marginalCovariance(Index key) const;
GTSAM_EXPORT GaussianFactor::shared_ptr marginalFactor(Index j) const;
GTSAM_EXPORT BayesNet<GaussianConditional>::shared_ptr marginalBayesNet(Index key) const;
GTSAM_EXPORT Matrix marginalCovariance(Index key) const;
/** return joint between two variables, as a Bayes net */
BayesNet<GaussianConditional>::shared_ptr jointBayesNet(Index key1, Index key2) const;
GTSAM_EXPORT BayesNet<GaussianConditional>::shared_ptr jointBayesNet(Index key1, Index key2) const;
/** return the conditional P(S|Root) on the separator given the root */
static BayesNet<GaussianConditional> shortcut(sharedClique clique, sharedClique root);
GTSAM_EXPORT static BayesNet<GaussianConditional> shortcut(sharedClique clique, sharedClique root);
}; // \class GaussianISAM
// optimize the BayesTree, starting from the root
VectorValues optimize(const GaussianISAM& isam);
GTSAM_EXPORT VectorValues optimize(const GaussianISAM& isam);
} // \namespace gtsam

View File

@ -60,7 +60,7 @@ namespace gtsam {
/**
* optimize the linear graph
*/
VectorValues optimize(Eliminate function) const;
GTSAM_EXPORT VectorValues optimize(Eliminate function) const;
// convenient function to return dimensions of all variables in the BayesTree<GaussianConditional>
template<class DIM_CONTAINER, class CLIQUE>

View File

@ -57,21 +57,21 @@ public:
* Construct the solver for a factor graph. This builds the junction
* tree, which already does some of the work of elimination.
*/
GaussianMultifrontalSolver(const FactorGraph<GaussianFactor>& factorGraph, bool useQR = false);
GTSAM_EXPORT GaussianMultifrontalSolver(const FactorGraph<GaussianFactor>& factorGraph, bool useQR = false);
/**
* Construct the solver with a shared pointer to a factor graph and to a
* VariableIndex. The solver will store these pointers, so this constructor
* is the fastest.
*/
GaussianMultifrontalSolver(const FactorGraph<GaussianFactor>::shared_ptr& factorGraph,
GTSAM_EXPORT GaussianMultifrontalSolver(const FactorGraph<GaussianFactor>::shared_ptr& factorGraph,
const VariableIndex::shared_ptr& variableIndex, bool useQR = false);
/**
* Named constructor to return a shared_ptr. This builds the elimination
* tree, which already does some of the symbolic work of elimination.
*/
static shared_ptr Create(const FactorGraph<GaussianFactor>::shared_ptr& factorGraph,
GTSAM_EXPORT static shared_ptr Create(const FactorGraph<GaussianFactor>::shared_ptr& factorGraph,
const VariableIndex::shared_ptr& variableIndex, bool useQR = false);
/**
@ -81,20 +81,20 @@ public:
* used in cases where the numerical values of the linear problem change,
* e.g. during iterative nonlinear optimization.
*/
void replaceFactors(const FactorGraph<GaussianFactor>::shared_ptr& factorGraph);
GTSAM_EXPORT void replaceFactors(const FactorGraph<GaussianFactor>::shared_ptr& factorGraph);
/**
* Eliminate the factor graph sequentially. Uses a column elimination tree
* to recursively eliminate.
*/
GaussianBayesTree::shared_ptr eliminate() const;
GTSAM_EXPORT GaussianBayesTree::shared_ptr eliminate() const;
/**
* Compute the least-squares solution of the GaussianFactorGraph. This
* eliminates to create a BayesNet and then back-substitutes this BayesNet to
* obtain the solution.
*/
VectorValues::shared_ptr optimize() const;
GTSAM_EXPORT VectorValues::shared_ptr optimize() const;
/**
* Compute the marginal joint over a set of variables, by integrating out
@ -103,7 +103,7 @@ public:
*
* NOTE: This function is limited to computing a joint on 2 variables
*/
GaussianFactorGraph::shared_ptr jointFactorGraph(const std::vector<Index>& js) const;
GTSAM_EXPORT GaussianFactorGraph::shared_ptr jointFactorGraph(const std::vector<Index>& js) const;
/**
* Compute the marginal Gaussian density over a variable, by integrating out
@ -111,7 +111,7 @@ public:
* triangular R factor and right-hand-side, i.e. a GaussianConditional with
* R*x = d. To get a mean and covariance matrix, use marginalStandard(...)
*/
GaussianFactor::shared_ptr marginalFactor(Index j) const;
GTSAM_EXPORT GaussianFactor::shared_ptr marginalFactor(Index j) const;
/**
* Compute the marginal Gaussian density over a variable, by integrating out
@ -120,7 +120,7 @@ public:
* returns a GaussianConditional, this function back-substitutes the R factor
* to obtain the mean, then computes \f$ \Sigma = (R^T * R)^{-1} \f$.
*/
Matrix marginalCovariance(Index j) const;
GTSAM_EXPORT Matrix marginalCovariance(Index j) const;
/** @return true if using QR */
inline bool usingQR() const { return useQR_; }

View File

@ -63,21 +63,21 @@ public:
* Construct the solver for a factor graph. This builds the elimination
* tree, which already does some of the work of elimination.
*/
GaussianSequentialSolver(const FactorGraph<GaussianFactor>& factorGraph, bool useQR = false);
GTSAM_EXPORT GaussianSequentialSolver(const FactorGraph<GaussianFactor>& factorGraph, bool useQR = false);
/**
* Construct the solver with a shared pointer to a factor graph and to a
* VariableIndex. The solver will store these pointers, so this constructor
* is the fastest.
*/
GaussianSequentialSolver(const FactorGraph<GaussianFactor>::shared_ptr& factorGraph,
GTSAM_EXPORT GaussianSequentialSolver(const FactorGraph<GaussianFactor>::shared_ptr& factorGraph,
const VariableIndex::shared_ptr& variableIndex, bool useQR = false);
/**
* Named constructor to return a shared_ptr. This builds the elimination
* tree, which already does some of the symbolic work of elimination.
*/
static shared_ptr Create(const FactorGraph<GaussianFactor>::shared_ptr& factorGraph,
GTSAM_EXPORT static shared_ptr Create(const FactorGraph<GaussianFactor>::shared_ptr& factorGraph,
const VariableIndex::shared_ptr& variableIndex, bool useQR = false);
/**
@ -87,20 +87,20 @@ public:
* used in cases where the numerical values of the linear problem change,
* e.g. during iterative nonlinear optimization.
*/
void replaceFactors(const FactorGraph<GaussianFactor>::shared_ptr& factorGraph);
GTSAM_EXPORT void replaceFactors(const FactorGraph<GaussianFactor>::shared_ptr& factorGraph);
/**
* Eliminate the factor graph sequentially. Uses a column elimination tree
* to recursively eliminate.
*/
GaussianBayesNet::shared_ptr eliminate() const;
GTSAM_EXPORT GaussianBayesNet::shared_ptr eliminate() const;
/**
* Compute the least-squares solution of the GaussianFactorGraph. This
* eliminates to create a BayesNet and then back-substitutes this BayesNet to
* obtain the solution.
*/
VectorValues::shared_ptr optimize() const;
GTSAM_EXPORT VectorValues::shared_ptr optimize() const;
/**
* Compute the marginal Gaussian density over a variable, by integrating out
@ -108,7 +108,7 @@ public:
* triangular R factor and right-hand-side, i.e. a GaussianConditional with
* R*x = d. To get a mean and covariance matrix, use marginalStandard(...)
*/
GaussianFactor::shared_ptr marginalFactor(Index j) const;
GTSAM_EXPORT GaussianFactor::shared_ptr marginalFactor(Index j) const;
/**
* Compute the marginal Gaussian density over a variable, by integrating out
@ -117,7 +117,7 @@ public:
* returns a GaussianConditional, this function back-substitutes the R factor
* to obtain the mean, then computes \f$ \Sigma = (R^T * R)^{-1} \f$.
*/
Matrix marginalCovariance(Index j) const;
GTSAM_EXPORT Matrix marginalCovariance(Index j) const;
/**
* Compute the marginal joint over a set of variables, by integrating out
@ -125,7 +125,7 @@ public:
* triangular R factor and right-hand-side, i.e. a GaussianBayesNet with
* R*x = d. To get a mean and covariance matrix, use jointStandard(...)
*/
GaussianFactorGraph::shared_ptr jointFactorGraph(const std::vector<Index>& js) const;
GTSAM_EXPORT GaussianFactorGraph::shared_ptr jointFactorGraph(const std::vector<Index>& js) const;
};

View File

@ -39,7 +39,7 @@ namespace gtsam {
// Definition of Scatter, which is an intermediate data structure used when
// building a HessianFactor incrementally, to get the keys in the right
// order.
struct SlotEntry {
struct GTSAM_EXPORT SlotEntry {
size_t slot;
size_t dimension;
SlotEntry(size_t _slot, size_t _dimension)
@ -111,7 +111,7 @@ namespace gtsam {
.......
\endcode
*/
class HessianFactor : public GaussianFactor {
class GTSAM_EXPORT HessianFactor : public GaussianFactor {
protected:
typedef Matrix InfoMatrix; ///< The full augmented Hessian
typedef SymmetricBlockView<InfoMatrix> BlockInfo; ///< A blockwise view of the Hessian

View File

@ -20,7 +20,7 @@ namespace gtsam {
/**
* parameters for iterative linear solvers
*/
class IterativeOptimizationParameters {
class GTSAM_EXPORT IterativeOptimizationParameters {
public:
@ -60,7 +60,7 @@ namespace gtsam {
static std::string verbosityTranslator(Verbosity v);
};
class IterativeSolver {
class GTSAM_EXPORT IterativeSolver {
public:
typedef boost::shared_ptr<IterativeSolver> shared_ptr;
IterativeSolver() {}

View File

@ -78,7 +78,7 @@ namespace gtsam {
* and the negative log-likelihood represented by this factor would be
* \f[ E(x) = \frac{1}{2} (A_1 x_{j1} + A_2 x_{j2} - b)^T \Sigma^{-1} (A_1 x_{j1} + A_2 x_{j2} - b) . \f]
*/
class JacobianFactor : public GaussianFactor {
class GTSAM_EXPORT JacobianFactor : public GaussianFactor {
protected:
typedef Matrix AbMatrix;
typedef VerticalBlockView<AbMatrix> BlockAb;

View File

@ -37,7 +37,7 @@ namespace gtsam {
* The filter is functional, in that it does not have state: you call init() to create
* an initial state, then predict() and update() that create new states out of old.
*/
class KalmanFilter {
class GTSAM_EXPORT KalmanFilter {
public:

View File

@ -44,7 +44,7 @@ namespace gtsam {
* Noise models must implement a 'whiten' function to normalize an error vector,
* and an 'unwhiten' function to unnormalize an error vector.
*/
class Base {
class GTSAM_EXPORT Base {
public:
typedef boost::shared_ptr<Base> shared_ptr;
@ -116,7 +116,7 @@ namespace gtsam {
* The named constructors return a shared_ptr because, when the smart flag is true,
* the underlying object might be a derived class such as Diagonal.
*/
class Gaussian: public Base {
class GTSAM_EXPORT Gaussian: public Base {
protected:
@ -232,7 +232,7 @@ namespace gtsam {
* elements of the diagonal specified in a Vector. This class has no public
* constructors, instead, use the static constructor functions Sigmas etc...
*/
class Diagonal : public Gaussian {
class GTSAM_EXPORT Diagonal : public Gaussian {
protected:
/** sigmas and reciprocal */
@ -330,7 +330,7 @@ namespace gtsam {
* The distance function in this function provides an error model
* for a penalty function with a scaling function, assuming a mask of
*/
class Constrained : public Diagonal {
class GTSAM_EXPORT Constrained : public Diagonal {
protected:
// Sigmas are contained in the base class
@ -470,7 +470,7 @@ namespace gtsam {
* An isotropic noise model corresponds to a scaled diagonal covariance
* To construct, use one of the static methods
*/
class Isotropic : public Diagonal {
class GTSAM_EXPORT Isotropic : public Diagonal {
protected:
double sigma_, invsigma_;
@ -536,7 +536,7 @@ namespace gtsam {
/**
* Unit: i.i.d. unit-variance noise on all m dimensions.
*/
class Unit : public Isotropic {
class GTSAM_EXPORT Unit : public Isotropic {
protected:
Unit(size_t dim=1): Isotropic(dim,1.0) {}
@ -576,7 +576,7 @@ namespace gtsam {
//---------------------------------------------------------------------------------------
class Base {
class GTSAM_EXPORT Base {
public:
enum ReweightScheme { Scalar, Block };
typedef boost::shared_ptr<Base> shared_ptr;
@ -616,7 +616,7 @@ namespace gtsam {
};
/// Null class is not robust so is a Gaussian ?
class Null : public Base {
class GTSAM_EXPORT Null : public Base {
public:
typedef boost::shared_ptr<Null> shared_ptr;
Null(const ReweightScheme reweight = Block) : Base(reweight) {}
@ -628,7 +628,7 @@ namespace gtsam {
};
/// Fair implements the "Fair" robust error model (Zhang97ivc)
class Fair : public Base {
class GTSAM_EXPORT Fair : public Base {
public:
typedef boost::shared_ptr<Fair> shared_ptr;
protected:
@ -645,7 +645,7 @@ namespace gtsam {
};
/// Huber implements the "Huber" robust error model (Zhang97ivc)
class Huber : public Base {
class GTSAM_EXPORT Huber : public Base {
public:
typedef boost::shared_ptr<Huber> shared_ptr;
protected:
@ -662,7 +662,7 @@ namespace gtsam {
};
/// Tukey implements the "Tukey" robust error model (Zhang97ivc)
class Tukey : public Base {
class GTSAM_EXPORT Tukey : public Base {
public:
typedef boost::shared_ptr<Tukey> shared_ptr;
protected:
@ -681,7 +681,7 @@ namespace gtsam {
} ///\namespace mEstimator
/// Base class for robust error models
class Robust : public Base {
class GTSAM_EXPORT Robust : public Base {
public:
typedef boost::shared_ptr<Robust> shared_ptr;

View File

@ -31,7 +31,7 @@ namespace gtsam {
* This is primarily to allow for variable seeds, and does roughly the same
* thing as sample() in NoiseModel.
*/
class Sampler {
class GTSAM_EXPORT Sampler {
protected:
/** noiseModel created at generation */
noiseModel::Diagonal::shared_ptr model_;

View File

@ -30,7 +30,7 @@ namespace gtsam {
* To use the class, give the Bayes Net R1*x=c1 and Graph A2*x=b2.
* Then solve for yhat using CG, and solve for xhat = system.x(yhat).
*/
class SubgraphPreconditioner {
class GTSAM_EXPORT SubgraphPreconditioner {
public:
typedef boost::shared_ptr<SubgraphPreconditioner> shared_ptr;
@ -94,24 +94,24 @@ namespace gtsam {
};
/* error, given y */
double error(const SubgraphPreconditioner& sp, const VectorValues& y);
GTSAM_EXPORT double error(const SubgraphPreconditioner& sp, const VectorValues& y);
/** gradient = y + inv(R1')*A2'*(A2*inv(R1)*y-b2bar) */
VectorValues gradient(const SubgraphPreconditioner& sp, const VectorValues& y);
GTSAM_EXPORT VectorValues gradient(const SubgraphPreconditioner& sp, const VectorValues& y);
/** Apply operator A */
Errors operator*(const SubgraphPreconditioner& sp, const VectorValues& y);
GTSAM_EXPORT Errors operator*(const SubgraphPreconditioner& sp, const VectorValues& y);
/** Apply operator A in place: needs e allocated already */
void multiplyInPlace(const SubgraphPreconditioner& sp, const VectorValues& y, Errors& e);
GTSAM_EXPORT void multiplyInPlace(const SubgraphPreconditioner& sp, const VectorValues& y, Errors& e);
/** Apply operator A' */
VectorValues operator^(const SubgraphPreconditioner& sp, const Errors& e);
GTSAM_EXPORT VectorValues operator^(const SubgraphPreconditioner& sp, const Errors& e);
/**
* Add A'*e to y
* y += alpha*A'*[e1;e2] = [alpha*e1; alpha*inv(R1')*A2'*e2]
*/
void transposeMultiplyAdd(const SubgraphPreconditioner& sp, double alpha, const Errors& e, VectorValues& y);
GTSAM_EXPORT void transposeMultiplyAdd(const SubgraphPreconditioner& sp, double alpha, const Errors& e, VectorValues& y);
} // namespace gtsam

View File

@ -19,7 +19,7 @@
namespace gtsam {
class SubgraphSolverParameters : public ConjugateGradientParameters {
class GTSAM_EXPORT SubgraphSolverParameters : public ConjugateGradientParameters {
public:
typedef ConjugateGradientParameters Base;
SubgraphSolverParameters() : Base() {}
@ -48,7 +48,7 @@ public:
* \nosubgrouping
*/
class SubgraphSolver : public IterativeSolver {
class GTSAM_EXPORT SubgraphSolver : public IterativeSolver {
public:
typedef SubgraphSolverParameters Parameters;

View File

@ -91,7 +91,7 @@ namespace gtsam {
* This class is additionally used in gradient descent and dog leg to store the gradient.
* \nosubgrouping
*/
class VectorValues {
class GTSAM_EXPORT VectorValues {
protected:
typedef std::vector<Vector> Values; ///< Typedef for the collection of Vectors making up a VectorValues
Values values_; ///< Collection of Vectors making up this VectorValues

View File

@ -41,7 +41,7 @@ namespace gtsam {
* Helper class encapsulating the combined system |Ax-b_|^2
* Needed to run Conjugate Gradients on matrices
* */
class System {
class GTSAM_EXPORT System {
private:
const Matrix& A_;
@ -93,7 +93,7 @@ namespace gtsam {
/**
* Method of steepest gradients, System version
*/
Vector steepestDescent(
GTSAM_EXPORT Vector steepestDescent(
const System& Ab,
const Vector& x,
const IterativeOptimizationParameters & parameters);
@ -101,7 +101,7 @@ namespace gtsam {
/**
* Method of conjugate gradients (CG), System version
*/
Vector conjugateGradientDescent(
GTSAM_EXPORT Vector conjugateGradientDescent(
const System& Ab,
const Vector& x,
const ConjugateGradientParameters & parameters);
@ -111,7 +111,7 @@ namespace gtsam {
/**
* Method of steepest gradients, Matrix version
*/
Vector steepestDescent(
GTSAM_EXPORT Vector steepestDescent(
const Matrix& A,
const Vector& b,
const Vector& x,
@ -120,7 +120,7 @@ namespace gtsam {
/**
* Method of conjugate gradients (CG), Matrix version
*/
Vector conjugateGradientDescent(
GTSAM_EXPORT Vector conjugateGradientDescent(
const Matrix& A,
const Vector& b,
const Vector& x,
@ -129,7 +129,7 @@ namespace gtsam {
/**
* Method of steepest gradients, Gaussian Factor Graph version
*/
VectorValues steepestDescent(
GTSAM_EXPORT VectorValues steepestDescent(
const GaussianFactorGraph& fg,
const VectorValues& x,
const ConjugateGradientParameters & parameters);
@ -137,7 +137,7 @@ namespace gtsam {
/**
* Method of conjugate gradients (CG), Gaussian Factor Graph version
*/
VectorValues conjugateGradientDescent(
GTSAM_EXPORT VectorValues conjugateGradientDescent(
const GaussianFactorGraph& fg,
const VectorValues& x,
const ConjugateGradientParameters & parameters);

View File

@ -29,7 +29,7 @@ class DoglegOptimizer;
* common to all nonlinear optimization algorithms. This class also contains
* all of those parameters.
*/
class DoglegParams : public SuccessiveLinearizationParams {
class GTSAM_EXPORT DoglegParams : public SuccessiveLinearizationParams {
public:
/** See DoglegParams::dlVerbosity */
enum VerbosityDL {
@ -65,7 +65,7 @@ private:
/**
* State for DoglegOptimizer
*/
class DoglegState : public NonlinearOptimizerState {
class GTSAM_EXPORT DoglegState : public NonlinearOptimizerState {
public:
double Delta;
@ -83,7 +83,7 @@ protected:
/**
* This class performs Dogleg nonlinear optimization
*/
class DoglegOptimizer : public NonlinearOptimizer {
class GTSAM_EXPORT DoglegOptimizer : public NonlinearOptimizer {
protected:
DoglegParams params_;

View File

@ -38,9 +38,9 @@ namespace gtsam {
* currently either GaussianSequentialSolver or GaussianMultifrontalSolver.
* The latter is typically faster, especially for non-trivial problems.
*/
struct DoglegOptimizerImpl {
struct GTSAM_EXPORT DoglegOptimizerImpl {
struct IterationResult {
struct GTSAM_EXPORT IterationResult {
double Delta;
VectorValues dx_d;
double f_error;

View File

@ -27,10 +27,10 @@ class GaussNewtonOptimizer;
/** Parameters for Gauss-Newton optimization, inherits from
* NonlinearOptimizationParams.
*/
class GaussNewtonParams : public SuccessiveLinearizationParams {
class GTSAM_EXPORT GaussNewtonParams : public SuccessiveLinearizationParams {
};
class GaussNewtonState : public NonlinearOptimizerState {
class GTSAM_EXPORT GaussNewtonState : public NonlinearOptimizerState {
protected:
GaussNewtonState(const NonlinearFactorGraph& graph, const Values& values, unsigned int iterations = 0) :
NonlinearOptimizerState(graph, values, iterations) {}
@ -41,7 +41,7 @@ protected:
/**
* This class performs Gauss-Newton nonlinear optimization
*/
class GaussNewtonOptimizer : public NonlinearOptimizer {
class GTSAM_EXPORT GaussNewtonOptimizer : public NonlinearOptimizer {
protected:
GaussNewtonParams params_;

View File

@ -22,16 +22,16 @@
namespace gtsam {
struct ISAM2::Impl {
struct GTSAM_EXPORT ISAM2::Impl {
struct PartialSolveResult {
struct GTSAM_EXPORT PartialSolveResult {
ISAM2::sharedClique bayesTree;
Permutation reorderingSelector;
Permutation reorderingPermutation;
internal::Reduction reorderingInverse;
};
struct ReorderingMode {
struct GTSAM_EXPORT ReorderingMode {
size_t nFullSystemVars;
enum { /*AS_ADDED,*/ COLAMD } algorithm;
enum { NO_CONSTRAINT, CONSTRAIN_LAST } constrain;

View File

@ -33,7 +33,7 @@ namespace gtsam {
* ISAM2DoglegParams should be specified as the optimizationParams in
* ISAM2Params, which should in turn be passed to ISAM2(const ISAM2Params&).
*/
struct ISAM2GaussNewtonParams {
struct GTSAM_EXPORT ISAM2GaussNewtonParams {
double wildfireThreshold; ///< Continue updating the linear delta only when changes are above this threshold (default: 0.001)
/** Specify parameters as constructor arguments */
@ -57,7 +57,7 @@ struct ISAM2GaussNewtonParams {
* ISAM2GaussNewtonParams should be specified as the optimizationParams in
* ISAM2Params, which should in turn be passed to ISAM2(const ISAM2Params&).
*/
struct ISAM2DoglegParams {
struct GTSAM_EXPORT ISAM2DoglegParams {
double initialDelta; ///< The initial trust region radius for Dogleg
double wildfireThreshold; ///< Continue updating the linear delta only when changes are above this threshold (default: 1e-5)
DoglegOptimizerImpl::TrustRegionAdaptationMode adaptationMode; ///< See description in DoglegOptimizerImpl::TrustRegionAdaptationMode
@ -100,7 +100,7 @@ struct ISAM2DoglegParams {
*/
typedef FastMap<char,Vector> ISAM2ThresholdMap;
typedef ISAM2ThresholdMap::value_type ISAM2ThresholdMapValue;
struct ISAM2Params {
struct GTSAM_EXPORT ISAM2Params {
typedef boost::variant<ISAM2GaussNewtonParams, ISAM2DoglegParams> OptimizationParams; ///< Either ISAM2GaussNewtonParams or ISAM2DoglegParams
typedef boost::variant<double, FastMap<char,Vector> > RelinearizationThreshold; ///< Either a constant relinearization threshold or a per-variable-type set of thresholds
@ -242,7 +242,7 @@ struct ISAM2Params {
* converging, and about how much work was required for the update. See member
* variables for details and information about each entry.
*/
struct ISAM2Result {
struct GTSAM_EXPORT ISAM2Result {
/** The nonlinear error of all of the factors, \a including new factors and
* variables added during the current call to ISAM2::update(). This error is
* calculated using the following variable values:
@ -339,7 +339,7 @@ struct ISAM2Result {
* Specialized Clique structure for ISAM2, incorporating caching and gradient contribution
* TODO: more documentation
*/
class ISAM2Clique : public BayesTreeCliqueBase<ISAM2Clique, GaussianConditional> {
class GTSAM_EXPORT ISAM2Clique : public BayesTreeCliqueBase<ISAM2Clique, GaussianConditional> {
public:
typedef ISAM2Clique This;
typedef BayesTreeCliqueBase<This,GaussianConditional> Base;
@ -504,16 +504,16 @@ public:
typedef BayesTree<GaussianConditional,ISAM2Clique> Base; ///< The BayesTree base class
/** Create an empty ISAM2 instance */
ISAM2(const ISAM2Params& params);
GTSAM_EXPORT ISAM2(const ISAM2Params& params);
/** Create an empty ISAM2 instance using the default set of parameters (see ISAM2Params) */
ISAM2();
GTSAM_EXPORT ISAM2();
/** Copy constructor */
ISAM2(const ISAM2& other);
GTSAM_EXPORT ISAM2(const ISAM2& other);
/** Assignment operator */
ISAM2& operator=(const ISAM2& rhs);
GTSAM_EXPORT ISAM2& operator=(const ISAM2& rhs);
typedef Base::Clique Clique; ///< A clique
typedef Base::sharedClique sharedClique; ///< Shared pointer to a clique
@ -543,13 +543,13 @@ public:
* be constrained to a particular grouping in the BayesTree
* @return An ISAM2Result struct containing information about the update
*/
ISAM2Result update(const NonlinearFactorGraph& newFactors = NonlinearFactorGraph(), const Values& newTheta = Values(),
GTSAM_EXPORT ISAM2Result update(const NonlinearFactorGraph& newFactors = NonlinearFactorGraph(), const Values& newTheta = Values(),
const FastVector<size_t>& removeFactorIndices = FastVector<size_t>(),
const boost::optional<FastMap<Key,int> >& constrainedKeys = boost::none,
const boost::optional<FastList<Key> >& noRelinKeys = boost::none,
bool force_relinearize = false);
void experimentalMarginalizeLeaves(const FastList<Key>& leafKeys);
GTSAM_EXPORT void experimentalMarginalizeLeaves(const FastList<Key>& leafKeys);
/** Access the current linearization point */
const Values& getLinearizationPoint() const { return theta_; }
@ -558,7 +558,7 @@ public:
* This delta is incomplete because it was not updated below wildfire_threshold. If only
* a single variable is needed, it is faster to call calculateEstimate(const KEY&).
*/
Values calculateEstimate() const;
GTSAM_EXPORT Values calculateEstimate() const;
/** Compute an estimate for a single variable using its incomplete linear delta computed
* during the last update. This is faster than calling the no-argument version of
@ -577,19 +577,19 @@ public:
/** Compute an estimate using a complete delta computed by a full back-substitution.
*/
Values calculateBestEstimate() const;
GTSAM_EXPORT Values calculateBestEstimate() const;
/** Access the current delta, computed during the last call to update */
const VectorValues& getDelta() const;
GTSAM_EXPORT const VectorValues& getDelta() const;
/** Access the set of nonlinear factors */
const NonlinearFactorGraph& getFactorsUnsafe() const { return nonlinearFactors_; }
GTSAM_EXPORT const NonlinearFactorGraph& getFactorsUnsafe() const { return nonlinearFactors_; }
/** Access the current ordering */
const Ordering& getOrdering() const { return ordering_; }
GTSAM_EXPORT const Ordering& getOrdering() const { return ordering_; }
/** Access the nonlinear variable index */
const VariableIndex& getVariableIndex() const { return variableIndex_; }
GTSAM_EXPORT const VariableIndex& getVariableIndex() const { return variableIndex_; }
size_t lastAffectedVariableCount;
size_t lastAffectedFactorCount;
@ -598,34 +598,34 @@ public:
mutable size_t lastBacksubVariableCount;
size_t lastNnzTop;
const ISAM2Params& params() const { return params_; }
GTSAM_EXPORT const ISAM2Params& params() const { return params_; }
/** prints out clique statistics */
void printStats() const { getCliqueData().getStats().print(); }
GTSAM_EXPORT void printStats() const { getCliqueData().getStats().print(); }
//@}
private:
FastList<size_t> getAffectedFactors(const FastList<Index>& keys) const;
FactorGraph<GaussianFactor>::shared_ptr relinearizeAffectedFactors(const FastList<Index>& affectedKeys, const FastSet<Index>& relinKeys) const;
GaussianFactorGraph getCachedBoundaryFactors(Cliques& orphans);
GTSAM_EXPORT FastList<size_t> getAffectedFactors(const FastList<Index>& keys) const;
GTSAM_EXPORT FactorGraph<GaussianFactor>::shared_ptr relinearizeAffectedFactors(const FastList<Index>& affectedKeys, const FastSet<Index>& relinKeys) const;
GTSAM_EXPORT GaussianFactorGraph getCachedBoundaryFactors(Cliques& orphans);
boost::shared_ptr<FastSet<Index> > recalculate(const FastSet<Index>& markedKeys, const FastSet<Index>& relinKeys,
GTSAM_EXPORT boost::shared_ptr<FastSet<Index> > recalculate(const FastSet<Index>& markedKeys, const FastSet<Index>& relinKeys,
const FastVector<Index>& observedKeys, const FastSet<Index>& unusedIndices, const boost::optional<FastMap<Index,int> >& constrainKeys, ISAM2Result& result);
// void linear_update(const GaussianFactorGraph& newFactors);
void updateDelta(bool forceFullSolve = false) const;
GTSAM_EXPORT void updateDelta(bool forceFullSolve = false) const;
friend void optimizeInPlace(const ISAM2&, VectorValues&);
friend void optimizeGradientSearchInPlace(const ISAM2&, VectorValues&);
GTSAM_EXPORT friend void optimizeInPlace(const ISAM2&, VectorValues&);
GTSAM_EXPORT friend void optimizeGradientSearchInPlace(const ISAM2&, VectorValues&);
}; // ISAM2
/** Get the linear delta for the ISAM2 object, unpermuted the delta returned by ISAM2::getDelta() */
VectorValues optimize(const ISAM2& isam);
GTSAM_EXPORT VectorValues optimize(const ISAM2& isam);
/** Get the linear delta for the ISAM2 object, unpermuted the delta returned by ISAM2::getDelta() */
void optimizeInPlace(const ISAM2& isam, VectorValues& delta);
GTSAM_EXPORT void optimizeInPlace(const ISAM2& isam, VectorValues& delta);
/// Optimize the BayesTree, starting from the root.
/// @param replaced Needs to contain
@ -671,10 +671,10 @@ int optimizeWildfireNonRecursive(const boost::shared_ptr<CLIQUE>& root,
*
* \f[ \delta x = \hat\alpha g = \frac{-g^T g}{(R g)^T(R g)} \f]
*/
VectorValues optimizeGradientSearch(const ISAM2& isam);
GTSAM_EXPORT VectorValues optimizeGradientSearch(const ISAM2& isam);
/** In-place version of optimizeGradientSearch requiring pre-allocated VectorValues \c x */
void optimizeGradientSearchInPlace(const ISAM2& isam, VectorValues& grad);
GTSAM_EXPORT void optimizeGradientSearchInPlace(const ISAM2& isam, VectorValues& grad);
/// calculate the number of non-zero entries for the tree starting at clique (use root for complete matrix)
template<class CLIQUE>
@ -691,7 +691,7 @@ int calculate_nnz(const boost::shared_ptr<CLIQUE>& clique);
* @param x0 The center about which to compute the gradient
* @return The gradient as a VectorValues
*/
VectorValues gradient(const ISAM2& bayesTree, const VectorValues& x0);
GTSAM_EXPORT VectorValues gradient(const ISAM2& bayesTree, const VectorValues& x0);
/**
* Compute the gradient of the energy function,
@ -704,7 +704,7 @@ VectorValues gradient(const ISAM2& bayesTree, const VectorValues& x0);
* @param [output] g A VectorValues to store the gradient, which must be preallocated, see allocateVectorValues
* @return The gradient as a VectorValues
*/
void gradientAtZero(const ISAM2& bayesTree, VectorValues& g);
GTSAM_EXPORT void gradientAtZero(const ISAM2& bayesTree, VectorValues& g);
} /// namespace gtsam

View File

@ -20,6 +20,7 @@
#include <boost/function.hpp>
#include <string>
#include <gtsam/base/types.h>
#include <gtsam/base/FastVector.h>
#include <gtsam/base/FastList.h>
#include <gtsam/base/FastSet.h>
@ -33,7 +34,7 @@ namespace gtsam {
typedef boost::function<std::string(Key)> KeyFormatter;
// Helper function for DefaultKeyFormatter
std::string _defaultKeyFormatter(Key key);
GTSAM_EXPORT std::string _defaultKeyFormatter(Key key);
/// The default KeyFormatter, which is used if no KeyFormatter is passed to
/// a nonlinear 'print' function. Automatically detects plain integer keys

View File

@ -29,7 +29,7 @@ class LevenbergMarquardtOptimizer;
* common to all nonlinear optimization algorithms. This class also contains
* all of those parameters.
*/
class LevenbergMarquardtParams : public SuccessiveLinearizationParams {
class GTSAM_EXPORT LevenbergMarquardtParams : public SuccessiveLinearizationParams {
public:
/** See LevenbergMarquardtParams::lmVerbosity */
@ -70,7 +70,7 @@ private:
/**
* State for LevenbergMarquardtOptimizer
*/
class LevenbergMarquardtState : public NonlinearOptimizerState {
class GTSAM_EXPORT LevenbergMarquardtState : public NonlinearOptimizerState {
public:
double lambda;
@ -89,7 +89,7 @@ protected:
/**
* This class performs Levenberg-Marquardt nonlinear optimization
*/
class LevenbergMarquardtOptimizer : public NonlinearOptimizer {
class GTSAM_EXPORT LevenbergMarquardtOptimizer : public NonlinearOptimizer {
protected:
LevenbergMarquardtParams params_; ///< LM parameters

View File

@ -17,7 +17,7 @@ namespace gtsam {
/**
* Dummy version of a generic linear factor to be injected into a nonlinear factor graph
*/
class LinearContainerFactor : public NonlinearFactor {
class GTSAM_EXPORT LinearContainerFactor : public NonlinearFactor {
protected:
GaussianFactor::shared_ptr factor_;

View File

@ -30,7 +30,7 @@ class JointMarginal;
/**
* A class for computing Gaussian marginals of variables in a NonlinearFactorGraph
*/
class Marginals {
class GTSAM_EXPORT Marginals {
public:
@ -78,7 +78,7 @@ public:
/**
* A class to store and access a joint marginal, returned from Marginals::jointMarginalCovariance and Marginals::jointMarginalInformation
*/
class JointMarginal {
class GTSAM_EXPORT JointMarginal {
protected:

View File

@ -14,14 +14,14 @@
namespace gtsam {
/** An implementation of the nonlinear cg method using the template below */
class NonlinearConjugateGradientState : public NonlinearOptimizerState {
class GTSAM_EXPORT NonlinearConjugateGradientState : public NonlinearOptimizerState {
public:
typedef NonlinearOptimizerState Base;
NonlinearConjugateGradientState(const NonlinearFactorGraph& graph, const Values& values)
: Base(graph, values) {}
};
class NonlinearConjugateGradientOptimizer : public NonlinearOptimizer {
class GTSAM_EXPORT NonlinearConjugateGradientOptimizer : public NonlinearOptimizer {
/* a class for the nonlinearConjugateGradient template */
class System {
public:

View File

@ -32,7 +32,7 @@ namespace gtsam {
* Formatting options when saving in GraphViz format using
* NonlinearFactorGraph::saveGraph.
*/
struct GraphvizFormatting {
struct GTSAM_EXPORT GraphvizFormatting {
enum Axis { X, Y, Z, NEGX, NEGY, NEGZ }; ///< World axes to be assigned to paper axes
Axis paperHorizontalAxis; ///< The world axis assigned to the horizontal paper axis
Axis paperVerticalAxis; ///< The world axis assigned to the vertical paper axis
@ -67,21 +67,21 @@ namespace gtsam {
typedef boost::shared_ptr<NonlinearFactor> sharedFactor;
/** print just calls base class */
void print(const std::string& str = "NonlinearFactorGraph: ", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
GTSAM_EXPORT void print(const std::string& str = "NonlinearFactorGraph: ", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
/** Write the graph in GraphViz format for visualization */
void saveGraph(std::ostream& stm, const Values& values = Values(),
GTSAM_EXPORT void saveGraph(std::ostream& stm, const Values& values = Values(),
const GraphvizFormatting& graphvizFormatting = GraphvizFormatting(),
const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
/** return keys as an ordered set - ordering is by key value */
FastSet<Key> keys() const;
GTSAM_EXPORT FastSet<Key> keys() const;
/** unnormalized error, \f$ 0.5 \sum_i (h_i(X_i)-z)^2/\sigma^2 \f$ in the most common case */
double error(const Values& c) const;
GTSAM_EXPORT double error(const Values& c) const;
/** Unnormalized probability. O(n) */
double probPrime(const Values& c) const;
GTSAM_EXPORT double probPrime(const Values& c) const;
/// Add a factor by value - copies the factor object
void add(const NonlinearFactor& factor) {
@ -96,7 +96,7 @@ namespace gtsam {
/**
* Create a symbolic factor graph using an existing ordering
*/
SymbolicFactorGraph::shared_ptr symbolic(const Ordering& ordering) const;
GTSAM_EXPORT SymbolicFactorGraph::shared_ptr symbolic(const Ordering& ordering) const;
/**
* Create a symbolic factor graph and initial variable ordering that can
@ -104,13 +104,13 @@ namespace gtsam {
* The graph and ordering should be permuted after such a fill-reducing
* ordering is found.
*/
std::pair<SymbolicFactorGraph::shared_ptr, Ordering::shared_ptr>
GTSAM_EXPORT std::pair<SymbolicFactorGraph::shared_ptr, Ordering::shared_ptr>
symbolic(const Values& config) const;
/**
* Compute a fill-reducing ordering using COLAMD.
*/
Ordering::shared_ptr orderingCOLAMD(const Values& config) const;
GTSAM_EXPORT Ordering::shared_ptr orderingCOLAMD(const Values& config) const;
/**
* Compute a fill-reducing ordering with constraints using CCOLAMD
@ -120,19 +120,19 @@ namespace gtsam {
* indices need to appear in the constraints, unconstrained is assumed for all
* other variables
*/
Ordering::shared_ptr orderingCOLAMDConstrained(const Values& config,
GTSAM_EXPORT Ordering::shared_ptr orderingCOLAMDConstrained(const Values& config,
const std::map<Key, int>& constraints) const;
/**
* linearize a nonlinear factor graph
*/
boost::shared_ptr<GaussianFactorGraph >
GTSAM_EXPORT boost::shared_ptr<GaussianFactorGraph >
linearize(const Values& config, const Ordering& ordering) const;
/**
* Clone() performs a deep-copy of the graph, including all of the factors
*/
NonlinearFactorGraph clone() const;
GTSAM_EXPORT NonlinearFactorGraph clone() const;
/**
* Rekey() performs a deep-copy of all of the factors, and changes
@ -143,7 +143,7 @@ namespace gtsam {
* @param rekey_mapping is a map of old->new keys
* @result a cloned graph with updated keys
*/
NonlinearFactorGraph rekey(const std::map<Key,Key>& rekey_mapping) const;
GTSAM_EXPORT NonlinearFactorGraph rekey(const std::map<Key,Key>& rekey_mapping) const;
private:

View File

@ -24,7 +24,7 @@ namespace gtsam {
/**
* Wrapper class to manage ISAM in a nonlinear context
*/
class NonlinearISAM {
class GTSAM_EXPORT NonlinearISAM {
protected:
/** The internal iSAM object */

View File

@ -27,7 +27,7 @@ class NonlinearOptimizer;
/** The common parameters for Nonlinear optimizers. Most optimizers
* deriving from NonlinearOptimizer also subclass the parameters.
*/
class NonlinearOptimizerParams {
class GTSAM_EXPORT NonlinearOptimizerParams {
public:
/** See NonlinearOptimizerParams::verbosity */
enum Verbosity {
@ -75,7 +75,7 @@ private:
* additional state specific to the algorithm (for example, Dogleg state
* contains the current trust region radius).
*/
class NonlinearOptimizerState {
class GTSAM_EXPORT NonlinearOptimizerState {
public:
/** The current estimate of the variable values. */
@ -174,7 +174,7 @@ Values::const_shared_ptr result = DoglegOptimizer(graph, initialValues, params).
* For more flexibility, since all functions are virtual, you may override them
* in your own derived class.
*/
class NonlinearOptimizer {
class GTSAM_EXPORT NonlinearOptimizer {
protected:
NonlinearFactorGraph graph_;
@ -249,7 +249,7 @@ protected:
* the absolute error decrease is less than absoluteErrorTreshold, <em>or</em>
* the error itself is less than errorThreshold.
*/
bool checkConvergence(double relativeErrorTreshold,
GTSAM_EXPORT bool checkConvergence(double relativeErrorTreshold,
double absoluteErrorTreshold, double errorThreshold,
double currentError, double newError, NonlinearOptimizerParams::Verbosity verbosity);

View File

@ -32,7 +32,7 @@ namespace gtsam {
* An ordering is a map from symbols (non-typed keys) to integer indices
* \nosubgrouping
*/
class Ordering {
class GTSAM_EXPORT Ordering {
protected:
typedef FastMap<Key, Index> Map;
typedef std::vector<Map::iterator> OrderingIndex;
@ -250,13 +250,13 @@ public:
bool exists(const Index& key) { return find(key) != end(); }
// Testable
void print(const std::string& s = "Unordered") const;
bool equals(const Unordered &t, double tol=0) const;
GTSAM_EXPORT void print(const std::string& s = "Unordered") const;
GTSAM_EXPORT bool equals(const Unordered &t, double tol=0) const;
};
// Create an index formatter that looks up the Key in an inverse ordering, then
// formats the key using the provided key formatter, used in saveGraph.
class OrderingIndexFormatter {
class GTSAM_EXPORT OrderingIndexFormatter {
private:
Ordering ordering_;
KeyFormatter keyFormatter_;

View File

@ -23,7 +23,7 @@
namespace gtsam {
class SuccessiveLinearizationParams : public NonlinearOptimizerParams {
class GTSAM_EXPORT SuccessiveLinearizationParams : public NonlinearOptimizerParams {
public:
/** See SuccessiveLinearizationParams::linearSolverType */
enum LinearSolverType {
@ -101,6 +101,6 @@ private:
};
/* a wrapper for solving a GaussianFactorGraph according to the parameters */
VectorValues solveGaussianFactorGraph(const GaussianFactorGraph &gfg, const SuccessiveLinearizationParams &params) ;
GTSAM_EXPORT VectorValues solveGaussianFactorGraph(const GaussianFactorGraph &gfg, const SuccessiveLinearizationParams &params) ;
} /* namespace gtsam */

View File

@ -29,7 +29,7 @@ namespace gtsam {
* keys when linearizing a nonlinear factor graph. This key is not type
* safe, so cannot be used with any Nonlinear* classes.
*/
class Symbol {
class GTSAM_EXPORT Symbol {
protected:
unsigned char c_;
size_t j_;

View File

@ -32,7 +32,7 @@
namespace gtsam {
/* ************************************************************************* */
class ValueCloneAllocator {
class GTSAM_EXPORT ValueCloneAllocator {
public:
static Value* allocate_clone(const Value& a) { return a.clone_(); }
static void deallocate_clone(const Value* a) { a->deallocate_(); }

View File

@ -61,7 +61,7 @@ namespace gtsam {
* manifold element, and hence supports operations dim, retract, and
* localCoordinates.
*/
class Values {
class GTSAM_EXPORT Values {
private:
@ -92,7 +92,7 @@ namespace gtsam {
typedef boost::shared_ptr<const Values> const_shared_ptr;
/// A key-value pair, which you get by dereferencing iterators
struct KeyValuePair {
struct GTSAM_EXPORT KeyValuePair {
const Key key; ///< The key
Value& value; ///< The value
@ -100,7 +100,7 @@ namespace gtsam {
};
/// A key-value pair, which you get by dereferencing iterators
struct ConstKeyValuePair {
struct GTSAM_EXPORT ConstKeyValuePair {
const Key key; ///< The key
const Value& value; ///< The value
@ -381,7 +381,7 @@ namespace gtsam {
};
/* ************************************************************************* */
class ValuesKeyAlreadyExists : public std::exception {
class GTSAM_EXPORT ValuesKeyAlreadyExists : public std::exception {
protected:
const Key key_; ///< The key that already existed
@ -403,7 +403,7 @@ namespace gtsam {
};
/* ************************************************************************* */
class ValuesKeyDoesNotExist : public std::exception {
class GTSAM_EXPORT ValuesKeyDoesNotExist : public std::exception {
protected:
const char* operation_; ///< The operation that attempted to access the key
const Key key_; ///< The key that does not exist
@ -426,7 +426,7 @@ namespace gtsam {
};
/* ************************************************************************* */
class ValuesIncorrectType : public std::exception {
class GTSAM_EXPORT ValuesIncorrectType : public std::exception {
protected:
const Key key_; ///< The key requested
const std::type_info& storedTypeId_;
@ -457,7 +457,7 @@ namespace gtsam {
};
/* ************************************************************************* */
class DynamicValuesMismatched : public std::exception {
class GTSAM_EXPORT DynamicValuesMismatched : public std::exception {
public:
DynamicValuesMismatched() throw() {}

View File

@ -37,7 +37,7 @@ namespace gtsam {
* @throw std::invalid_argument if no matching file could be found using the
* search process described above.
*/
std::string findExampleDataFile(const std::string& name);
GTSAM_EXPORT std::string findExampleDataFile(const std::string& name);
#endif
/**
@ -47,7 +47,7 @@ namespace gtsam {
* @param addNoise add noise to the edges
* @param smart try to reduce complexity of covariance to cheapest model
*/
std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr> load2D(
GTSAM_EXPORT std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr> load2D(
std::pair<std::string, boost::optional<noiseModel::Diagonal::shared_ptr> > dataset,
int maxID = 0, bool addNoise = false, bool smart = true);
@ -59,19 +59,19 @@ namespace gtsam {
* @param addNoise add noise to the edges
* @param smart try to reduce complexity of covariance to cheapest model
*/
std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr> load2D(
GTSAM_EXPORT std::pair<NonlinearFactorGraph::shared_ptr, Values::shared_ptr> load2D(
const std::string& filename,
boost::optional<gtsam::SharedDiagonal> model = boost::optional<
noiseModel::Diagonal::shared_ptr>(), int maxID = 0, bool addNoise = false,
bool smart = true);
/** save 2d graph */
void save2D(const NonlinearFactorGraph& graph, const Values& config,
GTSAM_EXPORT void save2D(const NonlinearFactorGraph& graph, const Values& config,
const noiseModel::Diagonal::shared_ptr model, const std::string& filename);
/**
* Load TORO 3D Graph
*/
bool load3D(const std::string& filename);
GTSAM_EXPORT bool load3D(const std::string& filename);
} // namespace gtsam

View File

@ -59,6 +59,9 @@ if (GTSAM_BUILD_STATIC_LIBRARY)
CLEAN_DIRECT_OUTPUT 1
VERSION ${gtsam_unstable_version}
SOVERSION ${gtsam_unstable_soversion})
if(WIN32) # Add 'lib' prefix to static library to avoid filename collision with shared library
set_target_properties(gtsam_unstable-static PROPERTIES PREFIX "lib")
endif()
target_link_libraries(gtsam_unstable-static gtsam-static ${GTSAM_UNSTABLE_BOOST_LIBRARIES})
install(TARGETS gtsam_unstable-static EXPORT GTSAM-exports ARCHIVE DESTINATION lib)
list(APPEND GTSAM_EXPORTED_TARGETS gtsam_unstable-static)
@ -73,6 +76,13 @@ if (GTSAM_BUILD_SHARED_LIBRARY)
CLEAN_DIRECT_OUTPUT 1
VERSION ${gtsam_unstable_version}
SOVERSION ${gtsam_unstable_soversion})
if(WIN32)
set_target_properties(gtsam_unstable-shared PROPERTIES
PREFIX ""
DEFINE_SYMBOL GTSAM_UNSTABLE_EXPORTS
RUNTIME_OUTPUT_DIRECTORY "${PROJECT_BINARY_DIR}/bin")
add_definitions(/wd4251 /wd4275) # Disable non-DLL-exported base class warnings
endif()
target_link_libraries(gtsam_unstable-shared gtsam-shared ${GTSAM_UNSTABLE_BOOST_LIBRARIES})
install(TARGETS gtsam_unstable-shared EXPORT GTSAM-exports LIBRARY DESTINATION lib ARCHIVE DESTINATION lib RUNTIME DESTINATION bin)
list(APPEND GTSAM_EXPORTED_TARGETS gtsam_unstable-shared)

View File

@ -17,11 +17,13 @@
* @date June 14, 2012
*/
#include <gtsam/base/types.h>
#include <gtsam_unstable/base/dllexport.h>
#include <string>
namespace gtsam {
struct Dummy {
struct GTSAM_UNSTABLE_EXPORT Dummy {
size_t id;
Dummy();
~Dummy();

View File

@ -0,0 +1,36 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file dllexport.h
* @brief Symbols for exporting classes and methods from DLLs
* @author Richard Roberts
* @date Mar 9, 2013
*/
#ifdef _WIN32
# ifdef GTSAM_UNSTABLE_EXPORTS
# define GTSAM_UNSTABLE_EXPORT __declspec(dllexport)
# define GTSAM_UNSTABLE_EXTERN_EXPORT __declspec(dllexport) extern
# else
# ifndef GTSAM_UNSTABLE_IMPORT_STATIC
# define GTSAM_UNSTABLE_EXPORT __declspec(dllimport)
# define GTSAM_UNSTABLE_EXTERN_EXPORT __declspec(dllimport)
# else /* GTSAM_UNSTABLE_IMPORT_STATIC */
# define GTSAM_UNSTABLE_EXPORT
# define GTSAM_UNSTABLE_EXTERN_EXPORT extern
# endif /* GTSAM_UNSTABLE_IMPORT_STATIC */
# endif /* GTSAM_UNSTABLE_EXPORTS */
#else /* _WIN32 */
# define GTSAM_UNSTABLE_EXPORT
# define GTSAM_UNSTABLE_EXTERN_EXPORT extern
#endif

View File

@ -19,7 +19,7 @@ namespace gtsam {
* for each variable we have a Index and an Index. In this factor, we
* keep the Indices locally, and the Indices are stored in IndexFactor.
*/
class AllDiff: public Constraint {
class GTSAM_UNSTABLE_EXPORT AllDiff: public Constraint {
std::map<Index,size_t> cardinalities_;

View File

@ -18,7 +18,7 @@ namespace gtsam {
* A specialization of a DiscreteFactorGraph.
* It knows about CSP-specific constraints and algorithms
*/
class CSP: public DiscreteFactorGraph {
class GTSAM_UNSTABLE_EXPORT CSP: public DiscreteFactorGraph {
public:
/** A map from keys to values */

View File

@ -17,6 +17,7 @@
#pragma once
#include <gtsam_unstable/base/dllexport.h>
#include <gtsam/discrete/DiscreteFactor.h>
namespace gtsam {

View File

@ -15,7 +15,7 @@ namespace gtsam {
/**
* Domain restriction constraint
*/
class Domain: public Constraint {
class GTSAM_UNSTABLE_EXPORT Domain: public Constraint {
size_t cardinality_; /// Cardinality
std::set<size_t> values_; /// allowed values

View File

@ -18,7 +18,7 @@ namespace gtsam {
* The "student" variable will determine when the student takes the qual.
* The "area" variables determine which faculty are on his/her committee.
*/
class Scheduler : public CSP {
class GTSAM_UNSTABLE_EXPORT Scheduler : public CSP {
private:

View File

@ -15,7 +15,7 @@ namespace gtsam {
/**
* SingleValue constraint
*/
class SingleValue: public Constraint {
class GTSAM_UNSTABLE_EXPORT SingleValue: public Constraint {
/// Number of values
size_t cardinality_;

Some files were not shown because too many files have changed in this diff Show More