Moved trunk Vector/Matrix to gtsam namespace

release/4.3a0
Alex Cunningham 2011-06-07 19:26:49 +00:00
parent cbf4d9e811
commit 2e058f2272
2 changed files with 14 additions and 13 deletions

View File

@ -29,9 +29,11 @@
#include <gtsam/base/Vector.h> #include <gtsam/base/Vector.h>
/** /**
* Matrix is a *global* typedef * Matrix is a typedef in the gtsam namespace
* TODO: make a version to work with matlab wrapping
* we use the default < double,col_major,unbounded_array<double> > * we use the default < double,col_major,unbounded_array<double> >
*/ */
namespace gtsam {
typedef Eigen::MatrixXd Matrix; typedef Eigen::MatrixXd Matrix;
typedef Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> MatrixRowMajor; typedef Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> MatrixRowMajor;
@ -40,8 +42,6 @@ typedef Eigen::Matrix<double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor> M
typedef Eigen::Block<Matrix> SubMatrix; typedef Eigen::Block<Matrix> SubMatrix;
typedef Eigen::Block<const Matrix> ConstSubMatrix; typedef Eigen::Block<const Matrix> ConstSubMatrix;
namespace gtsam {
/** /**
* constructor with size and initial data, row order ! * constructor with size and initial data, row order !
*/ */
@ -469,7 +469,7 @@ namespace serialization {
// split version - sends sizes ahead // split version - sends sizes ahead
template<class Archive> template<class Archive>
void save(Archive & ar, const Matrix & m, unsigned int version) void save(Archive & ar, const gtsam::Matrix & m, unsigned int version)
{ {
const int rows = m.rows(), cols = m.cols(), elements = rows*cols; const int rows = m.rows(), cols = m.cols(), elements = rows*cols;
std::vector<double> raw_data(elements); std::vector<double> raw_data(elements);
@ -479,18 +479,18 @@ void save(Archive & ar, const Matrix & m, unsigned int version)
ar << make_nvp("data", raw_data); ar << make_nvp("data", raw_data);
} }
template<class Archive> template<class Archive>
void load(Archive & ar, Matrix & m, unsigned int version) void load(Archive & ar, gtsam::Matrix & m, unsigned int version)
{ {
size_t rows, cols; size_t rows, cols;
std::vector<double> raw_data; std::vector<double> raw_data;
ar >> make_nvp("rows", rows); ar >> make_nvp("rows", rows);
ar >> make_nvp("cols", cols); ar >> make_nvp("cols", cols);
ar >> make_nvp("data", raw_data); ar >> make_nvp("data", raw_data);
m = Matrix(rows, cols); m = gtsam::Matrix(rows, cols);
std::copy(raw_data.begin(), raw_data.end(), m.data()); std::copy(raw_data.begin(), raw_data.end(), m.data());
} }
} // namespace serialization } // namespace serialization
} // namespace boost } // namespace boost
BOOST_SERIALIZATION_SPLIT_FREE(Matrix) BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Matrix)

View File

@ -25,7 +25,10 @@
#include <gtsam/3rdparty/Eigen/Core> #include <gtsam/3rdparty/Eigen/Core>
#include <boost/random/linear_congruential.hpp> #include <boost/random/linear_congruential.hpp>
// Vector is a *global* typedef // Vector is just a typedef of the Eigen dynamic vector type
// TODO: make a version that works for matlab wrapping
namespace gtsam {
// Typedef arbitary length vector // Typedef arbitary length vector
typedef Eigen::VectorXd Vector; typedef Eigen::VectorXd Vector;
@ -33,8 +36,6 @@ typedef Eigen::VectorXd Vector;
typedef Eigen::VectorBlock<Vector> SubVector; typedef Eigen::VectorBlock<Vector> SubVector;
typedef Eigen::VectorBlock<const Vector> ConstSubVector; typedef Eigen::VectorBlock<const Vector> ConstSubVector;
namespace gtsam {
/** /**
* An auxiliary function to printf for Win32 compatibility, added by Kai * An auxiliary function to printf for Win32 compatibility, added by Kai
*/ */
@ -353,7 +354,7 @@ namespace serialization {
// split version - copies into an STL vector for serialization // split version - copies into an STL vector for serialization
template<class Archive> template<class Archive>
void save(Archive & ar, const Vector & v, unsigned int version) void save(Archive & ar, const gtsam::Vector & v, unsigned int version)
{ {
const size_t n = v.size(); const size_t n = v.size();
std::vector<double> raw_data(n); std::vector<double> raw_data(n);
@ -361,7 +362,7 @@ void save(Archive & ar, const Vector & v, unsigned int version)
ar << make_nvp("data", raw_data); ar << make_nvp("data", raw_data);
} }
template<class Archive> template<class Archive>
void load(Archive & ar, Vector & v, unsigned int version) void load(Archive & ar, gtsam::Vector & v, unsigned int version)
{ {
std::vector<double> raw_data; std::vector<double> raw_data;
ar >> make_nvp("data", raw_data); ar >> make_nvp("data", raw_data);
@ -371,4 +372,4 @@ void load(Archive & ar, Vector & v, unsigned int version)
} // namespace serialization } // namespace serialization
} // namespace boost } // namespace boost
BOOST_SERIALIZATION_SPLIT_FREE(Vector) BOOST_SERIALIZATION_SPLIT_FREE(gtsam::Vector)