Added MATLAB tests

release/4.3a0
dellaert 2014-11-30 10:36:52 +01:00
parent b12255285b
commit 3cffb73155
4 changed files with 48 additions and 7 deletions

11
gtsam.h
View File

@ -1739,7 +1739,7 @@ class Values {
void insert(size_t j, const gtsam::EssentialMatrix& t);
void insert(size_t j, const gtsam::imuBias::ConstantBias& t);
void insert(size_t j, Vector t);
void insert(size_t j, Matrix t); //git/gtsam/gtsam/base/Manifold.h:254:1: error: invalid application of sizeof to incomplete type boost::STATIC_ASSERTION_FAILURE<false>
void insert(size_t j, Matrix t);
void update(size_t j, const gtsam::Point2& t);
void update(size_t j, const gtsam::Point3& t);
@ -1755,8 +1755,7 @@ class Values {
void update(size_t j, Vector t);
void update(size_t j, Matrix t);
template<T = {gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Pose2,
gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::imuBias::ConstantBias ,Vector, Matrix}> // Parse Error
template<T = {gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Pose2, gtsam::Rot3, gtsam::Pose3, gtsam::Cal3_S2, gtsam::Cal3DS2, gtsam::Cal3Bundler, gtsam::EssentialMatrix, gtsam::imuBias::ConstantBias, Vector, Matrix}>
T at(size_t j);
};
@ -2154,9 +2153,7 @@ class NonlinearISAM {
#include <gtsam/geometry/StereoPoint2.h>
#include <gtsam/slam/PriorFactor.h>
template<T = { gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2,
gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Cal3_S2,
gtsam::CalibratedCamera, gtsam::SimpleCamera, gtsam::imuBias::ConstantBias, Vector, Matrix }> // Parse Error
template<T = { gtsam::Point2, gtsam::StereoPoint2, gtsam::Point3, gtsam::Rot2, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::Cal3_S2,gtsam::CalibratedCamera, gtsam::SimpleCamera, gtsam::imuBias::ConstantBias}>
virtual class PriorFactor : gtsam::NoiseModelFactor {
PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel);
T prior() const;
@ -2167,7 +2164,7 @@ virtual class PriorFactor : gtsam::NoiseModelFactor {
#include <gtsam/slam/BetweenFactor.h>
template<T = {gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::imuBias::ConstantBias, Vector, Matrix}> // Parse Error
template<T = {gtsam::Point2, gtsam::Point3, gtsam::Rot2, gtsam::Rot3, gtsam::Pose2, gtsam::Pose3, gtsam::imuBias::ConstantBias}>
virtual class BetweenFactor : gtsam::NoiseModelFactor {
BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel);
T measured() const;

1
matlab/gtsam_tests/.gitignore vendored Normal file
View File

@ -0,0 +1 @@
*.m~

View File

@ -0,0 +1,40 @@
% test wrapping of Values
import gtsam.*;
values = Values;
E = EssentialMatrix(Rot3,Unit3);
tol = 1e-9;
values.insert(0, Point2);
values.insert(1, Point3);
values.insert(2, Rot2);
values.insert(3, Pose2);
values.insert(4, Rot3);
values.insert(5, Pose3);
values.insert(6, Cal3_S2);
values.insert(7, Cal3DS2);
values.insert(8, Cal3Bundler);
values.insert(9, E);
values.insert(10, imuBias.ConstantBias);
% special cases for Vector and Matrix:
values.insert(11, [1;2;3]);
values.insert(12, [1 2;3 4]);
EXPECT('at',values.atPoint2(0).equals(Point2,tol));
EXPECT('at',values.atPoint3(1).equals(Point3,tol));
EXPECT('at',values.atRot2(2).equals(Rot2,tol));
EXPECT('at',values.atPose2(3).equals(Pose2,tol));
EXPECT('at',values.atRot3(4).equals(Rot3,tol));
EXPECT('at',values.atPose3(5).equals(Pose3,tol));
EXPECT('at',values.atCal3_S2(6).equals(Cal3_S2,tol));
EXPECT('at',values.atCal3DS2(7).equals(Cal3DS2,tol));
EXPECT('at',values.atCal3Bundler(8).equals(Cal3Bundler,tol));
EXPECT('at',values.atEssentialMatrix(9).equals(E,tol));
EXPECT('at',values.atConstantBias(10).equals(imuBias.ConstantBias,tol));
% special cases for Vector and Matrix:
actualVector = values.atVector(11);
EQUALITY('at',[1 2;3 4],actualVector,tol);
actualMatrix = values.atMatrix(12);
EQUALITY('at',[1 2;3 4],actualMatrix,tol);

View File

@ -1,5 +1,8 @@
% Test runner script - runs each test
display 'Starting: testValues'
testValues
display 'Starting: testJacobianFactor'
testJacobianFactor