Disabled use of non-gtsam-namespace Vector and Matrix in wrap/matlab.h, removed two typeof uses (one more to go)

release/4.3a0
Alex Cunningham 2011-10-21 20:42:25 +00:00
parent d678ed3051
commit eebef44efd
3 changed files with 23 additions and 21 deletions

View File

@ -58,7 +58,7 @@ static inline bool choleskyStep(Matrix& ATA, size_t k, size_t order) {
if(k < (order-1)) {
// Update A(k,k+1:end) <- A(k,k+1:end) / beta
typedef typeof(ATA.row(k).segment(k+1, order-(k+1))) BlockRow;
typedef Matrix::RowXpr::SegmentReturnType BlockRow;
BlockRow V = ATA.row(k).segment(k+1, order-(k+1));
V *= betainv;

View File

@ -344,7 +344,9 @@ void HessianFactor::updateATA(const JacobianFactor& update, const Scatter& scatt
update.print("with (Jacobian): ");
}
Eigen::Block<typeof(update.matrix_)> updateA(update.matrix_.block(
// typedef Eigen::Block<typeof(update.matrix_)> BlockUpdateMatrix;
typedef Eigen::Block<const JacobianFactor::AbMatrix> BlockUpdateMatrix;
BlockUpdateMatrix updateA(update.matrix_.block(
update.Ab_.rowStart(),update.Ab_.offset(0), update.Ab_.full().rows(), update.Ab_.full().cols()));
if (debug) cout << "updateA: \n" << updateA << endl;

View File

@ -36,8 +36,8 @@ using namespace std;
using namespace boost; // not usual, but for conciseness of generated code
// start GTSAM Specifics /////////////////////////////////////////////////
typedef gtsam::Vector Vector; // NOTE: outside of gtsam namespace
typedef gtsam::Matrix Matrix;
//typedef gtsam::Vector Vector; // NOTE: outside of gtsam namespace
//typedef gtsam::Matrix Matrix;
// to make keys be constructed from strings:
#define GTSAM_MAGIC_KEY
@ -129,8 +129,8 @@ mxArray* wrap<double>(double& value) {
return mxCreateDoubleScalar(value);
}
// wrap a const BOOST vector into a double vector
mxArray* wrap_Vector(const Vector& v) {
// wrap a const Eigen vector into a double vector
mxArray* wrap_Vector(const gtsam::Vector& v) {
int m = v.size();
mxArray *result = mxCreateDoubleMatrix(m, 1, mxREAL);
double *data = mxGetPr(result);
@ -138,20 +138,20 @@ mxArray* wrap_Vector(const Vector& v) {
return result;
}
// specialization to BOOST vector -> double vector
// specialization to Eigen vector -> double vector
template<>
mxArray* wrap<Vector >(Vector& v) {
mxArray* wrap<gtsam::Vector >(gtsam::Vector& v) {
return wrap_Vector(v);
}
// const version
template<>
mxArray* wrap<const Vector >(const Vector& v) {
mxArray* wrap<const gtsam::Vector >(const gtsam::Vector& v) {
return wrap_Vector(v);
}
// wrap a const BOOST MATRIX into a double matrix
mxArray* wrap_Matrix(const Matrix& A) {
// wrap a const Eigen MATRIX into a double matrix
mxArray* wrap_Matrix(const gtsam::Matrix& A) {
int m = A.rows(), n = A.cols();
mxArray *result = mxCreateDoubleMatrix(m, n, mxREAL);
double *data = mxGetPr(result);
@ -160,15 +160,15 @@ mxArray* wrap_Matrix(const Matrix& A) {
return result;
}
// specialization to BOOST MATRIX -> double matrix
// specialization to Eigen MATRIX -> double matrix
template<>
mxArray* wrap<Matrix >(Matrix& A) {
mxArray* wrap<gtsam::Matrix >(gtsam::Matrix& A) {
return wrap_Matrix(A);
}
// const version
template<>
mxArray* wrap<const Matrix >(const Matrix& A) {
mxArray* wrap<const gtsam::Matrix >(const gtsam::Matrix& A) {
return wrap_Matrix(A);
}
@ -223,16 +223,16 @@ double unwrap<double>(const mxArray* array) {
return (double)mxGetScalar(array);
}
// specialization to BOOST vector
// specialization to Eigen vector
template<>
Vector unwrap< Vector >(const mxArray* array) {
gtsam::Vector unwrap< gtsam::Vector >(const mxArray* array) {
int m = mxGetM(array), n = mxGetN(array);
if (mxIsDouble(array)==false || n!=1) error("unwrap<vector>: not a vector");
#ifdef DEBUG_WRAP
mexPrintf("unwrap< Vector > called with %dx%d argument\n", m,n);
mexPrintf("unwrap< gtsam::Vector > called with %dx%d argument\n", m,n);
#endif
double* data = (double*)mxGetData(array);
Vector v(m);
gtsam::Vector v(m);
for (int i=0;i<m;i++,data++) v(i) = *data;
#ifdef DEBUG_WRAP
gtsam::print(v);
@ -240,13 +240,13 @@ Vector unwrap< Vector >(const mxArray* array) {
return v;
}
// specialization to BOOST matrix
// specialization to Eigen matrix
template<>
Matrix unwrap< Matrix >(const mxArray* array) {
gtsam::Matrix unwrap< gtsam::Matrix >(const mxArray* array) {
if (mxIsDouble(array)==false) error("unwrap<matrix>: not a matrix");
int m = mxGetM(array), n = mxGetN(array);
double* data = (double*)mxGetData(array);
Matrix A(m,n);
gtsam::Matrix A(m,n);
// converts from row-major to column-major
for (int j=0;j<n;j++) for (int i=0;i<m;i++,data++) A(i,j) = *data;
return A;