diff --git a/.cproject b/.cproject
index a35bd2fed..35f7946a4 100644
--- a/.cproject
+++ b/.cproject
@@ -36,6 +36,9 @@
@@ -681,6 +684,22 @@
true
true
+
+ make
+ -j5
+ all
+ true
+ false
+ true
+
+
+ make
+ -j5
+ check
+ true
+ false
+ true
+
make
-j2
@@ -2029,6 +2048,22 @@
true
true
+
+ make
+ -j5
+ check
+ true
+ false
+ true
+
+
+ make
+ -j5
+ install
+ true
+ false
+ true
+
make
-j2
@@ -2045,6 +2080,38 @@
true
true
+
+ make
+ -j2
+ tests/testSpirit.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ tests/testWrap.run
+ true
+ true
+ true
+
+
+ make
+ -j2
+ clean
+ true
+ true
+ true
+
+
+ make
+ -j2
+ all
+ true
+ true
+ true
+
diff --git a/configure.ac b/configure.ac
index 6b057ba46..5929b22ee 100644
--- a/configure.ac
+++ b/configure.ac
@@ -30,8 +30,11 @@ DX_PS_FEATURE(OFF)
DX_INIT_DOXYGEN(gtsam)
# Check for OS
-AC_CANONICAL_HOST # needs to be called at some point earlier
-AM_CONDITIONAL([DARWIN], [case $host_os in darwin*) true;; *) false;; esac])
+# needs to be called at some point earlier
+AC_CANONICAL_HOST
+AM_CONDITIONAL([DARWIN], [case $host_os in darwin*) true;; *) false;; esac])
+AM_CONDITIONAL([LINUX], [case $host_os in linux*) true;; *) false;; esac])
+AM_CONDITIONAL([IS_64BIT], [case $host_cpu in *x86_64*) true;; *) false;; esac])
# enable debug variable
AC_ARG_ENABLE([debug],
@@ -44,20 +47,6 @@ AC_ARG_ENABLE([debug],
AM_CONDITIONAL([DEBUG], [test x$debug = xtrue])
-
-AC_CANONICAL_HOST
-# We need to determine what os we are on to determine if we need to do
-# special things because we are on a mac
-case $host_os in
- darwin* )
- # Do something specific for mac
- ISMAC=true
- ;;
- *)
- ISMAC=false
- ;;
-esac
-
# enable profiling
AC_ARG_ENABLE([profiling],
[ --enable-profiling Enable profiling],
@@ -91,6 +80,77 @@ AC_ARG_ENABLE([install_cppunitlite],
AM_CONDITIONAL([ENABLE_INSTALL_CPPUNITLITE], [test x$install_cppunitlite = xtrue])
+# enable matlab toolbox generation
+AC_ARG_ENABLE([build_toolbox],
+ [ --enable-build-toolbox Enable building of the Matlab toolbox],
+ [case "${enableval}" in
+ yes) build_toolbox=true ;;
+ no) build_toolbox=false ;;
+ *) AC_MSG_ERROR([bad value ${enableval} for --enable-build-toolbox]) ;;
+ esac],[build_toolbox=false])
+
+AM_CONDITIONAL([ENABLE_BUILD_TOOLBOX], [test x$build_toolbox = xtrue])
+
+# enable installation of matlab tests
+AC_ARG_ENABLE([install_matlab_tests],
+ [ --enable-install-matlab-tests Enable installation of tests for the Matlab toolbox],
+ [case "${enableval}" in
+ yes) install_matlab_tests=true ;;
+ no) install_matlab_tests=false ;;
+ *) AC_MSG_ERROR([bad value ${enableval} for --enable-install-matlab-tests]) ;;
+ esac],[install_matlab_tests=true])
+
+AM_CONDITIONAL([ENABLE_INSTALL_MATLAB_TESTS], [test x$install_matlab_tests = xtrue])
+
+# enable installation of matlab examples
+AC_ARG_ENABLE([install_matlab_examples],
+ [ --enable-install-matlab-examples Enable installation of examples for the Matlab toolbox],
+ [case "${enableval}" in
+ yes) install_matlab_examples=true ;;
+ no) install_matlab_examples=false ;;
+ *) AC_MSG_ERROR([bad value ${enableval} for --enable-install-matlab-examples]) ;;
+ esac],[install_matlab_examples=true])
+
+AM_CONDITIONAL([ENABLE_INSTALL_MATLAB_EXAMPLES], [test x$install_matlab_examples = xtrue])
+
+# Matlab toolbox: optional flag to change location of toolbox, defaults to install prefix
+AC_ARG_WITH([toolbox],
+ [AS_HELP_STRING([--with-toolbox],
+ [specify the matlab toolbox directory for installation])],
+ [toolbox=$withval],
+ [toolbox=$prefix])
+AC_SUBST([toolbox])
+
+# enable installation of the wrap utility
+AC_ARG_ENABLE([install_wrap],
+ [ --enable-install-wrap Enable installation of the wrap tool for generating matlab interfaces],
+ [case "${enableval}" in
+ yes) install_wrap=true ;;
+ no) install_wrap=false ;;
+ *) AC_MSG_ERROR([bad value ${enableval} for --enable-install-wrap]) ;;
+ esac],[install_wrap=false])
+
+AM_CONDITIONAL([ENABLE_INSTALL_WRAP], [test x$install_wrap = xtrue])
+
+# enable unsafe mode for wrap
+AC_ARG_ENABLE([unsafe_wrap],
+ [ --enable-unsafe-wrap Enable using unsafe mode in wrap],
+ [case "${enableval}" in
+ yes) unsafe_wrap=true ;;
+ no) unsafe_wrap=false ;;
+ *) AC_MSG_ERROR([bad value ${enableval} for --enable-unsafe-wrap]) ;;
+ esac],[unsafe_wrap=false])
+
+AM_CONDITIONAL([ENABLE_UNSAFE_WRAP], [test x$unsafe_wrap = xtrue])
+
+# wrap install path: optional flag to change location of wrap, defaults to install prefix/bin
+AC_ARG_WITH([wrap],
+ [AS_HELP_STRING([--with-wrap],
+ [specify the wrap directory for installation])],
+ [wrap=$withval],
+ [wrap=$prefix/bin])
+AC_SUBST([wrap])
+
# Checks for programs.
AC_PROG_CXX
AC_PROG_CC
@@ -115,25 +175,6 @@ AC_CHECK_FUNCS([pow sqrt])
# Check for boost
AX_BOOST_BASE([1.40])
-# enable matlab toolbox generation
-AC_ARG_ENABLE([build_toolbox],
- [ --enable-build-toolbox Enable building of the Matlab toolbox],
- [case "${enableval}" in
- yes) build_toolbox=true ;;
- no) build_toolbox=false ;;
- *) AC_MSG_ERROR([bad value ${enableval} for --enable-build-toolbox]) ;;
- esac],[build_toolbox=false])
-
-AM_CONDITIONAL([ENABLE_BUILD_TOOLBOX], [test x$build_toolbox = xtrue])
-
-# Matlab toolbox: optional flag to change location of toolbox, defaults to install prefix
-AC_ARG_WITH([toolbox],
- [AS_HELP_STRING([--with-toolbox],
- [specify the matlab toolbox directory for installation])],
- [toolbox=$withval],
- [toolbox=$prefix])
-AC_SUBST([toolbox])
-
AC_CONFIG_FILES([CppUnitLite/Makefile \
wrap/Makefile \
gtsam/3rdparty/Makefile \
diff --git a/examples/Data/calib.txt b/examples/Data/calib.txt
index 8eeb7e656..cb8b77384 100644
--- a/examples/Data/calib.txt
+++ b/examples/Data/calib.txt
@@ -1 +1 @@
-800 600 -1119.61507797 1119.61507797 399.5 299.5
+800 600 1119.61507797 1119.61507797 399.5 299.5
diff --git a/examples/Data/measurementsISAM.txt b/examples/Data/measurementsISAM.txt
deleted file mode 100644
index 7325c7dd9..000000000
--- a/examples/Data/measurementsISAM.txt
+++ /dev/null
@@ -1,12 +0,0 @@
-10
-ttpy10.feat
-ttpy20.feat
-ttpy30.feat
-ttpy40.feat
-ttpy50.feat
-ttpy60.feat
-ttpy70.feat
-ttpy80.feat
-ttpy90.feat
-ttpy100.feat
-
diff --git a/examples/Data/posesISAM.txt b/examples/Data/posesISAM.txt
deleted file mode 100644
index ebe39c6f2..000000000
--- a/examples/Data/posesISAM.txt
+++ /dev/null
@@ -1,12 +0,0 @@
-10
-ttpy10.pose
-ttpy20.pose
-ttpy30.pose
-ttpy40.pose
-ttpy50.pose
-ttpy60.pose
-ttpy70.pose
-ttpy80.pose
-ttpy90.pose
-ttpy100.pose
-
diff --git a/examples/Data/ttpy10.pose b/examples/Data/ttpy10.pose
index ee0f6231a..b9226c723 100644
--- a/examples/Data/ttpy10.pose
+++ b/examples/Data/ttpy10.pose
@@ -1,4 +1,4 @@
-0.939693 0.34202 0 0
--0.241845 0.664463 -0.707107 0
--0.241845 0.664463 0.707107 0
-34.202 -93.9693 100 1
+0.93969 0.24185 -0.24185 34.202
+0.34202 -0.66446 0.66446 -93.969
+0 -0.70711 -0.70711 100
+0 0 0 1
diff --git a/examples/Data/ttpy100.pose b/examples/Data/ttpy100.pose
index 4225e3d4e..cbd21233f 100644
--- a/examples/Data/ttpy100.pose
+++ b/examples/Data/ttpy100.pose
@@ -1,4 +1,4 @@
--0.939693 -0.34202 0 0
-0.241845 -0.664463 -0.707107 0
-0.241845 -0.664463 0.707107 0
--34.202 93.9693 100 1
+-0.93969 -0.24185 0.24185 -34.202
+-0.34202 0.66446 -0.66446 93.969
+0 -0.70711 -0.70711 100
+0 0 0 1
diff --git a/examples/Data/ttpy20.pose b/examples/Data/ttpy20.pose
index f8b252855..bba2606d0 100644
--- a/examples/Data/ttpy20.pose
+++ b/examples/Data/ttpy20.pose
@@ -1,4 +1,4 @@
-0.766044 0.642788 0 0
--0.454519 0.541675 -0.707107 0
--0.454519 0.541675 0.707107 0
-64.2788 -76.6044 100 1
+0.76604 0.45452 -0.45452 64.279
+0.64279 -0.54168 0.54168 -76.604
+0 -0.70711 -0.70711 100
+0 0 0 1
diff --git a/examples/Data/ttpy30.pose b/examples/Data/ttpy30.pose
index f7ad9f674..737e391f2 100644
--- a/examples/Data/ttpy30.pose
+++ b/examples/Data/ttpy30.pose
@@ -1,4 +1,4 @@
-0.5 0.866025 0 0
--0.612372 0.353553 -0.707107 0
--0.612372 0.353553 0.707107 0
-86.6025 -50 100 1
+0.5 0.61237 -0.61237 86.603
+0.86603 -0.35355 0.35355 -50
+0 -0.70711 -0.70711 100
+0 0 0 1
diff --git a/examples/Data/ttpy40.pose b/examples/Data/ttpy40.pose
index e9c9cd251..4e241c130 100644
--- a/examples/Data/ttpy40.pose
+++ b/examples/Data/ttpy40.pose
@@ -1,4 +1,4 @@
-0.173648 0.984808 0 0
--0.696364 0.122788 -0.707107 0
--0.696364 0.122788 0.707107 0
-98.4808 -17.3648 100 1
+0.17365 0.69636 -0.69636 98.481
+0.98481 -0.12279 0.12279 -17.365
+0 -0.70711 -0.70711 100
+0 0 0 1
diff --git a/examples/Data/ttpy50.pose b/examples/Data/ttpy50.pose
index 9c84b54f3..5a57b10ef 100644
--- a/examples/Data/ttpy50.pose
+++ b/examples/Data/ttpy50.pose
@@ -1,4 +1,4 @@
--0.173648 0.984808 0 0
--0.696364 -0.122788 -0.707107 0
--0.696364 -0.122788 0.707107 0
-98.4808 17.3648 100 1
+-0.17365 0.69636 -0.69636 98.481
+0.98481 0.12279 -0.12279 17.365
+0 -0.70711 -0.70711 100
+0 0 0 1
diff --git a/examples/Data/ttpy60.pose b/examples/Data/ttpy60.pose
index 9c0a8c942..4e5455a0d 100644
--- a/examples/Data/ttpy60.pose
+++ b/examples/Data/ttpy60.pose
@@ -1,4 +1,4 @@
--0.5 0.866025 0 0
--0.612372 -0.353553 -0.707107 0
--0.612372 -0.353553 0.707107 0
-86.6025 50 100 1
+-0.5 0.61237 -0.61237 86.603
+0.86603 0.35355 -0.35355 50
+0 -0.70711 -0.70711 100
+0 0 0 1
diff --git a/examples/Data/ttpy70.pose b/examples/Data/ttpy70.pose
index 0c2254de6..608e9ff7c 100644
--- a/examples/Data/ttpy70.pose
+++ b/examples/Data/ttpy70.pose
@@ -1,4 +1,4 @@
--0.766044 0.642788 0 0
--0.454519 -0.541675 -0.707107 0
--0.454519 -0.541675 0.707107 0
-64.2788 76.6044 100 1
+-0.76604 0.45452 -0.45452 64.279
+0.64279 0.54168 -0.54168 76.604
+0 -0.70711 -0.70711 100
+0 0 0 1
diff --git a/examples/Data/ttpy80.pose b/examples/Data/ttpy80.pose
index 9d6491304..8a6ae4cd1 100644
--- a/examples/Data/ttpy80.pose
+++ b/examples/Data/ttpy80.pose
@@ -1,4 +1,4 @@
--0.939693 0.34202 0 0
--0.241845 -0.664463 -0.707107 0
--0.241845 -0.664463 0.707107 0
-34.202 93.9693 100 1
+-0.93969 0.24185 -0.24185 34.202
+0.34202 0.66446 -0.66446 93.969
+0 -0.70711 -0.70711 100
+0 0 0 1
diff --git a/examples/Data/ttpy90.pose b/examples/Data/ttpy90.pose
index b51c1a58f..863f71fea 100644
--- a/examples/Data/ttpy90.pose
+++ b/examples/Data/ttpy90.pose
@@ -1,4 +1,4 @@
--1 0 0 0
-0 -0.707107 -0.707107 0
-0 -0.707107 0.707107 0
-0 100 100 1
+-1 -0 0 0
+0 0.70711 -0.70711 100
+0 -0.70711 -0.70711 100
+0 0 0 1
diff --git a/examples/vSLAMexample/vISAMexample.cpp b/examples/vSLAMexample/vISAMexample.cpp
index ed3a68ba8..bd35e3636 100644
--- a/examples/vSLAMexample/vISAMexample.cpp
+++ b/examples/vSLAMexample/vISAMexample.cpp
@@ -17,6 +17,7 @@
*/
#include
+#include
using namespace boost;
// Magically casts strings like "x3" to a Symbol('x',3) key, see Key.h
@@ -40,8 +41,8 @@ using namespace boost;
/* ************************************************************************* */
#define CALIB_FILE "calib.txt"
#define LANDMARKS_FILE "landmarks.txt"
-#define POSES_FILE "posesISAM.txt"
-#define MEASUREMENTS_FILE "measurementsISAM.txt"
+#define POSES_FILE "poses.txt"
+#define MEASUREMENTS_FILE "measurements.txt"
// Base data folder
string g_dataFolder;
@@ -49,8 +50,8 @@ string g_dataFolder;
// Store groundtruth values, read from files
shared_ptrK g_calib;
map g_landmarks; // map:
-std::vector g_poses; // prior camera poses at each frame
-std::vector > g_measurements; // feature sets detected at each frame
+map g_poses; // map:
+std::map > g_measurements; // feature sets detected at each frame
// Noise models
SharedNoiseModel measurementSigma(noiseModel::Isotropic::Sigma(2, 5.0f));
@@ -69,7 +70,7 @@ void readAllDataISAM() {
g_landmarks = readLandMarks(g_dataFolder + LANDMARKS_FILE);
// Read groundtruth camera poses. These will be used later as intial estimates for pose nodes.
- g_poses = readPosesISAM(g_dataFolder, POSES_FILE);
+ g_poses = readPoses(g_dataFolder, POSES_FILE);
// Read all 2d measurements. Those will become factors linking their associating pose and the corresponding landmark.
g_measurements = readAllMeasurementsISAM(g_dataFolder, MEASUREMENTS_FILE);
@@ -80,7 +81,7 @@ void readAllDataISAM() {
* Setup newFactors and initialValues for each new pose and set of measurements at each frame.
*/
void createNewFactors(shared_ptr& newFactors, boost::shared_ptr& initialValues,
- int pose_id, Pose3& pose, std::vector& measurements, SharedNoiseModel measurementSigma, shared_ptrK calib) {
+ int pose_id, const Pose3& pose, const std::vector& measurements, SharedNoiseModel measurementSigma, shared_ptrK calib) {
// Create a graph of newFactors with new measurements
newFactors = shared_ptr (new Graph());
@@ -121,16 +122,19 @@ int main(int argc, char* argv[]) {
g_dataFolder = string(argv[1]) + "/";
readAllDataISAM();
- // Create an NonlinearISAM which will be relinearized and reordered after every "relinearizeInterval" updates
+ // Create a NonlinearISAM which will be relinearized and reordered after every "relinearizeInterval" updates
int relinearizeInterval = 3;
NonlinearISAM isam(relinearizeInterval);
- // At each frame i with new camera pose and new set of measurements associated with it,
+ // At each frame (poseId) with new camera pose and set of associated measurements,
// create a graph of new factors and update ISAM
- for (size_t i = 0; i < g_measurements.size(); i++) {
+ typedef std::map > FeatureMap;
+ BOOST_FOREACH(const FeatureMap::value_type& features, g_measurements) {
+ const int poseId = features.first;
shared_ptr newFactors;
shared_ptr initialValues;
- createNewFactors(newFactors, initialValues, i, g_poses[i], g_measurements[i], measurementSigma, g_calib);
+ createNewFactors(newFactors, initialValues, poseId, g_poses[poseId],
+ features.second, measurementSigma, g_calib);
isam.update(*newFactors, *initialValues);
visualSLAM::Values currentEstimate = isam.estimate();
diff --git a/examples/vSLAMexample/vSLAMutils.cpp b/examples/vSLAMexample/vSLAMutils.cpp
index ae9042f2a..1c3912f2d 100644
--- a/examples/vSLAMexample/vSLAMutils.cpp
+++ b/examples/vSLAMexample/vSLAMutils.cpp
@@ -46,10 +46,6 @@ std::map readLandMarks(const std::string& landmarkFile) {
}
/* ************************************************************************* */
-/**
- * Read pose from file, output by Panda3D.
- * Warning: row major!!!
- */
gtsam::Pose3 readPose(const char* Fn) {
ifstream poseFile(Fn);
if (!poseFile) {
@@ -62,18 +58,7 @@ gtsam::Pose3 readPose(const char* Fn) {
poseFile >> v[i];
poseFile.close();
- // Because panda3d's camera is z-up, y-view,
- // we swap z and y to have y-up, z-view, then negate z to stick with the right-hand rule
- //... similar to OpenGL's camera
- for (int i = 0; i<3; i++) {
- float t = v[4+i];
- v[4+i] = v[8+i];
- v[8+i] = -t;
- }
-
- ::Vector vec = Vector_(16, v);
-
- Matrix T = Matrix_(4,4, vec); // column order !!!
+ Matrix T = Matrix_(4,4, v); // row order !!!
Pose3 pose(T);
return pose;
@@ -166,28 +151,7 @@ std::vector readAllMeasurements(const std::string& baseFolder, const
}
/* ************************************************************************* */
-std::vector readPosesISAM(const std::string& baseFolder, const std::string& posesFn) {
- ifstream posesFile((baseFolder+posesFn).c_str());
- if (!posesFile) {
- cout << "Cannot read all pose ISAM file: " << posesFn << endl;
- exit(0);
- }
- int numPoses;
- posesFile >> numPoses;
- vector poses;
- for (int i = 0; i> poseFileName;
-
- Pose3 pose = readPose((baseFolder+poseFileName).c_str());
- poses.push_back(pose);
- }
-
- return poses;
-}
-
-/* ************************************************************************* */
-std::vector > readAllMeasurementsISAM(const std::string& baseFolder, const std::string& measurementsFn) {
+std::map > readAllMeasurementsISAM(const std::string& baseFolder, const std::string& measurementsFn) {
ifstream measurementsFile((baseFolder+measurementsFn).c_str());
if (!measurementsFile) {
cout << "Cannot read all pose file: " << baseFolder+measurementsFn << endl;
@@ -196,13 +160,16 @@ std::vector > readAllMeasurementsISAM(const std::string&
int numPoses;
measurementsFile >> numPoses;
- std::vector > allFeatures;
+ std::map > allFeatures;
for (int i = 0; i> poseId;
+
string featureFileName;
measurementsFile >> featureFileName;
- vector features = readFeatures(-1, (baseFolder+featureFileName).c_str()); // we don't care about pose id in ISAM
- allFeatures.push_back(features);
+ vector features = readFeatures(poseId, (baseFolder+featureFileName).c_str());
+ allFeatures[poseId] = features;
}
return allFeatures;
diff --git a/examples/vSLAMexample/vSLAMutils.h b/examples/vSLAMexample/vSLAMutils.h
index f1483cd70..52d492224 100644
--- a/examples/vSLAMexample/vSLAMutils.h
+++ b/examples/vSLAMexample/vSLAMutils.h
@@ -29,11 +29,9 @@ std::map readLandMarks(const std::string& landmarkFile);
gtsam::Pose3 readPose(const char* poseFn);
std::map readPoses(const std::string& baseFolder, const std::string& posesFN);
-std::vector readPosesISAM(const std::string& baseFolder, const std::string& posesFN);
-
gtsam::shared_ptrK readCalibData(const std::string& calibFn);
std::vector readFeatureFile(const char* filename);
std::vector readAllMeasurements(const std::string& baseFolder, const std::string& measurementsFn);
-std::vector< std::vector > readAllMeasurementsISAM(const std::string& baseFolder, const std::string& measurementsFn);
+std::map > readAllMeasurementsISAM(const std::string& baseFolder, const std::string& measurementsFn);
diff --git a/gtsam-broken.h b/gtsam-broken.h
deleted file mode 100644
index 09113a695..000000000
--- a/gtsam-broken.h
+++ /dev/null
@@ -1,182 +0,0 @@
-// These are considered to be broken and will be added back as they start working
-// It's assumed that there have been interface changes that might break this
-
-class Ordering{
- Ordering(string key);
- void print(string s) const;
- bool equals(const Ordering& ord, double tol) const;
- Ordering subtract(const Ordering& keys) const;
- void unique ();
- void reverse ();
- void push_back(string s);
-};
-
-class GaussianFactorSet {
- GaussianFactorSet();
- void push_back(GaussianFactor* factor);
-};
-
-class Simulated2DValues {
- Simulated2DValues();
- void print(string s) const;
- void insertPose(int i, const Point2& p);
- void insertPoint(int j, const Point2& p);
- int nrPoses() const;
- int nrPoints() const;
- Point2* pose(int i);
- Point2* point(int j);
-};
-
-class Simulated2DOrientedValues {
- Simulated2DOrientedValues();
- void print(string s) const;
- void insertPose(int i, const Pose2& p);
- void insertPoint(int j, const Point2& p);
- int nrPoses() const;
- int nrPoints() const;
- Pose2* pose(int i);
- Point2* point(int j);
-};
-
-class Simulated2DPosePrior {
- Simulated2DPosePrior(Point2& mu, const SharedDiagonal& model, int i);
- void print(string s) const;
- double error(const Simulated2DValues& c) const;
-};
-
-class Simulated2DOrientedPosePrior {
- Simulated2DOrientedPosePrior(Pose2& mu, const SharedDiagonal& model, int i);
- void print(string s) const;
- double error(const Simulated2DOrientedValues& c) const;
-};
-
-class Simulated2DPointPrior {
- Simulated2DPointPrior(Point2& mu, const SharedDiagonal& model, int i);
- void print(string s) const;
- double error(const Simulated2DValues& c) const;
-};
-
-class Simulated2DOdometry {
- Simulated2DOdometry(Point2& mu, const SharedDiagonal& model, int i1, int i2);
- void print(string s) const;
- double error(const Simulated2DValues& c) const;
-};
-
-class Simulated2DOrientedOdometry {
- Simulated2DOrientedOdometry(Pose2& mu, const SharedDiagonal& model, int i1, int i2);
- void print(string s) const;
- double error(const Simulated2DOrientedValues& c) const;
-};
-
-class Simulated2DMeasurement {
- Simulated2DMeasurement(Point2& mu, const SharedDiagonal& model, int i, int j);
- void print(string s) const;
- double error(const Simulated2DValues& c) const;
-};
-
-// These are currently broken
-// Solve by parsing a namespace pose2SLAM::Values and making a Pose2SLAMValues class
-// We also have to solve the shared pointer mess to avoid duplicate methods
-
-class GaussianFactor {
- GaussianFactor(string key1,
- Matrix A1,
- Vector b_in,
- const SharedDiagonal& model);
- GaussianFactor(string key1,
- Matrix A1,
- string key2,
- Matrix A2,
- Vector b_in,
- const SharedDiagonal& model);
- GaussianFactor(string key1,
- Matrix A1,
- string key2,
- Matrix A2,
- string key3,
- Matrix A3,
- Vector b_in,
- const SharedDiagonal& model);
- bool involves(string key) const;
- Matrix getA(string key) const;
- pair matrix(const Ordering& ordering) const;
- pair eliminate(string key) const;
-};
-
-class GaussianFactorGraph {
- GaussianConditional* eliminateOne(string key);
- GaussianBayesNet* eliminate_(const Ordering& ordering);
- VectorValues* optimize_(const Ordering& ordering);
- pair matrix(const Ordering& ordering) const;
- VectorValues* steepestDescent_(const VectorValues& x0) const;
- VectorValues* conjugateGradientDescent_(const VectorValues& x0) const;
-};
-
-
-class Pose2Values{
- Pose2Values();
- Pose2 get(string key) const;
- void insert(string name, const Pose2& val);
- void print(string s) const;
- void clear();
- int size();
-};
-
-class Pose2Factor {
- Pose2Factor(string key1, string key2,
- const Pose2& measured, Matrix measurement_covariance);
- void print(string name) const;
- double error(const Pose2Values& c) const;
- size_t size() const;
- GaussianFactor* linearize(const Pose2Values& config) const;
-};
-
-class Pose2Graph{
- Pose2Graph();
- void print(string s) const;
- GaussianFactorGraph* linearize_(const Pose2Values& config) const;
- void push_back(Pose2Factor* factor);
-};
-
-class SymbolicFactor{
- SymbolicFactor(const Ordering& keys);
- void print(string s) const;
-};
-
-class Simulated2DPosePrior {
- GaussianFactor* linearize(const Simulated2DValues& config) const;
-};
-
-class Simulated2DOrientedPosePrior {
- GaussianFactor* linearize(const Simulated2DOrientedValues& config) const;
-};
-
-class Simulated2DPointPrior {
- GaussianFactor* linearize(const Simulated2DValues& config) const;
-};
-
-class Simulated2DOdometry {
- GaussianFactor* linearize(const Simulated2DValues& config) const;
-};
-
-class Simulated2DOrientedOdometry {
- GaussianFactor* linearize(const Simulated2DOrientedValues& config) const;
-};
-
-class Simulated2DMeasurement {
- GaussianFactor* linearize(const Simulated2DValues& config) const;
-};
-
-class Pose2SLAMOptimizer {
- Pose2SLAMOptimizer(string dataset_name);
- void print(string s) const;
- void update(Vector x) const;
- Vector optimize() const;
- double error() const;
- Matrix a1() const;
- Matrix a2() const;
- Vector b1() const;
- Vector b2() const;
-};
-
-
diff --git a/gtsam.h b/gtsam.h
index 331bdd09a..071ababc8 100644
--- a/gtsam.h
+++ b/gtsam.h
@@ -1,29 +1,139 @@
+/**
+ * GTSAM Wrap Module Definition
+ *
+ * These are the current classes available through the matlab toolbox interface,
+ * add more functions/classes as they are available.
+ *
+ * Requirements:
+ * Classes must start with an uppercase letter
+ * Only one Method/Constructor per line
+ * Methods can return
+ * - Eigen types: Matrix, Vector
+ * - C/C++ basic types: string, bool, size_t, int, double
+ * - void
+ * - Any class with which be copied with boost::make_shared()
+ * - boost::shared_ptr of any object type
+ * Limitations on methods
+ * - Parsing does not support overloading
+ * - There can only be one method with a given name
+ * Arguments to functions any of
+ * - Eigen types: Matrix, Vector
+ * - Eigen types and classes as an optionally const reference
+ * - C/C++ basic types: string, bool, size_t, int, double
+ * - Any class with which be copied with boost::make_shared() (except Eigen)
+ * - boost::shared_ptr of any object type (except Eigen)
+ * Comments can use either C++ or C style, with multiple lines
+ * Namespace definitions
+ * - Names of namespaces must start with a lowercase letter
+ * - start a namespace with "namespace {"
+ * - end a namespace with exactly "}///\namespace [namespace_name]", optionally adding the name of the namespace
+ * - This ending is not C++ standard, and must contain "}///\namespace" to parse
+ * - Namespaces can be nested
+ * Namespace usage
+ * - Namespaces can be specified for classes in arguments and return values
+ * - In each case, the namespace must be fully specified, e.g., "namespace1::namespace2::ClassName"
+ * Methods must start with a lowercase letter
+ * Static methods must start with a letter (upper or lowercase) and use the "static" keyword
+ * Includes in C++ wrappers
+ * - By default, the include will be <[classname].h>
+ * - To override, add a full include statement inside the class definition
+ */
+
+/**
+ * Status:
+ * - TODO: global functions
+ * - TODO: default values for arguments
+ * - TODO: overloaded functions
+ * - TODO: Handle Rot3M conversions to quaternions
+ */
+
+// Everything is in the gtsam namespace, so we avoid copying everything in
+using namespace gtsam;
+
class Point2 {
Point2();
Point2(double x, double y);
+ static Point2 Expmap(Vector v);
+ static Vector Logmap(const Point2& p);
void print(string s) const;
double x();
double y();
+ Vector localCoordinates(const Point2& p);
+ Point2 compose(const Point2& p2);
+ Point2 between(const Point2& p2);
+ Point2 retract(Vector v);
};
class Point3 {
Point3();
Point3(double x, double y, double z);
Point3(Vector v);
+ static Point3 Expmap(Vector v);
+ static Vector Logmap(const Point3& p);
void print(string s) const;
+ bool equals(const Point3& p, double tol);
Vector vector() const;
double x();
double y();
double z();
+ Vector localCoordinates(const Point3& p);
+ Point3 retract(Vector v);
+ Point3 compose(const Point3& p2);
+ Point3 between(const Point3& p2);
};
class Rot2 {
Rot2();
Rot2(double theta);
+ static Rot2 Expmap(Vector v);
+ static Vector Logmap(const Rot2& p);
+ static Rot2 fromAngle(double theta);
+ static Rot2 fromDegrees(double theta);
+ static Rot2 fromCosSin(double c, double s);
+ static Rot2 relativeBearing(const Point2& d); // Ignoring derivative
+ static Rot2 atan2(double y, double x);
void print(string s) const;
- bool equals(const Rot2& pose, double tol) const;
+ bool equals(const Rot2& rot, double tol) const;
+ double theta() const;
+ double degrees() const;
double c() const;
double s() const;
+ Vector localCoordinates(const Rot2& p);
+ Rot2 retract(Vector v);
+ Rot2 compose(const Rot2& p2);
+ Rot2 between(const Rot2& p2);
+};
+
+class Rot3 {
+ Rot3();
+ Rot3(Matrix R);
+ static Rot3 Expmap(Vector v);
+ static Vector Logmap(const Rot3& p);
+ static Rot3 ypr(double y, double p, double r);
+ static Rot3 Rx(double t);
+ static Rot3 Ry(double t);
+ static Rot3 Rz(double t);
+ static Rot3 RzRyRx(double x, double y, double z);
+ static Rot3 RzRyRx(const Vector& xyz);
+ static Rot3 yaw (double t); // positive yaw is to right (as in aircraft heading)
+ static Rot3 pitch(double t); // positive pitch is up (increasing aircraft altitude)
+ static Rot3 roll (double t); // positive roll is to right (increasing yaw in aircraft)
+ static Rot3 quaternion(double w, double x, double y, double z);
+ static Rot3 rodriguez(const Vector& v);
+ Matrix matrix() const;
+ Matrix transpose() const;
+ Vector xyz() const;
+ Vector ypr() const;
+ double roll() const;
+ double pitch() const;
+ double yaw() const;
+// Vector toQuaternion() const; // FIXME: Can't cast to Vector properly
+ void print(string s) const;
+ bool equals(const Rot3& rot, double tol) const;
+ Vector localCoordinates(const Rot3& p);
+ Rot3 retract(Vector v);
+ Rot3 compose(const Rot3& p2);
+ Rot3 between(const Rot3& p2);
};
class Pose2 {
@@ -32,15 +142,41 @@ class Pose2 {
Pose2(double theta, const Point2& t);
Pose2(const Rot2& r, const Point2& t);
Pose2(Vector v);
+ static Pose2 Expmap(Vector v);
+ static Vector Logmap(const Pose2& p);
void print(string s) const;
bool equals(const Pose2& pose, double tol) const;
double x() const;
double y() const;
double theta() const;
int dim() const;
- Pose2* compose_(const Pose2& p2);
- Pose2* between_(const Pose2& p2);
Vector localCoordinates(const Pose2& p);
+ Pose2 retract(Vector v);
+ Pose2 compose(const Pose2& p2);
+ Pose2 between(const Pose2& p2);
+ Rot2 bearing(const Point2& point);
+ double range(const Point2& point);
+};
+
+class Pose3 {
+ Pose3();
+ Pose3(const Rot3& r, const Point3& t);
+ Pose3(Vector v);
+ Pose3(Matrix t);
+ static Pose3 Expmap(Vector v);
+ static Vector Logmap(const Pose3& p);
+ void print(string s) const;
+ bool equals(const Pose3& pose, double tol) const;
+ double x() const;
+ double y() const;
+ double z() const;
+ Matrix matrix() const;
+ Matrix adjointMap() const;
+ Pose3 compose(const Pose3& p2);
+ Pose3 between(const Pose3& p2);
+ Pose3 retract(Vector v);
+ Point3 translation() const;
+ Rot3 rotation() const;
};
class SharedGaussian {
@@ -54,6 +190,12 @@ class SharedDiagonal {
Vector sample() const;
};
+class SharedNoiseModel {
+#include
+ SharedNoiseModel(const SharedDiagonal& model);
+ SharedNoiseModel(const SharedGaussian& model);
+};
+
class VectorValues {
VectorValues();
VectorValues(int nVars, int varDim);
@@ -118,6 +260,14 @@ class GaussianFactorGraph {
Matrix sparseJacobian_() const;
};
+class GaussianSequentialSolver {
+ GaussianSequentialSolver(const GaussianFactorGraph& graph, bool useQR);
+ GaussianBayesNet* eliminate() const;
+ VectorValues* optimize() const;
+ GaussianFactor* marginalFactor(int j) const;
+ Matrix marginalCovariance(int j) const;
+};
+
class KalmanFilter {
KalmanFilter(Vector x, const SharedDiagonal& model);
void print(string s) const;
@@ -129,14 +279,6 @@ class KalmanFilter {
void update(Matrix H, Vector z, const SharedDiagonal& model);
};
-class Landmark2 {
- Landmark2();
- Landmark2(double x, double y);
- void print(string s) const;
- double x();
- double y();
-};
-
class Ordering {
Ordering();
void print(string s) const;
@@ -144,22 +286,28 @@ class Ordering {
void push_back(string key);
};
-class PlanarSLAMValues {
- PlanarSLAMValues();
+// Planar SLAM example domain
+namespace planarSLAM {
+
+class Values {
+#include
+ Values();
void print(string s) const;
- Pose2* pose(int key);
+ Pose2 pose(int key) const;
+ Point2 point(int key) const;
void insertPose(int key, const Pose2& pose);
void insertPoint(int key, const Point2& point);
};
-class PlanarSLAMGraph {
- PlanarSLAMGraph();
+class Graph {
+#include
+ Graph();
void print(string s) const;
- double error(const PlanarSLAMValues& values) const;
- Ordering* orderingCOLAMD(const PlanarSLAMValues& values) const;
- GaussianFactorGraph* linearize(const PlanarSLAMValues& values,
+ double error(const planarSLAM::Values& values) const;
+ Ordering* orderingCOLAMD(const planarSLAM::Values& values) const;
+ GaussianFactorGraph* linearize(const planarSLAM::Values& values,
const Ordering& ordering) const;
void addPrior(int key, const Pose2& pose, const SharedNoiseModel& noiseModel);
@@ -169,18 +317,215 @@ class PlanarSLAMGraph {
void addRange(int poseKey, int pointKey, double range, const SharedNoiseModel& noiseModel);
void addBearingRange(int poseKey, int pointKey, const Rot2& bearing, double range,
const SharedNoiseModel& noiseModel);
- PlanarSLAMValues* optimize_(const PlanarSLAMValues& initialEstimate);
+ planarSLAM::Values optimize(const planarSLAM::Values& initialEstimate);
};
-class PlanarSLAMOdometry {
- PlanarSLAMOdometry(int key1, int key2, const Pose2& measured,
+class Odometry {
+#include
+ Odometry(int key1, int key2, const Pose2& measured,
const SharedNoiseModel& model);
void print(string s) const;
- GaussianFactor* linearize(const PlanarSLAMValues& center, const Ordering& ordering) const;
+ GaussianFactor* linearize(const planarSLAM::Values& center, const Ordering& ordering) const;
};
-class GaussianSequentialSolver {
- GaussianSequentialSolver(const GaussianFactorGraph& graph, bool useQR);
- GaussianBayesNet* eliminate();
- VectorValues* optimize();
+}///\namespace planarSLAM
+
+// Simulated2D Example Domain
+namespace simulated2D {
+
+class Values {
+#include
+ Values();
+ void insertPose(int i, const Point2& p);
+ void insertPoint(int j, const Point2& p);
+ int nrPoses() const;
+ int nrPoints() const;
+ Point2 pose(int i);
+ Point2 point(int j);
};
+
+class Graph {
+#include
+ Graph();
+};
+
+// TODO: add factors, etc.
+
+}///\namespace simulated2D
+
+// Simulated2DOriented Example Domain
+namespace simulated2DOriented {
+
+class Values {
+#include
+ Values();
+ void insertPose(int i, const Pose2& p);
+ void insertPoint(int j, const Point2& p);
+ int nrPoses() const;
+ int nrPoints() const;
+ Pose2 pose(int i);
+ Point2 point(int j);
+};
+
+class Graph {
+#include
+ Graph();
+};
+
+// TODO: add factors, etc.
+
+}///\namespace simulated2DOriented
+
+//// These are considered to be broken and will be added back as they start working
+//// It's assumed that there have been interface changes that might break this
+//
+//class Ordering{
+// Ordering(string key);
+// void print(string s) const;
+// bool equals(const Ordering& ord, double tol) const;
+// Ordering subtract(const Ordering& keys) const;
+// void unique ();
+// void reverse ();
+// void push_back(string s);
+//};
+//
+//class GaussianFactorSet {
+// GaussianFactorSet();
+// void push_back(GaussianFactor* factor);
+//};
+//
+//class Simulated2DPosePrior {
+// Simulated2DPosePrior(Point2& mu, const SharedDiagonal& model, int i);
+// void print(string s) const;
+// double error(const Simulated2DValues& c) const;
+//};
+//
+//class Simulated2DOrientedPosePrior {
+// Simulated2DOrientedPosePrior(Pose2& mu, const SharedDiagonal& model, int i);
+// void print(string s) const;
+// double error(const Simulated2DOrientedValues& c) const;
+//};
+//
+//class Simulated2DPointPrior {
+// Simulated2DPointPrior(Point2& mu, const SharedDiagonal& model, int i);
+// void print(string s) const;
+// double error(const Simulated2DValues& c) const;
+//};
+//
+//class Simulated2DOdometry {
+// Simulated2DOdometry(Point2& mu, const SharedDiagonal& model, int i1, int i2);
+// void print(string s) const;
+// double error(const Simulated2DValues& c) const;
+//};
+//
+//class Simulated2DOrientedOdometry {
+// Simulated2DOrientedOdometry(Pose2& mu, const SharedDiagonal& model, int i1, int i2);
+// void print(string s) const;
+// double error(const Simulated2DOrientedValues& c) const;
+//};
+//
+//class Simulated2DMeasurement {
+// Simulated2DMeasurement(Point2& mu, const SharedDiagonal& model, int i, int j);
+// void print(string s) const;
+// double error(const Simulated2DValues& c) const;
+//};
+//
+//class GaussianFactor {
+// GaussianFactor(string key1,
+// Matrix A1,
+// Vector b_in,
+// const SharedDiagonal& model);
+// GaussianFactor(string key1,
+// Matrix A1,
+// string key2,
+// Matrix A2,
+// Vector b_in,
+// const SharedDiagonal& model);
+// GaussianFactor(string key1,
+// Matrix A1,
+// string key2,
+// Matrix A2,
+// string key3,
+// Matrix A3,
+// Vector b_in,
+// const SharedDiagonal& model);
+// bool involves(string key) const;
+// Matrix getA(string key) const;
+// pair matrix(const Ordering& ordering) const;
+// pair eliminate(string key) const;
+//};
+//
+//class GaussianFactorGraph {
+// GaussianConditional* eliminateOne(string key);
+// GaussianBayesNet* eliminate_(const Ordering& ordering);
+// VectorValues* optimize_(const Ordering& ordering);
+// pair matrix(const Ordering& ordering) const;
+// VectorValues* steepestDescent_(const VectorValues& x0) const;
+// VectorValues* conjugateGradientDescent_(const VectorValues& x0) const;
+//};
+//
+//class Pose2Values{
+// Pose2Values();
+// Pose2 get(string key) const;
+// void insert(string name, const Pose2& val);
+// void print(string s) const;
+// void clear();
+// int size();
+//};
+//
+//class Pose2Factor {
+// Pose2Factor(string key1, string key2,
+// const Pose2& measured, Matrix measurement_covariance);
+// void print(string name) const;
+// double error(const Pose2Values& c) const;
+// size_t size() const;
+// GaussianFactor* linearize(const Pose2Values& config) const;
+//};
+//
+//class Pose2Graph{
+// Pose2Graph();
+// void print(string s) const;
+// GaussianFactorGraph* linearize_(const Pose2Values& config) const;
+// void push_back(Pose2Factor* factor);
+//};
+//
+//class SymbolicFactor{
+// SymbolicFactor(const Ordering& keys);
+// void print(string s) const;
+//};
+//
+//class Simulated2DPosePrior {
+// GaussianFactor* linearize(const Simulated2DValues& config) const;
+//};
+//
+//class Simulated2DOrientedPosePrior {
+// GaussianFactor* linearize(const Simulated2DOrientedValues& config) const;
+//};
+//
+//class Simulated2DPointPrior {
+// GaussianFactor* linearize(const Simulated2DValues& config) const;
+//};
+//
+//class Simulated2DOdometry {
+// GaussianFactor* linearize(const Simulated2DValues& config) const;
+//};
+//
+//class Simulated2DOrientedOdometry {
+// GaussianFactor* linearize(const Simulated2DOrientedValues& config) const;
+//};
+//
+//class Simulated2DMeasurement {
+// GaussianFactor* linearize(const Simulated2DValues& config) const;
+//};
+//
+//class Pose2SLAMOptimizer {
+// Pose2SLAMOptimizer(string dataset_name);
+// void print(string s) const;
+// void update(Vector x) const;
+// Vector optimize() const;
+// double error() const;
+// Matrix a1() const;
+// Matrix a2() const;
+// Vector b1() const;
+// Vector b2() const;
+//};
diff --git a/gtsam/base/TestableAssertions.h b/gtsam/base/TestableAssertions.h
index 69fa02a45..46f738f7d 100644
--- a/gtsam/base/TestableAssertions.h
+++ b/gtsam/base/TestableAssertions.h
@@ -277,6 +277,18 @@ bool assert_container_equality(const V& expected, const V& actual) {
return true;
}
+/**
+ * Compare strings for unit tests
+ */
+bool assert_equal(const std::string& expected, const std::string& actual) {
+ if (expected == actual)
+ return true;
+ printf("Not equal:\n");
+ std::cout << "expected: [" << expected << "]\n";
+ std::cout << "actual: [" << actual << "]" << std::endl;
+ return false;
+}
+
/**
* Allow for testing inequality
*/
diff --git a/gtsam/base/cholesky.cpp b/gtsam/base/cholesky.cpp
index 16f07f5ab..3f015e9d3 100644
--- a/gtsam/base/cholesky.cpp
+++ b/gtsam/base/cholesky.cpp
@@ -164,13 +164,14 @@ Eigen::LDLT::TranspositionType ldlPartial(Matrix& ABC, size_t nFrontal)
if(debug) {
cout << "Partial LDL with " << nFrontal << " frontal scalars, ";
- print(ABC, "ABC: ");
+ print(ABC, "LDL ABC: ");
}
// Compute Cholesky factorization of A, overwrites A = sqrt(D)*R
// tic(1, "ldl");
Eigen::LDLT ldlt;
ldlt.compute(ABC.block(0,0,nFrontal,nFrontal).selfadjointView());
+ if (debug) ldlt.isNegative() ? cout << "Matrix is negative" << endl : cout << "Matrix is not negative" << endl;
if(ldlt.vectorD().unaryExpr(boost::bind(less(), _1, 0.0)).any()) {
if(ISDEBUG("detailed_exceptions"))
@@ -180,14 +181,15 @@ Eigen::LDLT::TranspositionType ldlPartial(Matrix& ABC, size_t nFrontal)
}
Vector sqrtD = ldlt.vectorD().cwiseSqrt(); // FIXME: we shouldn't do sqrt in LDL
- if (debug) cout << "Dsqrt: " << sqrtD << endl;
+ if (debug) cout << "LDL Dsqrt:\n" << sqrtD << endl;
// U = sqrtD * L^
Matrix U = ldlt.matrixU();
+ if(debug) cout << "LDL U:\n" << U << endl;
// we store the permuted upper triangular matrix
ABC.block(0,0,nFrontal,nFrontal) = sqrtD.asDiagonal() * U; // FIXME: this isn't actually LDL', it's Cholesky
- if(debug) cout << "R:\n" << ABC.topLeftCorner(nFrontal,nFrontal) << endl;
+ if(debug) cout << "LDL R:\n" << ABC.topLeftCorner(nFrontal,nFrontal) << endl;
// toc(1, "ldl");
// Compute S = inv(R') * B = inv(P'U')*B = inv(U')*P*B
@@ -196,20 +198,19 @@ Eigen::LDLT::TranspositionType ldlPartial(Matrix& ABC, size_t nFrontal)
ABC.topRightCorner(nFrontal, n-nFrontal) = ldlt.transpositionsP() * ABC.topRightCorner(nFrontal, n-nFrontal);
ABC.block(0,0,nFrontal,nFrontal).triangularView().transpose().solveInPlace(ABC.topRightCorner(nFrontal, n-nFrontal));
}
- if(debug) cout << "S:\n" << ABC.topRightCorner(nFrontal, n-nFrontal) << endl;
+ if(debug) cout << "LDL S:\n" << ABC.topRightCorner(nFrontal, n-nFrontal) << endl;
// toc(2, "compute S");
// Compute L = C - S' * S
// tic(3, "compute L");
- if(debug) cout << "C:\n" << Eigen::MatrixXd(ABC.bottomRightCorner(n-nFrontal,n-nFrontal).selfadjointView()) << endl;
+ if(debug) cout << "LDL C:\n" << Eigen::MatrixXd(ABC.bottomRightCorner(n-nFrontal,n-nFrontal).selfadjointView()) << endl;
if(n - nFrontal > 0)
ABC.bottomRightCorner(n-nFrontal,n-nFrontal).selfadjointView().rankUpdate(
ABC.topRightCorner(nFrontal, n-nFrontal).transpose(), -1.0);
- if(debug) cout << "L:\n" << Eigen::MatrixXd(ABC.bottomRightCorner(n-nFrontal,n-nFrontal).selfadjointView()) << endl;
+ if(debug) cout << "LDL L:\n" << Eigen::MatrixXd(ABC.bottomRightCorner(n-nFrontal,n-nFrontal).selfadjointView()) << endl;
// toc(3, "compute L");
- if(debug) cout << "P: " << ldlt.transpositionsP().indices() << endl;
-
+ if(debug) cout << "LDL P: " << ldlt.transpositionsP().indices() << endl;
return ldlt.transpositionsP();
}
diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h
index de311249a..74cb2453d 100644
--- a/gtsam/geometry/Pose2.h
+++ b/gtsam/geometry/Pose2.h
@@ -103,11 +103,6 @@ public:
boost::optional H1 = boost::none,
boost::optional H2 = boost::none) const;
- /// MATLAB version returns shared pointer
- boost::shared_ptr compose_(const Pose2& p2) {
- return boost::shared_ptr(new Pose2(compose(p2)));
- }
-
/// compose syntactic sugar
inline Pose2 operator*(const Pose2& p2) const {
return Pose2(r_*p2.r(), t_ + r_*p2.t());
@@ -151,11 +146,6 @@ public:
boost::optional H1=boost::none,
boost::optional H2=boost::none) const;
- /// MATLAB version returns shared pointer
- boost::shared_ptr between_(const Pose2& p2) {
- return boost::shared_ptr(new Pose2(between(p2)));
- }
-
/**
* Return point coordinates in pose coordinate frame
*/
diff --git a/gtsam/geometry/Pose3.cpp b/gtsam/geometry/Pose3.cpp
index fa6f02828..6c6860f0f 100644
--- a/gtsam/geometry/Pose3.cpp
+++ b/gtsam/geometry/Pose3.cpp
@@ -38,7 +38,7 @@ namespace gtsam {
// Calculate Adjoint map
// Ad_pose is 6*6 matrix that when applied to twist xi, returns Ad_pose(xi)
// Experimental - unit tests of derivatives based on it do not check out yet
- Matrix Pose3::AdjointMap() const {
+ Matrix Pose3::adjointMap() const {
const Matrix R = R_.matrix();
const Vector t = t_.vector();
Matrix A = skewSymmetric(t)*R;
@@ -188,7 +188,7 @@ namespace gtsam {
boost::optional H1, boost::optional H2) const {
if (H1) {
#ifdef CORRECT_POSE3_EXMAP
- *H1 = AdjointMap(inverse(p2)); // FIXME: this function doesn't exist with this interface
+ *H1 = adjointMap(inverse(p2)); // FIXME: this function doesn't exist with this interface
#else
const Rot3& R2 = p2.rotation();
const Point3& t2 = p2.translation();
@@ -214,22 +214,23 @@ namespace gtsam {
/* ************************************************************************* */
Pose3 Pose3::inverse(boost::optional H1) const {
- if (H1)
+ if (H1)
#ifdef CORRECT_POSE3_EXMAP
- { *H1 = - AdjointMap(p); } // FIXME: this function doesn't exist with this interface - should this be "*H1 = -AdjointMap();" ?
+ // FIXME: this function doesn't exist with this interface - should this be "*H1 = -adjointMap();" ?
+ { *H1 = - adjointMap(p); }
#else
- {
- Matrix Rt = R_.transpose();
- Matrix DR_R1 = -R_.matrix(), DR_t1 = Z3;
- Matrix Dt_R1 = -skewSymmetric(R_.unrotate(t_).vector()), Dt_t1 = -Rt;
- Matrix DR = collect(2, &DR_R1, &DR_t1);
- Matrix Dt = collect(2, &Dt_R1, &Dt_t1);
- *H1 = gtsam::stack(2, &DR, &Dt);
- }
+ {
+ Matrix Rt = R_.transpose();
+ Matrix DR_R1 = -R_.matrix(), DR_t1 = Z3;
+ Matrix Dt_R1 = -skewSymmetric(R_.unrotate(t_).vector()), Dt_t1 = -Rt;
+ Matrix DR = collect(2, &DR_R1, &DR_t1);
+ Matrix Dt = collect(2, &Dt_R1, &Dt_t1);
+ *H1 = gtsam::stack(2, &DR, &Dt);
+ }
#endif
- Rot3 Rt = R_.inverse();
- return Pose3(Rt, Rt*(-t_));
- }
+ Rot3 Rt = R_.inverse();
+ return Pose3(Rt, Rt*(-t_));
+ }
/* ************************************************************************* */
// between = compose(p2,inverse(p1));
diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h
index f03dcde06..17b547e79 100644
--- a/gtsam/geometry/Pose3.h
+++ b/gtsam/geometry/Pose3.h
@@ -99,16 +99,16 @@ namespace gtsam {
/// @{
/// Dimensionality of tangent space = 6 DOF - used to autodetect sizes
- static size_t Dim() { return dimension; }
+ static size_t Dim() { return dimension; }
/// Dimensionality of the tangent space = 6 DOF
size_t dim() const { return dimension; }
- /** Exponential map around another pose */ /// Retraction from R^6 to Pose3 manifold neighborhood around current pose
+ /// Retraction from R^6 to Pose3 manifold neighborhood around current pose
Pose3 retract(const Vector& d) const;
- /// Logarithm map around another pose T1 /// Local 6D coordinates of Pose3 manifold neighborhood around current pose
+ /// Local 6D coordinates of Pose3 manifold neighborhood around current pose
Vector localCoordinates(const Pose3& T2) const;
/// @}
@@ -148,8 +148,8 @@ namespace gtsam {
* Calculate Adjoint map
* Ad_pose is 6*6 matrix that when applied to twist xi, returns Ad_pose(xi)
*/
- Matrix AdjointMap() const;
- Vector Adjoint(const Vector& xi) const {return AdjointMap()*xi; }
+ Matrix adjointMap() const; /// FIXME Not tested - marked as incorrect
+ Vector adjoint(const Vector& xi) const {return adjointMap()*xi; } /// FIXME Not tested - marked as incorrect
/**
* wedge for Pose3:
diff --git a/gtsam/geometry/Rot3M.cpp b/gtsam/geometry/Rot3M.cpp
index 928b9b450..a4816914e 100644
--- a/gtsam/geometry/Rot3M.cpp
+++ b/gtsam/geometry/Rot3M.cpp
@@ -25,224 +25,234 @@ using namespace std;
namespace gtsam {
- /** Explicit instantiation of base class to export members */
- INSTANTIATE_LIE(Rot3M);
+/** Explicit instantiation of base class to export members */
+INSTANTIATE_LIE(Rot3M);
- static const Matrix I3 = eye(3);
+static const Matrix I3 = eye(3);
- /* ************************************************************************* */
- // static member functions to construct rotations
+/* ************************************************************************* */
+Rot3M Rot3M::Rx(double t) {
+ double st = sin(t), ct = cos(t);
+ return Rot3M(
+ 1, 0, 0,
+ 0, ct,-st,
+ 0, st, ct);
+}
- Rot3M Rot3M::Rx(double t) {
- double st = sin(t), ct = cos(t);
- return Rot3M(
- 1, 0, 0,
- 0, ct,-st,
- 0, st, ct);
- }
+/* ************************************************************************* */
+Rot3M Rot3M::Ry(double t) {
+ double st = sin(t), ct = cos(t);
+ return Rot3M(
+ ct, 0, st,
+ 0, 1, 0,
+ -st, 0, ct);
+}
- Rot3M Rot3M::Ry(double t) {
- double st = sin(t), ct = cos(t);
- return Rot3M(
- ct, 0, st,
- 0, 1, 0,
- -st, 0, ct);
- }
+/* ************************************************************************* */
+Rot3M Rot3M::Rz(double t) {
+ double st = sin(t), ct = cos(t);
+ return Rot3M(
+ ct,-st, 0,
+ st, ct, 0,
+ 0, 0, 1);
+}
- Rot3M Rot3M::Rz(double t) {
- double st = sin(t), ct = cos(t);
- return Rot3M(
- ct,-st, 0,
- st, ct, 0,
- 0, 0, 1);
- }
+/* ************************************************************************* */
+// Considerably faster than composing matrices above !
+Rot3M Rot3M::RzRyRx(double x, double y, double z) {
+ double cx=cos(x),sx=sin(x);
+ double cy=cos(y),sy=sin(y);
+ double cz=cos(z),sz=sin(z);
+ double ss_ = sx * sy;
+ double cs_ = cx * sy;
+ double sc_ = sx * cy;
+ double cc_ = cx * cy;
+ double c_s = cx * sz;
+ double s_s = sx * sz;
+ double _cs = cy * sz;
+ double _cc = cy * cz;
+ double s_c = sx * cz;
+ double c_c = cx * cz;
+ double ssc = ss_ * cz, csc = cs_ * cz, sss = ss_ * sz, css = cs_ * sz;
+ return Rot3M(
+ _cc,- c_s + ssc, s_s + csc,
+ _cs, c_c + sss, -s_c + css,
+ -sy, sc_, cc_
+ );
+}
- // Considerably faster than composing matrices above !
- Rot3M Rot3M::RzRyRx(double x, double y, double z) {
- double cx=cos(x),sx=sin(x);
- double cy=cos(y),sy=sin(y);
- double cz=cos(z),sz=sin(z);
- double ss_ = sx * sy;
- double cs_ = cx * sy;
- double sc_ = sx * cy;
- double cc_ = cx * cy;
- double c_s = cx * sz;
- double s_s = sx * sz;
- double _cs = cy * sz;
- double _cc = cy * cz;
- double s_c = sx * cz;
- double c_c = cx * cz;
- double ssc = ss_ * cz, csc = cs_ * cz, sss = ss_ * sz, css = cs_ * sz;
- return Rot3M(
- _cc,- c_s + ssc, s_s + csc,
- _cs, c_c + sss, -s_c + css,
- -sy, sc_, cc_
- );
- }
-
- /* ************************************************************************* */
- Rot3M Rot3M::rodriguez(const Vector& w, double theta) {
- // get components of axis \omega
- double wx = w(0), wy=w(1), wz=w(2);
- double wwTxx = wx*wx, wwTyy = wy*wy, wwTzz = wz*wz;
+/* ************************************************************************* */
+Rot3M Rot3M::rodriguez(const Vector& w, double theta) {
+ // get components of axis \omega
+ double wx = w(0), wy=w(1), wz=w(2);
+ double wwTxx = wx*wx, wwTyy = wy*wy, wwTzz = wz*wz;
#ifndef NDEBUG
- double l_n = wwTxx + wwTyy + wwTzz;
- if (fabs(l_n-1.0)>1e-9) throw domain_error("rodriguez: length of n should be 1");
+ double l_n = wwTxx + wwTyy + wwTzz;
+ if (fabs(l_n-1.0)>1e-9) throw domain_error("rodriguez: length of n should be 1");
#endif
- double c = cos(theta), s = sin(theta), c_1 = 1 - c;
+ double c = cos(theta), s = sin(theta), c_1 = 1 - c;
- double swx = wx * s, swy = wy * s, swz = wz * s;
- double C00 = c_1*wwTxx, C01 = c_1*wx*wy, C02 = c_1*wx*wz;
- double C11 = c_1*wwTyy, C12 = c_1*wy*wz;
- double C22 = c_1*wwTzz;
+ double swx = wx * s, swy = wy * s, swz = wz * s;
+ double C00 = c_1*wwTxx, C01 = c_1*wx*wy, C02 = c_1*wx*wz;
+ double C11 = c_1*wwTyy, C12 = c_1*wy*wz;
+ double C22 = c_1*wwTzz;
- return Rot3M( c + C00, -swz + C01, swy + C02,
- swz + C01, c + C11, -swx + C12,
- -swy + C02, swx + C12, c + C22);
- }
+ return Rot3M(
+ c + C00, -swz + C01, swy + C02,
+ swz + C01, c + C11, -swx + C12,
+ -swy + C02, swx + C12, c + C22);
+}
- /* ************************************************************************* */
- Rot3M Rot3M::rodriguez(const Vector& w) {
- double t = w.norm();
- if (t < 1e-10) return Rot3M();
- return rodriguez(w/t, t);
- }
+/* ************************************************************************* */
+Rot3M Rot3M::rodriguez(const Vector& w) {
+ double t = w.norm();
+ if (t < 1e-10) return Rot3M();
+ return rodriguez(w/t, t);
+}
- /* ************************************************************************* */
- bool Rot3M::equals(const Rot3M & R, double tol) const {
- return equal_with_abs_tol(matrix(), R.matrix(), tol);
- }
+/* ************************************************************************* */
+bool Rot3M::equals(const Rot3M & R, double tol) const {
+ return equal_with_abs_tol(matrix(), R.matrix(), tol);
+}
- /* ************************************************************************* */
- Matrix Rot3M::matrix() const {
- double r[] = { r1_.x(), r2_.x(), r3_.x(),
- r1_.y(), r2_.y(), r3_.y(),
- r1_.z(), r2_.z(), r3_.z() };
- return Matrix_(3,3, r);
- }
+/* ************************************************************************* */
+Matrix Rot3M::matrix() const {
+ Matrix R(3,3);
+ R <<
+ r1_.x(), r2_.x(), r3_.x(),
+ r1_.y(), r2_.y(), r3_.y(),
+ r1_.z(), r2_.z(), r3_.z();
+ return R;
+}
- /* ************************************************************************* */
- Matrix Rot3M::transpose() const {
- double r[] = { r1_.x(), r1_.y(), r1_.z(),
- r2_.x(), r2_.y(), r2_.z(),
- r3_.x(), r3_.y(), r3_.z()};
- return Matrix_(3,3, r);
- }
+/* ************************************************************************* */
+Matrix Rot3M::transpose() const {
+ Matrix Rt(3,3);
+ Rt <<
+ r1_.x(), r1_.y(), r1_.z(),
+ r2_.x(), r2_.y(), r2_.z(),
+ r3_.x(), r3_.y(), r3_.z();
+ return Rt;
+}
- /* ************************************************************************* */
- Point3 Rot3M::column(int index) const{
- if(index == 3)
- return r3_;
- else if (index == 2)
- return r2_;
- else
- return r1_; // default returns r1
- }
+/* ************************************************************************* */
+Point3 Rot3M::column(int index) const{
+ if(index == 3)
+ return r3_;
+ else if (index == 2)
+ return r2_;
+ else
+ return r1_; // default returns r1
+}
- /* ************************************************************************* */
- Vector Rot3M::xyz() const {
- Matrix I;Vector q;
- boost::tie(I,q)=RQ(matrix());
- return q;
- }
+/* ************************************************************************* */
+Vector Rot3M::xyz() const {
+ Matrix I;Vector q;
+ boost::tie(I,q)=RQ(matrix());
+ return q;
+}
- Vector Rot3M::ypr() const {
- Vector q = xyz();
- return Vector_(3,q(2),q(1),q(0));
- }
+/* ************************************************************************* */
+Vector Rot3M::ypr() const {
+ Vector q = xyz();
+ return Vector_(3,q(2),q(1),q(0));
+}
- Vector Rot3M::rpy() const {
- Vector q = xyz();
- return Vector_(3,q(0),q(1),q(2));
- }
+/* ************************************************************************* */
+Vector Rot3M::rpy() const {
+ Vector q = xyz();
+ return Vector_(3,q(0),q(1),q(2));
+}
- /* ************************************************************************* */
- // Log map at identity - return the canonical coordinates of this rotation
- Vector Rot3M::Logmap(const Rot3M& R) {
- double tr = R.r1().x()+R.r2().y()+R.r3().z();
- if (tr > 3.0 - 1e-17) { // when theta = 0, +-2pi, +-4pi, etc. (or tr > 3 + 1E-10)
- return zero(3);
- } else if (tr > 3.0 - 1e-10) { // when theta near 0, +-2pi, +-4pi, etc. (or tr > 3 + 1E-3)
- double theta = acos((tr-1.0)/2.0);
- // Using Taylor expansion: theta/(2*sin(theta)) \approx 1/2+theta^2/12 + O(theta^4)
- return (0.5 + theta*theta/12)*Vector_(3,
- R.r2().z()-R.r3().y(),
- R.r3().x()-R.r1().z(),
- R.r1().y()-R.r2().x());
- } else if (fabs(tr - -1.0) < 1e-10) { // when theta = +-pi, +-3pi, +-5pi, etc.
- if(fabs(R.r3().z() - -1.0) > 1e-10)
- return (boost::math::constants::pi() / sqrt(2.0+2.0*R.r3().z())) *
- Vector_(3, R.r3().x(), R.r3().y(), 1.0+R.r3().z());
- else if(fabs(R.r2().y() - -1.0) > 1e-10)
- return (boost::math::constants::pi() / sqrt(2.0+2.0*R.r2().y())) *
- Vector_(3, R.r2().x(), 1.0+R.r2().y(), R.r2().z());
- else // if(fabs(R.r1().x() - -1.0) > 1e-10) This is implicit
- return (boost::math::constants::pi() / sqrt(2.0+2.0*R.r1().x())) *
- Vector_(3, 1.0+R.r1().x(), R.r1().y(), R.r1().z());
- } else {
- double theta = acos((tr-1.0)/2.0);
- return (theta/2.0/sin(theta))*Vector_(3,
- R.r2().z()-R.r3().y(),
- R.r3().x()-R.r1().z(),
- R.r1().y()-R.r2().x());
- }
- }
-
- /* ************************************************************************* */
- Point3 Rot3M::rotate(const Point3& p,
- boost::optional H1, boost::optional H2) const {
- if (H1) *H1 = matrix() * skewSymmetric(-p.x(), -p.y(), -p.z());
- if (H2) *H2 = matrix();
- return r1_ * p.x() + r2_ * p.y() + r3_ * p.z();
- }
-
- /* ************************************************************************* */
- // see doc/math.lyx, SO(3) section
- Point3 Rot3M::unrotate(const Point3& p,
- boost::optional H1, boost::optional H2) const {
- const Matrix Rt(transpose());
- Point3 q(Rt*p.vector()); // q = Rt*p
- if (H1) *H1 = skewSymmetric(q.x(), q.y(), q.z());
- if (H2) *H2 = Rt;
- return q;
- }
-
- /* ************************************************************************* */
- Rot3M Rot3M::compose (const Rot3M& R2,
- boost::optional H1, boost::optional H2) const {
- if (H1) *H1 = R2.transpose();
- if (H2) *H2 = I3;
- return *this * R2;
- }
-
- /* ************************************************************************* */
- Rot3M Rot3M::between (const Rot3M& R2,
- boost::optional H1, boost::optional H2) const {
- if (H1) *H1 = -(R2.transpose()*matrix());
- if (H2) *H2 = I3;
- return between_default(*this, R2);
- }
-
- /* ************************************************************************* */
- pair RQ(const Matrix& A) {
-
- double x = -atan2(-A(2, 1), A(2, 2));
- Rot3M Qx = Rot3M::Rx(-x);
- Matrix B = A * Qx.matrix();
-
- double y = -atan2(B(2, 0), B(2, 2));
- Rot3M Qy = Rot3M::Ry(-y);
- Matrix C = B * Qy.matrix();
-
- double z = -atan2(-C(1, 0), C(1, 1));
- Rot3M Qz = Rot3M::Rz(-z);
- Matrix R = C * Qz.matrix();
-
- Vector xyz = Vector_(3, x, y, z);
- return make_pair(R, xyz);
+/* ************************************************************************* */
+// Log map at identity - return the canonical coordinates of this rotation
+Vector Rot3M::Logmap(const Rot3M& R) {
+ double tr = R.r1().x()+R.r2().y()+R.r3().z();
+ // FIXME should tr in statement below be absolute value?
+ if (tr > 3.0 - 1e-17) { // when theta = 0, +-2pi, +-4pi, etc. (or tr > 3 + 1E-10)
+ return zero(3);
+ } else if (tr > 3.0 - 1e-10) { // when theta near 0, +-2pi, +-4pi, etc. (or tr > 3 + 1E-3)
+ double theta = acos((tr-1.0)/2.0);
+ // Using Taylor expansion: theta/(2*sin(theta)) \approx 1/2+theta^2/12 + O(theta^4)
+ return (0.5 + theta*theta/12)*Vector_(3,
+ R.r2().z()-R.r3().y(),
+ R.r3().x()-R.r1().z(),
+ R.r1().y()-R.r2().x());
+ // FIXME: in statement below, is this the right comparision?
+ } else if (fabs(tr - -1.0) < 1e-10) { // when theta = +-pi, +-3pi, +-5pi, etc.
+ if(fabs(R.r3().z() - -1.0) > 1e-10)
+ return (boost::math::constants::pi() / sqrt(2.0+2.0*R.r3().z())) *
+ Vector_(3, R.r3().x(), R.r3().y(), 1.0+R.r3().z());
+ else if(fabs(R.r2().y() - -1.0) > 1e-10)
+ return (boost::math::constants::pi() / sqrt(2.0+2.0*R.r2().y())) *
+ Vector_(3, R.r2().x(), 1.0+R.r2().y(), R.r2().z());
+ else // if(fabs(R.r1().x() - -1.0) > 1e-10) This is implicit
+ return (boost::math::constants::pi() / sqrt(2.0+2.0*R.r1().x())) *
+ Vector_(3, 1.0+R.r1().x(), R.r1().y(), R.r1().z());
+ } else {
+ double theta = acos((tr-1.0)/2.0);
+ return (theta/2.0/sin(theta))*Vector_(3,
+ R.r2().z()-R.r3().y(),
+ R.r3().x()-R.r1().z(),
+ R.r1().y()-R.r2().x());
}
+}
- /* ************************************************************************* */
+/* ************************************************************************* */
+Point3 Rot3M::rotate(const Point3& p,
+ boost::optional H1, boost::optional H2) const {
+ if (H1) *H1 = matrix() * skewSymmetric(-p.x(), -p.y(), -p.z());
+ if (H2) *H2 = matrix();
+ return r1_ * p.x() + r2_ * p.y() + r3_ * p.z();
+}
+
+/* ************************************************************************* */
+// see doc/math.lyx, SO(3) section
+Point3 Rot3M::unrotate(const Point3& p,
+ boost::optional H1, boost::optional H2) const {
+ const Matrix Rt(transpose());
+ Point3 q(Rt*p.vector()); // q = Rt*p
+ if (H1) *H1 = skewSymmetric(q.x(), q.y(), q.z());
+ if (H2) *H2 = Rt;
+ return q;
+}
+
+/* ************************************************************************* */
+Rot3M Rot3M::compose (const Rot3M& R2,
+ boost::optional H1, boost::optional H2) const {
+ if (H1) *H1 = R2.transpose();
+ if (H2) *H2 = I3;
+ return *this * R2;
+}
+
+/* ************************************************************************* */
+Rot3M Rot3M::between (const Rot3M& R2,
+ boost::optional H1, boost::optional H2) const {
+ if (H1) *H1 = -(R2.transpose()*matrix());
+ if (H2) *H2 = I3;
+ return between_default(*this, R2);
+}
+
+/* ************************************************************************* */
+pair RQ(const Matrix& A) {
+
+ double x = -atan2(-A(2, 1), A(2, 2));
+ Rot3M Qx = Rot3M::Rx(-x);
+ Matrix B = A * Qx.matrix();
+
+ double y = -atan2(B(2, 0), B(2, 2));
+ Rot3M Qy = Rot3M::Ry(-y);
+ Matrix C = B * Qy.matrix();
+
+ double z = -atan2(-C(1, 0), C(1, 1));
+ Rot3M Qz = Rot3M::Rz(-z);
+ Matrix R = C * Qz.matrix();
+
+ Vector xyz = Vector_(3, x, y, z);
+ return make_pair(R, xyz);
+}
+
+/* ************************************************************************* */
} // namespace gtsam
diff --git a/gtsam/geometry/Rot3M.h b/gtsam/geometry/Rot3M.h
index e41e01ef3..02ca733d1 100644
--- a/gtsam/geometry/Rot3M.h
+++ b/gtsam/geometry/Rot3M.h
@@ -226,10 +226,20 @@ namespace gtsam {
/**
* Use RQ to calculate roll-pitch-yaw angle representation
- * @return a vector containing ypr s.t. R = Rot3M::ypr(y,p,r)
+ * @return a vector containing rpy s.t. R = Rot3M::ypr(y,p,r)
*/
Vector rpy() const;
+ /**
+ * Accessors to get to components of angle representations
+ * NOTE: these are not efficient to get to multiple separate parts,
+ * you should instead use xyz() or ypr()
+ * TODO: make this more efficient
+ */
+ inline double roll() const { return ypr()(2); }
+ inline double pitch() const { return ypr()(1); }
+ inline double yaw() const { return ypr()(0); }
+
/** Compute the quaternion representation of this rotation.
* @return The quaternion
*/
diff --git a/gtsam/geometry/tests/testPose3.cpp b/gtsam/geometry/tests/testPose3.cpp
index cb336bb7e..94b81cb0c 100644
--- a/gtsam/geometry/tests/testPose3.cpp
+++ b/gtsam/geometry/tests/testPose3.cpp
@@ -51,7 +51,6 @@ TEST( Pose3, expmap_a)
v(0) = 0.3;
EXPECT(assert_equal(id.retract(v), Pose3(R, Point3())));
#ifdef CORRECT_POSE3_EXMAP
-
v(3)=0.2;v(4)=0.394742;v(5)=-2.08998;
#else
v(3)=0.2;v(4)=0.7;v(5)=-2;
@@ -100,89 +99,6 @@ namespace screw {
Pose3 expected(expectedR, expectedT);
}
-#ifdef CORRECT_POSE3_EXMAP
-/* ************************************************************************* */
-TEST(Pose3, expmap_c)
-{
- EXPECT(assert_equal(screw::expected, expm(screw::xi),1e-6));
- EXPECT(assert_equal(screw::expected, Pose3::Expmap(screw::xi),1e-6));
-}
-
-/* ************************************************************************* */
-// assert that T*exp(xi)*T^-1 is equal to exp(Ad_T(xi))
-TEST(Pose3, Adjoint)
-{
- Pose3 expected = T * Pose3::Expmap(screw::xi) * inverse(T);
- Vector xiprime = Adjoint(T, screw::xi);
- EXPECT(assert_equal(expected, Pose3::Expmap(xiprime), 1e-6));
-
- Pose3 expected2 = T2 * Pose3::Expmap(screw::xi) * inverse(T2);
- Vector xiprime2 = Adjoint(T2, screw::xi);
- EXPECT(assert_equal(expected2, Pose3::Expmap(xiprime2), 1e-6));
-
- Pose3 expected3 = T3 * Pose3::Expmap(screw::xi) * inverse(T3);
- Vector xiprime3 = Adjoint(T3, screw::xi);
- EXPECT(assert_equal(expected3, Pose3::Expmap(xiprime3), 1e-6));
-}
-
-/* ************************************************************************* */
-/** Agrawal06iros version */
-Pose3 Agrawal06iros(const Vector& xi) {
- Vector w = vector_range(xi, range(0,3));
- Vector v = vector_range(xi, range(3,6));
- double t = norm_2(w);
- if (t < 1e-5)
- return Pose3(Rot3(), expmap (v));
- else {
- Matrix W = skewSymmetric(w/t);
- Matrix A = eye(3) + ((1 - cos(t)) / t) * W + ((t - sin(t)) / t) * (W * W);
- return Pose3(Rot3::Expmap (w), expmap (A * v));
- }
-}
-
-/* ************************************************************************* */
-TEST(Pose3, expmaps_galore)
-{
- Vector xi; Pose3 actual;
- xi = Vector_(6,0.1,0.2,0.3,0.4,0.5,0.6);
- actual = Pose3::Expmap(xi);
- EXPECT(assert_equal(expm(xi), actual,1e-6));
- EXPECT(assert_equal(Agrawal06iros(xi), actual,1e-6));
- EXPECT(assert_equal(xi, localCoordinates(actual),1e-6));
-
- xi = Vector_(6,0.1,-0.2,0.3,-0.4,0.5,-0.6);
- for (double theta=1.0;0.3*theta<=M_PI;theta*=2) {
- Vector txi = xi*theta;
- actual = Pose3::Expmap(txi);
- EXPECT(assert_equal(expm(txi,30), actual,1e-6));
- EXPECT(assert_equal(Agrawal06iros(txi), actual,1e-6));
- Vector log = localCoordinates(actual);
- EXPECT(assert_equal(actual, Pose3::Expmap(log),1e-6));
- EXPECT(assert_equal(txi,log,1e-6)); // not true once wraps
- }
-
- // Works with large v as well, but expm needs 10 iterations!
- xi = Vector_(6,0.2,0.3,-0.8,100.0,120.0,-60.0);
- actual = Pose3::Expmap(xi);
- EXPECT(assert_equal(expm(xi,10), actual,1e-5));
- EXPECT(assert_equal(Agrawal06iros(xi), actual,1e-6));
- EXPECT(assert_equal(xi, localCoordinates(actual),1e-6));
-}
-
-/* ************************************************************************* */
-TEST(Pose3, Adjoint_compose)
-{
- // To debug derivatives of compose, assert that
- // T1*T2*exp(Adjoint(inv(T2),x) = T1*exp(x)*T2
- const Pose3& T1 = T;
- Vector x = Vector_(6,0.1,0.1,0.1,0.4,0.2,0.8);
- Pose3 expected = T1 * Pose3::Expmap(x) * T2;
- Vector y = Adjoint(inverse(T2), x);
- Pose3 actual = T1 * T2 * Pose3::Expmap(y);
- EXPECT(assert_equal(expected, actual, 1e-6));
-}
-#endif // SLOW_BUT_CORRECT_EXMAP
-
/* ************************************************************************* */
TEST(Pose3, expmap_c_full)
{
@@ -195,15 +111,15 @@ TEST(Pose3, expmap_c_full)
TEST(Pose3, Adjoint_full)
{
Pose3 expected = T * Pose3::Expmap(screw::xi) * T.inverse();
- Vector xiprime = T.Adjoint(screw::xi);
+ Vector xiprime = T.adjoint(screw::xi);
EXPECT(assert_equal(expected, Pose3::Expmap(xiprime), 1e-6));
Pose3 expected2 = T2 * Pose3::Expmap(screw::xi) * T2.inverse();
- Vector xiprime2 = T2.Adjoint(screw::xi);
+ Vector xiprime2 = T2.adjoint(screw::xi);
EXPECT(assert_equal(expected2, Pose3::Expmap(xiprime2), 1e-6));
Pose3 expected3 = T3 * Pose3::Expmap(screw::xi) * T3.inverse();
- Vector xiprime3 = T3.Adjoint(screw::xi);
+ Vector xiprime3 = T3.adjoint(screw::xi);
EXPECT(assert_equal(expected3, Pose3::Expmap(xiprime3), 1e-6));
}
@@ -259,7 +175,7 @@ TEST(Pose3, Adjoint_compose_full)
const Pose3& T1 = T;
Vector x = Vector_(6,0.1,0.1,0.1,0.4,0.2,0.8);
Pose3 expected = T1 * Pose3::Expmap(x) * T2;
- Vector y = T2.inverse().Adjoint(x);
+ Vector y = T2.inverse().adjoint(x);
Pose3 actual = T1 * T2 * Pose3::Expmap(y);
EXPECT(assert_equal(expected, actual, 1e-6));
}
diff --git a/gtsam/inference/BayesTree.h b/gtsam/inference/BayesTree.h
index 2f6b9735e..8cb9e3278 100644
--- a/gtsam/inference/BayesTree.h
+++ b/gtsam/inference/BayesTree.h
@@ -178,6 +178,11 @@ namespace gtsam {
/** check equality */
bool equals(const BayesTree& other, double tol = 1e-9) const;
+ /** deep copy from another tree */
+ void cloneTo(shared_ptr& newTree) const {
+ root_->cloneToBayesTree(*newTree);
+ }
+
/**
* Find parent clique of a conditional. It will look at all parents and
* return the one with the lowest index in the ordering.
diff --git a/gtsam/inference/BayesTreeCliqueBase.h b/gtsam/inference/BayesTreeCliqueBase.h
index 549814312..83496dfc0 100644
--- a/gtsam/inference/BayesTreeCliqueBase.h
+++ b/gtsam/inference/BayesTreeCliqueBase.h
@@ -77,6 +77,20 @@ namespace gtsam {
*/
static derived_ptr Create(const std::pair >& result) { return boost::make_shared(result); }
+ void cloneToBayesTree(BayesTree& newTree, shared_ptr parent_clique = shared_ptr()) const {
+ sharedConditional newConditional = sharedConditional(new CONDITIONAL(*conditional_));
+ sharedClique newClique = newTree.addClique(newConditional, parent_clique);
+ if (cachedFactor_)
+ newClique->cachedFactor_ = cachedFactor_->clone();
+ else newClique->cachedFactor_ = typename FactorType::shared_ptr();
+ if (!parent_clique) {
+ newTree.root_ = newClique;
+ }
+ BOOST_FOREACH(const shared_ptr& childClique, children_) {
+ childClique->cloneToBayesTree(newTree, newClique);
+ }
+ }
+
/** print this node */
void print(const std::string& s = "") const;
diff --git a/gtsam/inference/Permutation.h b/gtsam/inference/Permutation.h
index 421d03ad5..99d717681 100644
--- a/gtsam/inference/Permutation.h
+++ b/gtsam/inference/Permutation.h
@@ -174,6 +174,13 @@ public:
/** Access the container through the permutation (const version) */
const value_type& operator[](size_t index) const { return container_[permutation_[index]]; }
+ /** Assignment operator for cloning in ISAM2 */
+ Permuted operator=(const Permuted& other) {
+ permutation_ = other.permutation_;
+ container_ = other.container_;
+ return *this;
+ }
+
/** Permute this view by applying a permutation to the underlying permutation */
void permute(const Permutation& permutation) { assert(permutation.size() == this->size()); permutation_ = *permutation_.permute(permutation); }
diff --git a/gtsam/linear/GaussianFactor.h b/gtsam/linear/GaussianFactor.h
index 7f4b90748..2d889ee64 100644
--- a/gtsam/linear/GaussianFactor.h
+++ b/gtsam/linear/GaussianFactor.h
@@ -88,6 +88,9 @@ namespace gtsam {
/** Return the dimension of the variable pointed to by the given key iterator */
virtual size_t getDim(const_iterator variable) const = 0;
+ /** Clone a factor (make a deep copy) */
+ virtual GaussianFactor::shared_ptr clone() const = 0;
+
/**
* Permutes the GaussianFactor, but for efficiency requires the permutation
* to already be inverted. This acts just as a change-of-name for each
diff --git a/gtsam/linear/HessianFactor.h b/gtsam/linear/HessianFactor.h
index f2de0be4c..88e4364ae 100644
--- a/gtsam/linear/HessianFactor.h
+++ b/gtsam/linear/HessianFactor.h
@@ -191,6 +191,12 @@ namespace gtsam {
/** Destructor */
virtual ~HessianFactor() {}
+ /** Clone this JacobianFactor */
+ virtual GaussianFactor::shared_ptr clone() const {
+ return boost::static_pointer_cast(
+ shared_ptr(new HessianFactor(*this)));
+ }
+
/** Print the factor for debugging and testing (implementing Testable) */
virtual void print(const std::string& s = "") const;
diff --git a/gtsam/linear/JacobianFactor.h b/gtsam/linear/JacobianFactor.h
index b8f40d6ef..09089df20 100644
--- a/gtsam/linear/JacobianFactor.h
+++ b/gtsam/linear/JacobianFactor.h
@@ -136,6 +136,12 @@ namespace gtsam {
virtual ~JacobianFactor() {}
+ /** Clone this JacobianFactor */
+ virtual GaussianFactor::shared_ptr clone() const {
+ return boost::static_pointer_cast(
+ shared_ptr(new JacobianFactor(*this)));
+ }
+
// Implementing Testable interface
virtual void print(const std::string& s = "") const;
virtual bool equals(const GaussianFactor& lf, double tol = 1e-9) const;
diff --git a/gtsam/nonlinear/GaussianISAM2.h b/gtsam/nonlinear/GaussianISAM2.h
index d4d177815..fe29936cb 100644
--- a/gtsam/nonlinear/GaussianISAM2.h
+++ b/gtsam/nonlinear/GaussianISAM2.h
@@ -27,12 +27,18 @@ namespace gtsam {
*/
template >
class GaussianISAM2 : public ISAM2 {
+ typedef ISAM2 Base;
public:
/** Create an empty ISAM2 instance */
GaussianISAM2(const ISAM2Params& params) : ISAM2(params) {}
/** Create an empty ISAM2 instance using the default set of parameters (see ISAM2Params) */
GaussianISAM2() : ISAM2() {}
+
+ void cloneTo(boost::shared_ptr& newGaussianISAM2) const {
+ boost::shared_ptr isam2 = boost::static_pointer_cast(newGaussianISAM2);
+ Base::cloneTo(isam2);
+ }
};
// optimize the BayesTree, starting from the root
diff --git a/gtsam/nonlinear/ISAM2.h b/gtsam/nonlinear/ISAM2.h
index 3e3d34996..f3e960db4 100644
--- a/gtsam/nonlinear/ISAM2.h
+++ b/gtsam/nonlinear/ISAM2.h
@@ -214,6 +214,27 @@ public:
typedef typename Base::sharedClique sharedClique; ///< Shared pointer to a clique
typedef typename Base::Cliques Cliques; ///< List of Clique typedef from base class
+ void cloneTo(boost::shared_ptr& newISAM2) const {
+ boost::shared_ptr bayesTree = boost::static_pointer_cast(newISAM2);
+ Base::cloneTo(bayesTree);
+ newISAM2->theta_ = theta_;
+ newISAM2->variableIndex_ = variableIndex_;
+ newISAM2->deltaUnpermuted_ = deltaUnpermuted_;
+ newISAM2->delta_ = delta_;
+ newISAM2->nonlinearFactors_ = nonlinearFactors_;
+ newISAM2->ordering_ = ordering_;
+ newISAM2->params_ = params_;
+#ifndef NDEBUG
+ newISAM2->lastRelinVariables_ = lastRelinVariables_;
+#endif
+ newISAM2->lastAffectedVariableCount = lastAffectedVariableCount;
+ newISAM2->lastAffectedFactorCount = lastAffectedFactorCount;
+ newISAM2->lastAffectedCliqueCount = lastAffectedCliqueCount;
+ newISAM2->lastAffectedMarkedCount = lastAffectedMarkedCount;
+ newISAM2->lastBacksubVariableCount = lastBacksubVariableCount;
+ newISAM2->lastNnzTop = lastNnzTop;
+ }
+
/**
* Add new factors, updating the solution and relinearizing as needed.
*
@@ -279,6 +300,8 @@ public:
size_t lastBacksubVariableCount;
size_t lastNnzTop;
+ ISAM2Params params() const { return params_; }
+
//@}
private:
diff --git a/gtsam/slam/Landmark2.h b/gtsam/slam/Landmark2.h
deleted file mode 100644
index f67cfed56..000000000
--- a/gtsam/slam/Landmark2.h
+++ /dev/null
@@ -1,27 +0,0 @@
-/* ----------------------------------------------------------------------------
-
- * 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 Landmark2.h
- * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
- * @author Frank Dellaert
- */
-
-#pragma once
-
-#include
-
-namespace gtsam {
-
- typedef gtsam::Point2 Landmark2;
-
-}
-
diff --git a/gtsam/slam/Makefile.am b/gtsam/slam/Makefile.am
index 406431edd..fa51a9512 100644
--- a/gtsam/slam/Makefile.am
+++ b/gtsam/slam/Makefile.am
@@ -15,24 +15,12 @@ headers += simulated2DConstraints.h
sources += simulated2D.cpp smallExample.cpp
check_PROGRAMS += tests/testSimulated2D
-# MATLAB Wrap headers for simulated2D
-headers += Simulated2DMeasurement.h
-headers += Simulated2DOdometry.h
-headers += Simulated2DPointPrior.h
-headers += Simulated2DPosePrior.h
-headers += Simulated2DValues.h
-
# simulated2DOriented example
sources += simulated2DOriented.cpp
check_PROGRAMS += tests/testSimulated2DOriented
-# MATLAB Wrap headers for simulated2DOriented
-headers += Simulated2DOrientedOdometry.h
-headers += Simulated2DOrientedPosePrior.h
-headers += Simulated2DOrientedValues.h
-
# simulated3D example
-sources += Simulated3D.cpp
+sources += simulated3D.cpp
check_PROGRAMS += tests/testSimulated3D
# Generic SLAM headers
@@ -50,12 +38,6 @@ check_PROGRAMS += tests/testPose2SLAM
sources += planarSLAM.cpp
check_PROGRAMS += tests/testPlanarSLAM
-# MATLAB Wrap headers for planarSLAM
-headers += Landmark2.h
-headers += PlanarSLAMGraph.h
-headers += PlanarSLAMValues.h
-headers += PlanarSLAMOdometry.h
-
# 3D Pose constraints
sources += pose3SLAM.cpp
check_PROGRAMS += tests/testPose3SLAM
diff --git a/gtsam/slam/PlanarSLAMGraph.h b/gtsam/slam/PlanarSLAMGraph.h
deleted file mode 100644
index 98eb9aaef..000000000
--- a/gtsam/slam/PlanarSLAMGraph.h
+++ /dev/null
@@ -1,28 +0,0 @@
-/* ----------------------------------------------------------------------------
-
- * 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 PlanarSLAMGraph.h
- * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
- * @author Frank Dellaert
- */
-
-#pragma once
-
-#include
-#include
-
-namespace gtsam {
-
- typedef gtsam::planarSLAM::Graph PlanarSLAMGraph;
-
-}
-
diff --git a/gtsam/slam/PlanarSLAMOdometry.h b/gtsam/slam/PlanarSLAMOdometry.h
deleted file mode 100644
index 941eda285..000000000
--- a/gtsam/slam/PlanarSLAMOdometry.h
+++ /dev/null
@@ -1,28 +0,0 @@
-/* ----------------------------------------------------------------------------
-
- * 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 PlanarSLAMOdometry.h
- * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
- * @author Frank Dellaert
- */
-
-#pragma once
-
-#include
-#include
-
-namespace gtsam {
-
- typedef gtsam::planarSLAM::Odometry PlanarSLAMOdometry;
-
-}
-
diff --git a/gtsam/slam/PlanarSLAMValues.h b/gtsam/slam/PlanarSLAMValues.h
deleted file mode 100644
index d174229fd..000000000
--- a/gtsam/slam/PlanarSLAMValues.h
+++ /dev/null
@@ -1,27 +0,0 @@
-/* ----------------------------------------------------------------------------
-
- * 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 PlanarSLAMValues.h
- * @brief Convenience for MATLAB wrapper, which does not allow for identically named methods
- * @author Frank Dellaert
- */
-
-#pragma once
-
-#include
-
-namespace gtsam {
-
- typedef gtsam::planarSLAM::Values PlanarSLAMValues;
-
-}
-
diff --git a/gtsam/slam/Simulated2DMeasurement.h b/gtsam/slam/Simulated2DMeasurement.h
deleted file mode 100644
index 0ab661086..000000000
--- a/gtsam/slam/Simulated2DMeasurement.h
+++ /dev/null
@@ -1,28 +0,0 @@
-/* ----------------------------------------------------------------------------
-
- * 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 Simulated2DMeasurement.h
- * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
- * @author Frank Dellaert
- */
-
-#pragma once
-
-#include
-#include
-
-namespace gtsam {
-
- typedef simulated2D::Measurement Simulated2DMeasurement;
-
-}
-
diff --git a/gtsam/slam/Simulated2DOdometry.h b/gtsam/slam/Simulated2DOdometry.h
deleted file mode 100644
index 5bd3afc14..000000000
--- a/gtsam/slam/Simulated2DOdometry.h
+++ /dev/null
@@ -1,28 +0,0 @@
-/* ----------------------------------------------------------------------------
-
- * 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 Simulated2DOdometry.h
- * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
- * @author Frank Dellaert
- */
-
-#pragma once
-
-#include
-#include
-
-namespace gtsam {
-
- typedef simulated2D::Odometry Simulated2DOdometry;
-
-}
-
diff --git a/gtsam/slam/Simulated2DOrientedOdometry.h b/gtsam/slam/Simulated2DOrientedOdometry.h
deleted file mode 100644
index 1a659c081..000000000
--- a/gtsam/slam/Simulated2DOrientedOdometry.h
+++ /dev/null
@@ -1,28 +0,0 @@
-/* ----------------------------------------------------------------------------
-
- * 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 Simulated2DOrientedOdometry.h
- * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
- * @author Kai Ni
- */
-
-#pragma once
-
-#include
-#include
-
-namespace gtsam {
-
- typedef simulated2DOriented::Odometry Simulated2DOrientedOdometry;
-
-}
-
diff --git a/gtsam/slam/Simulated2DOrientedPosePrior.h b/gtsam/slam/Simulated2DOrientedPosePrior.h
deleted file mode 100644
index 54a83f1be..000000000
--- a/gtsam/slam/Simulated2DOrientedPosePrior.h
+++ /dev/null
@@ -1,29 +0,0 @@
-/* ----------------------------------------------------------------------------
-
- * 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 Simulated2DOrientedPosePrior.h
- * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
- * @author Kai Ni
- */
-
-#pragma once
-
-#include
-#include
-
-namespace gtsam {
-
- /** Create a prior on a pose Point2 with key 'x1' etc... */
- typedef simulated2DOriented::GenericPosePrior Simulated2DOrientedPosePrior;
-
-}
-
diff --git a/gtsam/slam/Simulated2DOrientedValues.h b/gtsam/slam/Simulated2DOrientedValues.h
deleted file mode 100644
index b1fe098f8..000000000
--- a/gtsam/slam/Simulated2DOrientedValues.h
+++ /dev/null
@@ -1,59 +0,0 @@
-/* ----------------------------------------------------------------------------
-
- * 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 Simulated2DValues.h
- * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
- * @author Frank Dellaert
- */
-
-#pragma once
-
-#include
-
-namespace gtsam {
-
- class Simulated2DOrientedValues: public simulated2DOriented::Values {
- public:
- typedef boost::shared_ptr sharedPoint;
- typedef boost::shared_ptr sharedPose;
-
- Simulated2DOrientedValues() {
- }
-
- void insertPose(const simulated2DOriented::PoseKey& i, const Pose2& p) {
- insert(i, p);
- }
-
- void insertPoint(const simulated2DOriented::PointKey& j, const Point2& p) {
- insert(j, p);
- }
-
- int nrPoses() const {
- return this->first_.size();
- }
-
- int nrPoints() const {
- return this->second_.size();
- }
-
- sharedPose pose(const simulated2DOriented::PoseKey& i) {
- return sharedPose(new Pose2((*this)[i]));
- }
-
- sharedPoint point(const simulated2DOriented::PointKey& j) {
- return sharedPoint(new Point2((*this)[j]));
- }
-
- };
-
-} // namespace gtsam
-
diff --git a/gtsam/slam/Simulated2DPointPrior.h b/gtsam/slam/Simulated2DPointPrior.h
deleted file mode 100644
index 8fc896d92..000000000
--- a/gtsam/slam/Simulated2DPointPrior.h
+++ /dev/null
@@ -1,29 +0,0 @@
-/* ----------------------------------------------------------------------------
-
- * 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 Simulated2DPointPrior.h
- * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
- * @author Frank Dellaert
- */
-
-#pragma once
-
-#include
-#include
-
-namespace gtsam {
-
- /** Create a prior on a landmark Point2 with key 'l1' etc... */
- typedef simulated2D::GenericPrior Simulated2DPointPrior;
-
-}
-
diff --git a/gtsam/slam/Simulated2DPosePrior.h b/gtsam/slam/Simulated2DPosePrior.h
deleted file mode 100644
index 1c85e4d5b..000000000
--- a/gtsam/slam/Simulated2DPosePrior.h
+++ /dev/null
@@ -1,29 +0,0 @@
-/* ----------------------------------------------------------------------------
-
- * 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 Simulated2DPosePrior.h
- * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
- * @author Frank Dellaert
- */
-
-#pragma once
-
-#include
-#include
-
-namespace gtsam {
-
- /** Create a prior on a pose Point2 with key 'x1' etc... */
- typedef simulated2D::GenericPrior Simulated2DPosePrior;
-
-}
-
diff --git a/gtsam/slam/Simulated2DValues.h b/gtsam/slam/Simulated2DValues.h
deleted file mode 100644
index c4d1d1534..000000000
--- a/gtsam/slam/Simulated2DValues.h
+++ /dev/null
@@ -1,58 +0,0 @@
-/* ----------------------------------------------------------------------------
-
- * 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 Simulated2DValues.h
- * @brief Re-created on Feb 22, 2010 for compatibility with MATLAB
- * @author Frank Dellaert
- */
-
-#pragma once
-
-#include
-
-namespace gtsam {
-
- class Simulated2DValues: public simulated2D::Values {
- public:
- typedef boost::shared_ptr sharedPoint;
-
- Simulated2DValues() {
- }
-
- void insertPose(const simulated2D::PoseKey& i, const Point2& p) {
- insert(i, p);
- }
-
- void insertPoint(const simulated2D::PointKey& j, const Point2& p) {
- insert(j, p);
- }
-
- int nrPoses() const {
- return this->first_.size();
- }
-
- int nrPoints() const {
- return this->second_.size();
- }
-
- sharedPoint pose(const simulated2D::PoseKey& i) {
- return sharedPoint(new Point2((*this)[i]));
- }
-
- sharedPoint point(const simulated2D::PointKey& j) {
- return sharedPoint(new Point2((*this)[j]));
- }
-
- };
-
-} // namespace gtsam
-
diff --git a/gtsam/slam/Simulated3D.cpp b/gtsam/slam/Simulated3D.cpp
index 76e65a8cf..e2f6211a5 100644
--- a/gtsam/slam/Simulated3D.cpp
+++ b/gtsam/slam/Simulated3D.cpp
@@ -15,7 +15,7 @@
* @author Alex Cunningham
**/
-#include
+#include
namespace gtsam {
diff --git a/gtsam/slam/planarSLAM.h b/gtsam/slam/planarSLAM.h
index 228ced08c..5776e989c 100644
--- a/gtsam/slam/planarSLAM.h
+++ b/gtsam/slam/planarSLAM.h
@@ -71,10 +71,10 @@ namespace gtsam {
// Convenience for MATLAB wrapper, which does not allow for identically named methods
/// get a pose
- boost::shared_ptr pose(int key) {
- Pose2 pose = (*this)[PoseKey(key)];
- return boost::shared_ptr(new Pose2(pose));
- }
+ Pose2 pose(int key) const { return (*this)[PoseKey(key)]; }
+
+ /// get a point
+ Point2 point(int key) const { return (*this)[PointKey(key)]; }
/// insert a pose
void insertPose(int key, const Pose2& pose) {insert(PoseKey(key), pose); }
@@ -131,14 +131,11 @@ namespace gtsam {
void addBearingRange(const PoseKey& poseKey, const PointKey& pointKey,
const Rot2& bearing, double range, const SharedNoiseModel& model);
- /// Optimize_ for MATLAB
- boost::shared_ptr optimize_(const Values& initialEstimate) {
+ /// Optimize
+ Values optimize(const Values& initialEstimate) {
typedef NonlinearOptimizer Optimizer;
- boost::shared_ptr result(
- new Values(
- *Optimizer::optimizeLM(*this, initialEstimate,
- NonlinearOptimizationParameters::LAMBDA)));
- return result;
+ return *Optimizer::optimizeLM(*this, initialEstimate,
+ NonlinearOptimizationParameters::LAMBDA);
}
};
diff --git a/gtsam/slam/simulated2D.h b/gtsam/slam/simulated2D.h
index 3b63c9595..cae60bb80 100644
--- a/gtsam/slam/simulated2D.h
+++ b/gtsam/slam/simulated2D.h
@@ -21,6 +21,7 @@
#include
#include
#include
+#include
// \namespace
@@ -72,13 +73,13 @@ namespace gtsam {
}
/// Return pose i
- sharedPoint pose(const simulated2D::PoseKey& i) {
- return sharedPoint(new Point2((*this)[i]));
+ Point2 pose(const simulated2D::PoseKey& i) const {
+ return (*this)[i];
}
/// Return point j
- sharedPoint point(const simulated2D::PointKey& j) {
- return sharedPoint(new Point2((*this)[j]));
+ Point2 point(const simulated2D::PointKey& j) const {
+ return (*this)[j];
}
};
@@ -232,5 +233,12 @@ namespace gtsam {
typedef GenericOdometry Odometry;
typedef GenericMeasurement Measurement;
+ // Specialization of a graph for this example domain
+ // TODO: add functions to add factor types
+ class Graph : public NonlinearFactorGraph {
+ public:
+ Graph() {}
+ };
+
} // namespace simulated2D
} // namespace gtsam
diff --git a/gtsam/slam/simulated2DOriented.h b/gtsam/slam/simulated2DOriented.h
index 3710f29ad..b9cf150ef 100644
--- a/gtsam/slam/simulated2DOriented.h
+++ b/gtsam/slam/simulated2DOriented.h
@@ -21,6 +21,7 @@
#include
#include
#include
+#include
// \namespace
@@ -33,7 +34,27 @@ namespace gtsam {
typedef TypedSymbol PoseKey;
typedef Values PoseValues;
typedef Values PointValues;
- typedef TupleValues2 Values;
+
+ /// Specialized Values structure with syntactic sugar for
+ /// compatibility with matlab
+ class Values: public TupleValues2 {
+ public:
+ Values() {}
+
+ void insertPose(const PoseKey& i, const Pose2& p) {
+ insert(i, p);
+ }
+
+ void insertPoint(const PointKey& j, const Point2& p) {
+ insert(j, p);
+ }
+
+ int nrPoses() const { return this->first_.size(); }
+ int nrPoints() const { return this->second_.size(); }
+
+ Pose2 pose(const PoseKey& i) const { return (*this)[i]; }
+ Point2 point(const PointKey& j) const { return (*this)[j]; }
+ };
//TODO:: point prior is not implemented right now
@@ -100,5 +121,12 @@ namespace gtsam {
typedef GenericOdometry Odometry;
+ /// Graph specialization for syntactic sugar use with matlab
+ class Graph : public NonlinearFactorGraph {
+ public:
+ Graph() {}
+ // TODO: add functions to add factors
+ };
+
} // namespace simulated2DOriented
} // namespace gtsam
diff --git a/gtsam/slam/simulated3D.cpp b/gtsam/slam/simulated3D.cpp
new file mode 100644
index 000000000..e2f6211a5
--- /dev/null
+++ b/gtsam/slam/simulated3D.cpp
@@ -0,0 +1,43 @@
+/* ----------------------------------------------------------------------------
+
+ * 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 Simulated3D.cpp
+* @brief measurement functions and derivatives for simulated 3D robot
+* @author Alex Cunningham
+**/
+
+#include
+
+namespace gtsam {
+
+namespace simulated3D {
+
+Point3 prior (const Point3& x, boost::optional H) {
+ if (H) *H = eye(3);
+ return x;
+}
+
+Point3 odo(const Point3& x1, const Point3& x2,
+ boost::optional H1, boost::optional H2) {
+ if (H1) *H1 = -1 * eye(3);
+ if (H2) *H2 = eye(3);
+ return x2 - x1;
+}
+
+Point3 mea(const Point3& x, const Point3& l,
+ boost::optional H1, boost::optional H2) {
+ if (H1) *H1 = -1 * eye(3);
+ if (H2) *H2 = eye(3);
+ return l - x;
+}
+
+}} // namespace gtsam::simulated3D
diff --git a/gtsam/slam/simulated3D.h b/gtsam/slam/simulated3D.h
new file mode 100644
index 000000000..32f05e967
--- /dev/null
+++ b/gtsam/slam/simulated3D.h
@@ -0,0 +1,132 @@
+/* ----------------------------------------------------------------------------
+
+ * 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 Simulated3D.h
+ * @brief measurement functions and derivatives for simulated 3D robot
+ * @author Alex Cunningham
+ **/
+
+// \callgraph
+
+#pragma once
+
+#include
+#include
+#include
+#include
+#include
+#include
+
+// \namespace
+
+namespace gtsam {
+namespace simulated3D {
+
+/**
+ * This is a linear SLAM domain where both poses and landmarks are
+ * 3D points, without rotation. The structure and use is based on
+ * the simulated2D domain.
+ */
+
+typedef gtsam::TypedSymbol PoseKey;
+typedef gtsam::TypedSymbol PointKey;
+
+typedef Values PoseValues;
+typedef Values PointValues;
+typedef TupleValues2 Values;
+
+/**
+ * Prior on a single pose
+ */
+Point3 prior(const Point3& x, boost::optional H = boost::none);
+
+/**
+ * odometry between two poses
+ */
+Point3 odo(const Point3& x1, const Point3& x2,
+ boost::optional H1 = boost::none,
+ boost::optional H2 = boost::none);
+
+/**
+ * measurement between landmark and pose
+ */
+Point3 mea(const Point3& x, const Point3& l,
+ boost::optional H1 = boost::none,
+ boost::optional H2 = boost::none);
+
+/**
+ * A prior factor on a single linear robot pose
+ */
+struct PointPrior3D: public NonlinearFactor1 {
+
+ Point3 z_; ///< The prior pose value for the variable attached to this factor
+
+ /**
+ * Constructor for a prior factor
+ * @param z is the measured/prior position for the pose
+ * @param model is the measurement model for the factor (Dimension: 3)
+ * @param j is the key for the pose
+ */
+ PointPrior3D(const Point3& z,
+ const SharedNoiseModel& model, const PoseKey& j) :
+ NonlinearFactor1 (model, j), z_(z) {
+ }
+
+ /**
+ * Evaluates the error at a given value of x,
+ * with optional derivatives.
+ * @param x is the current value of the variable
+ * @param H is an optional Jacobian matrix (Dimension: 3x3)
+ * @return Vector error between prior value and x (Dimension: 3)
+ */
+ Vector evaluateError(const Point3& x, boost::optional H =
+ boost::none) {
+ return (prior(x, H) - z_).vector();
+ }
+};
+
+/**
+ * Models a linear 3D measurement between 3D points
+ */
+struct Simulated3DMeasurement: public NonlinearFactor2 {
+
+ Point3 z_; ///< Linear displacement between a pose and landmark
+
+ /**
+ * Creates a measurement factor with a given measurement
+ * @param z is the measurement, a linear displacement between poses and landmarks
+ * @param model is a measurement model for the factor (Dimension: 3)
+ * @param j1 is the pose key of the robot
+ * @param j2 is the point key for the landmark
+ */
+ Simulated3DMeasurement(const Point3& z,
+ const SharedNoiseModel& model, PoseKey& j1, PointKey j2) :
+ NonlinearFactor2 (
+ model, j1, j2), z_(z) {
+ }
+
+ /**
+ * Error function with optional derivatives
+ * @param x1 a robot pose value
+ * @param x2 a landmark point value
+ * @param H1 is an optional Jacobian matrix in terms of x1 (Dimension: 3x3)
+ * @param H2 is an optional Jacobian matrix in terms of x2 (Dimension: 3x3)
+ * @return vector error between measurement and prediction (Dimension: 3)
+ */
+ Vector evaluateError(const Point3& x1, const Point3& x2, boost::optional<
+ Matrix&> H1 = boost::none, boost::optional H2 = boost::none) {
+ return (mea(x1, x2, H1, H2) - z_).vector();
+ }
+};
+
+}} // namespace simulated3D
diff --git a/gtsam/slam/tests/testSimulated3D.cpp b/gtsam/slam/tests/testSimulated3D.cpp
index de2c534bb..30f41e2fd 100644
--- a/gtsam/slam/tests/testSimulated3D.cpp
+++ b/gtsam/slam/tests/testSimulated3D.cpp
@@ -21,7 +21,7 @@
#include
#include
#include
-#include
+#include
using namespace gtsam;
diff --git a/myconfigure.matlab b/myconfigure.matlab
index 33addb665..a94644b77 100755
--- a/myconfigure.matlab
+++ b/myconfigure.matlab
@@ -1 +1,12 @@
-../configure --prefix=$HOME --with-toolbox=$HOME/toolbox --enable-build-toolbox CFLAGS="-fno-inline -g -Wall" CXXFLAGS="-fno-inline -g -Wall" LDFLAGS="-fno-inline -g -Wall" --disable-static --disable-fast-install
+../configure --prefix=$HOME \
+ --with-toolbox=$HOME/toolbox \
+ --enable-build-toolbox \
+ --enable-install-matlab-tests \
+ --enable-install-matlab-examples \
+ --enable-install-wrap \
+ --with-wrap=$HOME/bin \
+ CFLAGS="-fno-inline -g -Wall" \
+ CXXFLAGS="-fno-inline -g -Wall" \
+ LDFLAGS="-fno-inline -g -Wall" \
+ --disable-static \
+ --disable-fast-install
diff --git a/tests/matlab/test_gtsam.m b/tests/matlab/test_gtsam.m
new file mode 100644
index 000000000..aab3dac0f
--- /dev/null
+++ b/tests/matlab/test_gtsam.m
@@ -0,0 +1,10 @@
+% Test runner script - runs each test
+
+display 'Starting: testJacobianFactor'
+testJacobianFactor
+
+display 'Starting: testKalmanFilter'
+testKalmanFilter
+
+% end of tests
+display 'Tests complete!'
diff --git a/tests/testGaussianISAM2.cpp b/tests/testGaussianISAM2.cpp
index 378afade3..121717cf3 100644
--- a/tests/testGaussianISAM2.cpp
+++ b/tests/testGaussianISAM2.cpp
@@ -292,6 +292,110 @@ TEST(ISAM2, slamlike_solution)
EXPECT(isam_check(fullgraph, fullinit, isam));
}
+/* ************************************************************************* */
+TEST_UNSAFE(ISAM2, clone) {
+
+ // Pose and landmark key types from planarSLAM
+ typedef planarSLAM::PoseKey PoseKey;
+ typedef planarSLAM::PointKey PointKey;
+
+ // Set up parameters
+ SharedDiagonal odoNoise = sharedSigmas(Vector_(3, 0.1, 0.1, M_PI/100.0));
+ SharedDiagonal brNoise = sharedSigmas(Vector_(2, M_PI/100.0, 0.1));
+
+ // These variables will be reused and accumulate factors and values
+ GaussianISAM2 isam(ISAM2Params(0.001, 0.0, 0, false, true));
+ planarSLAM::Values fullinit;
+ planarSLAM::Graph fullgraph;
+
+ // i keeps track of the time step
+ size_t i = 0;
+
+ // Add a prior at time 0 and update isam
+ {
+ planarSLAM::Graph newfactors;
+ newfactors.addPrior(0, Pose2(0.0, 0.0, 0.0), odoNoise);
+ fullgraph.push_back(newfactors);
+
+ planarSLAM::Values init;
+ init.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01));
+ fullinit.insert(PoseKey(0), Pose2(0.01, 0.01, 0.01));
+
+ isam.update(newfactors, init);
+ }
+
+ EXPECT(isam_check(fullgraph, fullinit, isam));
+
+ // Add odometry from time 0 to time 5
+ for( ; i<5; ++i) {
+ planarSLAM::Graph newfactors;
+ newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
+ fullgraph.push_back(newfactors);
+
+ planarSLAM::Values init;
+ init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
+ fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
+
+ isam.update(newfactors, init);
+ }
+
+ // Add odometry from time 5 to 6 and landmark measurement at time 5
+ {
+ planarSLAM::Graph newfactors;
+ newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
+ newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0), 5.0, brNoise);
+ newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0), 5.0, brNoise);
+ fullgraph.push_back(newfactors);
+
+ planarSLAM::Values init;
+ init.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01));
+ init.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0)));
+ init.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0)));
+ fullinit.insert(PoseKey(i+1), Pose2(1.01, 0.01, 0.01));
+ fullinit.insert(PointKey(0), Point2(5.0/sqrt(2.0), 5.0/sqrt(2.0)));
+ fullinit.insert(PointKey(1), Point2(5.0/sqrt(2.0), -5.0/sqrt(2.0)));
+
+ isam.update(newfactors, init);
+ ++ i;
+ }
+
+ // Add odometry from time 6 to time 10
+ for( ; i<10; ++i) {
+ planarSLAM::Graph newfactors;
+ newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
+ fullgraph.push_back(newfactors);
+
+ planarSLAM::Values init;
+ init.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
+ fullinit.insert(PoseKey(i+1), Pose2(double(i+1)+0.1, -0.1, 0.01));
+
+ isam.update(newfactors, init);
+ }
+
+ // Add odometry from time 10 to 11 and landmark measurement at time 10
+ {
+ planarSLAM::Graph newfactors;
+ newfactors.addOdometry(i, i+1, Pose2(1.0, 0.0, 0.0), odoNoise);
+ newfactors.addBearingRange(i, 0, Rot2::fromAngle(M_PI/4.0 + M_PI/16.0), 4.5, brNoise);
+ newfactors.addBearingRange(i, 1, Rot2::fromAngle(-M_PI/4.0 + M_PI/16.0), 4.5, brNoise);
+ fullgraph.push_back(newfactors);
+
+ planarSLAM::Values init;
+ init.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01));
+ fullinit.insert(PoseKey(i+1), Pose2(6.9, 0.1, 0.01));
+
+ isam.update(newfactors, init);
+ ++ i;
+ }
+
+ // CLONING...
+ boost::shared_ptr > isam2
+ = boost::shared_ptr >(new GaussianISAM2());
+ isam.cloneTo(isam2);
+
+ CHECK(assert_equal(isam, *isam2));
+}
+
/* ************************************************************************* */
int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
/* ************************************************************************* */
diff --git a/wrap/Argument.cpp b/wrap/Argument.cpp
index e0d01ab63..1610f98aa 100644
--- a/wrap/Argument.cpp
+++ b/wrap/Argument.cpp
@@ -22,34 +22,43 @@
#include "Argument.h"
using namespace std;
+using namespace wrap;
/* ************************************************************************* */
-void Argument::matlab_unwrap(ofstream& ofs,
- const string& matlabName)
-{
+void Argument::matlab_unwrap(ofstream& ofs, const string& matlabName) const {
ofs << " ";
+ string cppType = qualifiedType("::");
+ string matlabType = qualifiedType();
+
if (is_ptr)
// A pointer: emit an "unwrap_shared_ptr" call which returns a pointer
- ofs << "shared_ptr<" << type << "> " << name << " = unwrap_shared_ptr< ";
+ ofs << "shared_ptr<" << cppType << "> " << name << " = unwrap_shared_ptr< ";
else if (is_ref)
// A reference: emit an "unwrap_shared_ptr" call and de-reference the pointer
- ofs << type << "& " << name << " = *unwrap_shared_ptr< ";
+ ofs << cppType << "& " << name << " = *unwrap_shared_ptr< ";
else
// Not a pointer or a reference: emit an "unwrap" call
// unwrap is specified in matlab.h as a series of template specializations
// that know how to unpack the expected MATLAB object
// example: double tol = unwrap< double >(in[2]);
// example: Vector v = unwrap< Vector >(in[1]);
- ofs << type << " " << name << " = unwrap< ";
+ ofs << cppType << " " << name << " = unwrap< ";
- ofs << type << " >(" << matlabName;
- if (is_ptr || is_ref) ofs << ", \"" << type << "\"";
+ ofs << cppType << " >(" << matlabName;
+ if (is_ptr || is_ref) ofs << ", \"" << matlabType << "\"";
ofs << ");" << endl;
}
/* ************************************************************************* */
-string ArgumentList::types() {
+string Argument::qualifiedType(const string& delim) const {
+ string result;
+ BOOST_FOREACH(const string& ns, namespaces) result += ns + delim;
+ return result + type;
+}
+
+/* ************************************************************************* */
+string ArgumentList::types() const {
string str;
bool first=true;
BOOST_FOREACH(Argument arg, *this) {
@@ -59,7 +68,7 @@ string ArgumentList::types() {
}
/* ************************************************************************* */
-string ArgumentList::signature() {
+string ArgumentList::signature() const {
string str;
BOOST_FOREACH(Argument arg, *this)
str += arg.type[0];
@@ -67,7 +76,7 @@ string ArgumentList::signature() {
}
/* ************************************************************************* */
-string ArgumentList::names() {
+string ArgumentList::names() const {
string str;
bool first=true;
BOOST_FOREACH(Argument arg, *this) {
@@ -77,7 +86,7 @@ string ArgumentList::names() {
}
/* ************************************************************************* */
-void ArgumentList::matlab_unwrap(ofstream& ofs, int start) {
+void ArgumentList::matlab_unwrap(ofstream& ofs, int start) const {
int index = start;
BOOST_FOREACH(Argument arg, *this) {
stringstream buf;
diff --git a/wrap/Argument.h b/wrap/Argument.h
index 2248e1790..cb5b1b8c8 100644
--- a/wrap/Argument.h
+++ b/wrap/Argument.h
@@ -18,27 +18,32 @@
#pragma once
#include
-#include
+#include
+
+namespace wrap {
/// Argument class
struct Argument {
bool is_const, is_ref, is_ptr;
std::string type;
std::string name;
+ std::vector namespaces;
Argument() :
is_const(false), is_ref(false), is_ptr(false) {
}
+ std::string qualifiedType(const std::string& delim = "") const; // adds namespaces to type
+
/// MATLAB code generation, MATLAB to C++
- void matlab_unwrap(std::ofstream& ofs, const std::string& matlabName);
+ void matlab_unwrap(std::ofstream& ofs, const std::string& matlabName) const;
};
/// Argument list
-struct ArgumentList: public std::list {
- std::list args;
- std::string types();
- std::string signature();
- std::string names();
+struct ArgumentList: public std::vector {
+ std::vector args; // why does it contain this?
+ std::string types() const;
+ std::string signature() const;
+ std::string names() const;
// MATLAB code generation:
@@ -47,6 +52,8 @@ struct ArgumentList: public std::list {
* @param ofs output stream
* @param start initial index for input array, set to 1 for method
*/
- void matlab_unwrap(std::ofstream& ofs, int start = 0); // MATLAB to C++
+ void matlab_unwrap(std::ofstream& ofs, int start = 0) const; // MATLAB to C++
};
+} // \namespace wrap
+
diff --git a/wrap/Class.cpp b/wrap/Class.cpp
index d701731d8..47e01f00b 100644
--- a/wrap/Class.cpp
+++ b/wrap/Class.cpp
@@ -14,6 +14,7 @@
* @author Frank Dellaert
**/
+#include
#include
#include
@@ -23,24 +24,28 @@
#include "utilities.h"
using namespace std;
+using namespace wrap;
/* ************************************************************************* */
-void Class::matlab_proxy(const string& classFile) {
+void Class::matlab_proxy(const string& classFile) const {
// open destination classFile
ofstream ofs(classFile.c_str());
if(!ofs) throw CantOpenFile(classFile);
if(verbose_) cerr << "generating " << classFile << endl;
+ // get the name of actual matlab object
+ string matlabName = qualifiedName();
+
// emit class proxy code
- ofs << "classdef " << name << endl;
+ ofs << "classdef " << matlabName << endl;
ofs << " properties" << endl;
ofs << " self = 0" << endl;
ofs << " end" << endl;
ofs << " methods" << endl;
- ofs << " function obj = " << name << "(varargin)" << endl;
+ ofs << " function obj = " << matlabName << "(varargin)" << endl;
BOOST_FOREACH(Constructor c, constructors)
- c.matlab_proxy_fragment(ofs,name);
- ofs << " if nargin ~= 13 && obj.self == 0, error('" << name << " constructor failed'); end" << endl;
+ c.matlab_proxy_fragment(ofs,matlabName);
+ ofs << " if nargin ~= 13 && obj.self == 0, error('" << matlabName << " constructor failed'); end" << endl;
ofs << " end" << endl;
ofs << " function display(obj), obj.print(''); end" << endl;
ofs << " function disp(obj), obj.display; end" << endl;
@@ -52,33 +57,98 @@ void Class::matlab_proxy(const string& classFile) {
}
/* ************************************************************************* */
-void Class::matlab_constructors(const string& toolboxPath,const string& nameSpace) {
+void Class::matlab_constructors(const string& toolboxPath, const vector& using_namespaces) const {
BOOST_FOREACH(Constructor c, constructors) {
- c.matlab_mfile (toolboxPath, name);
- c.matlab_wrapper(toolboxPath, name, nameSpace);
+ c.matlab_mfile (toolboxPath, qualifiedName());
+ c.matlab_wrapper(toolboxPath, qualifiedName("::"), qualifiedName(), using_namespaces, includes);
}
}
/* ************************************************************************* */
-void Class::matlab_methods(const string& classPath, const string& nameSpace) {
+void Class::matlab_methods(const string& classPath, const vector& using_namespaces) const {
+ string matlabName = qualifiedName(), cppName = qualifiedName("::");
BOOST_FOREACH(Method m, methods) {
m.matlab_mfile (classPath);
- m.matlab_wrapper(classPath, name, nameSpace);
+ m.matlab_wrapper(classPath, name, cppName, matlabName, using_namespaces, includes);
+ }
+}
+
+/* ************************************************************************* */
+void Class::matlab_static_methods(const string& toolboxPath, const vector& using_namespaces) const {
+ string matlabName = qualifiedName(), cppName = qualifiedName("::");
+ BOOST_FOREACH(const StaticMethod& m, static_methods) {
+ m.matlab_mfile (toolboxPath, qualifiedName());
+ m.matlab_wrapper(toolboxPath, name, matlabName, cppName, using_namespaces, includes);
}
}
/* ************************************************************************* */
void Class::matlab_make_fragment(ofstream& ofs,
const string& toolboxPath,
- const string& mexFlags)
-{
+ const string& mexFlags) const {
string mex = "mex " + mexFlags + " ";
+ string matlabClassName = qualifiedName();
BOOST_FOREACH(Constructor c, constructors)
- ofs << mex << c.matlab_wrapper_name(name) << ".cpp" << endl;
- ofs << endl << "cd @" << name << endl;
+ ofs << mex << c.matlab_wrapper_name(matlabClassName) << ".cpp" << endl;
+ BOOST_FOREACH(StaticMethod sm, static_methods)
+ ofs << mex << matlabClassName + "_" + sm.name << ".cpp" << endl;
+ ofs << endl << "cd @" << matlabClassName << endl;
BOOST_FOREACH(Method m, methods)
- ofs << mex << m.name_ << ".cpp" << endl;
+ ofs << mex << m.name << ".cpp" << endl;
ofs << endl;
}
/* ************************************************************************* */
+void Class::makefile_fragment(ofstream& ofs) const {
+// new_Point2_.$(MEXENDING): new_Point2_.cpp
+// $(MEX) $(mex_flags) new_Point2_.cpp
+// new_Point2_dd.$(MEXENDING): new_Point2_dd.cpp
+// $(MEX) $(mex_flags) new_Point2_dd.cpp
+// @Point2/x.$(MEXENDING): @Point2/x.cpp
+// $(MEX) $(mex_flags) @Point2/x.cpp -output @Point2/x
+// @Point2/y.$(MEXENDING): @Point2/y.cpp
+// $(MEX) $(mex_flags) @Point2/y.cpp -output @Point2/y
+// @Point2/dim.$(MEXENDING): @Point2/dim.cpp
+// $(MEX) $(mex_flags) @Point2/dim.cpp -output @Point2/dim
+//
+// Point2: new_Point2_.$(MEXENDING) new_Point2_dd.$(MEXENDING) @Point2/x.$(MEXENDING) @Point2/y.$(MEXENDING) @Point2/dim.$(MEXENDING)
+
+ string matlabName = qualifiedName();
+
+ // collect names
+ vector file_names;
+ BOOST_FOREACH(Constructor c, constructors) {
+ string file_base = c.matlab_wrapper_name(matlabName);
+ file_names.push_back(file_base);
+ }
+ BOOST_FOREACH(StaticMethod c, static_methods) {
+ string file_base = matlabName + "_" + c.name;
+ file_names.push_back(file_base);
+ }
+ BOOST_FOREACH(Method c, methods) {
+ string file_base = "@" + matlabName + "/" + c.name;
+ file_names.push_back(file_base);
+ }
+
+ BOOST_FOREACH(const string& file_base, file_names) {
+ ofs << file_base << ".$(MEXENDING): " << file_base << ".cpp" << endl;
+ ofs << "\t$(MEX) $(mex_flags) " << file_base << ".cpp -output " << file_base << endl;
+ }
+
+ // class target
+ ofs << "\n" << matlabName << ": ";
+ BOOST_FOREACH(const string& file_base, file_names) {
+ ofs << file_base << ".$(MEXENDING) ";
+ }
+ ofs << "\n" << endl;
+}
+
+/* ************************************************************************* */
+string Class::qualifiedName(const string& delim) const {
+ string result;
+ BOOST_FOREACH(const string& ns, namespaces)
+ result += ns + delim;
+ return result + name;
+}
+
+/* ************************************************************************* */
diff --git a/wrap/Class.h b/wrap/Class.h
index ca85b06b1..d8ebe1a10 100644
--- a/wrap/Class.h
+++ b/wrap/Class.h
@@ -18,10 +18,12 @@
#pragma once
#include
-#include
#include "Constructor.h"
#include "Method.h"
+#include "StaticMethod.h"
+
+namespace wrap {
/// Class has name, constructors, methods
struct Class {
@@ -29,19 +31,28 @@ struct Class {
Class(bool verbose=true) : verbose_(verbose) {}
// Then the instance variables are set directly by the Module constructor
- std::string name; ///< Class name
- std::list constructors; ///< Class constructors
- std::list methods; ///< Class methods
- bool verbose_; ///< verbose flag
+ std::string name; ///< Class name
+ std::vector constructors; ///< Class constructors
+ std::vector methods; ///< Class methods
+ std::vector static_methods; ///< Static methods
+ std::vector namespaces; ///< Stack of namespaces
+ std::vector includes; ///< header include overrides
+ bool verbose_; ///< verbose flag
// And finally MATLAB code is emitted, methods below called by Module::matlab_code
- void matlab_proxy(const std::string& classFile); ///< emit proxy class
+ void matlab_proxy(const std::string& classFile) const; ///< emit proxy class
void matlab_constructors(const std::string& toolboxPath,
- const std::string& nameSpace); ///< emit constructor wrappers
+ const std::vector& using_namespaces) const; ///< emit constructor wrappers
void matlab_methods(const std::string& classPath,
- const std::string& nameSpace); ///< emit method wrappers
+ const std::vector& using_namespaces) const; ///< emit method wrappers
+ void matlab_static_methods(const std::string& classPath,
+ const std::vector& using_namespaces) const; ///< emit static method wrappers
void matlab_make_fragment(std::ofstream& ofs,
const std::string& toolboxPath,
- const std::string& mexFlags); ///< emit make fragment for global make script
+ const std::string& mexFlags) const; ///< emit make fragment for global make script
+ void makefile_fragment(std::ofstream& ofs) const; ///< emit makefile fragment
+ std::string qualifiedName(const std::string& delim = "") const; ///< creates a namespace-qualified name, optional delimiter
};
+} // \namespace wrap
+
diff --git a/wrap/Constructor.cpp b/wrap/Constructor.cpp
index 9caf4793f..a822f722f 100644
--- a/wrap/Constructor.cpp
+++ b/wrap/Constructor.cpp
@@ -23,15 +23,16 @@
#include "Constructor.h"
using namespace std;
+using namespace wrap;
/* ************************************************************************* */
-string Constructor::matlab_wrapper_name(const string& className) {
+string Constructor::matlab_wrapper_name(const string& className) const {
string str = "new_" + className + "_" + args.signature();
return str;
}
/* ************************************************************************* */
-void Constructor::matlab_proxy_fragment(ofstream& ofs, const string& className) {
+void Constructor::matlab_proxy_fragment(ofstream& ofs, const string& className) const {
ofs << " if nargin == " << args.size() << ", obj.self = "
<< matlab_wrapper_name(className) << "(";
bool first = true;
@@ -44,22 +45,22 @@ void Constructor::matlab_proxy_fragment(ofstream& ofs, const string& className)
}
/* ************************************************************************* */
-void Constructor::matlab_mfile(const string& toolboxPath, const string& className) {
+void Constructor::matlab_mfile(const string& toolboxPath, const string& qualifiedMatlabName) const {
- string name = matlab_wrapper_name(className);
+ string matlabName = matlab_wrapper_name(qualifiedMatlabName);
// open destination m-file
- string wrapperFile = toolboxPath + "/" + name + ".m";
+ string wrapperFile = toolboxPath + "/" + matlabName + ".m";
ofstream ofs(wrapperFile.c_str());
if(!ofs) throw CantOpenFile(wrapperFile);
if(verbose_) cerr << "generating " << wrapperFile << endl;
// generate code
- emit_header_comment(ofs, "%");
- ofs << "function result = " << name << "(obj";
+ generateHeaderComment(ofs, "%");
+ ofs << "function result = " << matlabName << "(obj";
if (args.size()) ofs << "," << args.names();
ofs << ")" << endl;
- ofs << " error('need to compile " << name << ".cpp');" << endl;
+ ofs << " error('need to compile " << matlabName << ".cpp');" << endl;
ofs << "end" << endl;
// close file
@@ -67,30 +68,29 @@ void Constructor::matlab_mfile(const string& toolboxPath, const string& classNam
}
/* ************************************************************************* */
-void Constructor::matlab_wrapper(const string& toolboxPath,
- const string& className,
- const string& nameSpace)
-{
-
- string name = matlab_wrapper_name(className);
+void Constructor::matlab_wrapper(const string& toolboxPath,
+ const string& cppClassName,
+ const string& matlabClassName,
+ const vector& using_namespaces, const vector& includes) const {
+ string matlabName = matlab_wrapper_name(matlabClassName);
// open destination wrapperFile
- string wrapperFile = toolboxPath + "/" + name + ".cpp";
+ string wrapperFile = toolboxPath + "/" + matlabName + ".cpp";
ofstream ofs(wrapperFile.c_str());
if(!ofs) throw CantOpenFile(wrapperFile);
if(verbose_) cerr << "generating " << wrapperFile << endl;
// generate code
- emit_header_comment(ofs, "//");
- ofs << "#include " << endl;
- ofs << "#include <" << className << ".h>" << endl;
- if (!nameSpace.empty()) ofs << "using namespace " << nameSpace << ";" << endl;
+ generateHeaderComment(ofs, "//");
+ generateIncludes(ofs, name, includes);
+ generateUsingNamespace(ofs, using_namespaces);
+
ofs << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])" << endl;
ofs << "{" << endl;
- ofs << " checkArguments(\"" << name << "\",nargout,nargin," << args.size() << ");" << endl;
+ ofs << " checkArguments(\"" << matlabName << "\",nargout,nargin," << args.size() << ");" << endl;
args.matlab_unwrap(ofs); // unwrap arguments
- ofs << " " << className << "* self = new " << className << "(" << args.names() << ");" << endl;
- ofs << " out[0] = wrap_constructed(self,\"" << className << "\");" << endl;
+ ofs << " " << cppClassName << "* self = new " << cppClassName << "(" << args.names() << ");" << endl; // need qualified name, delim: "::"
+ ofs << " out[0] = wrap_constructed(self,\"" << matlabClassName << "\");" << endl; // need matlab qualified name
ofs << "}" << endl;
// close file
diff --git a/wrap/Constructor.h b/wrap/Constructor.h
index 340ac0fd2..b9a44e2cc 100644
--- a/wrap/Constructor.h
+++ b/wrap/Constructor.h
@@ -18,10 +18,12 @@
#pragma once
#include
-#include
+#include
#include "Argument.h"
+namespace wrap {
+
// Constructor class
struct Constructor {
@@ -32,6 +34,7 @@ struct Constructor {
// Then the instance variables are set directly by the Module constructor
ArgumentList args;
+ std::string name;
bool verbose_;
// MATLAB code generation
@@ -39,17 +42,22 @@ struct Constructor {
// classFile is class proxy file, e.g., ../matlab/@Point2/Point2.m
/// wrapper name
- std::string matlab_wrapper_name(const std::string& className);
+ std::string matlab_wrapper_name(const std::string& className) const;
/// proxy class fragment
- void matlab_proxy_fragment(std::ofstream& ofs, const std::string& className);
+ void matlab_proxy_fragment(std::ofstream& ofs, const std::string& className) const;
/// m-file
void matlab_mfile(const std::string& toolboxPath,
- const std::string& className);
+ const std::string& qualifiedMatlabName) const;
- /// wrapper
+ /// cpp wrapper
void matlab_wrapper(const std::string& toolboxPath,
- const std::string& className, const std::string& nameSpace);
+ const std::string& cppClassName,
+ const std::string& matlabClassName,
+ const std::vector& using_namespaces,
+ const std::vector& includes) const;
};
+} // \namespace wrap
+
diff --git a/wrap/Makefile.am b/wrap/Makefile.am
index 895830537..8b3e4f493 100644
--- a/wrap/Makefile.am
+++ b/wrap/Makefile.am
@@ -9,15 +9,22 @@ AM_DEFAULT_SOURCE_EXT = .cpp
headers =
sources =
-check_PROGRAMS =
+check_PROGRAMS =
+noinst_PROGRAMS =
+wrap_PROGRAMS =
+wrapdir = $(pkgincludedir)/wrap
# disable all of matlab toolbox build by default
if ENABLE_BUILD_TOOLBOX
# Build a library from the core sources
-sources += utilities.cpp Argument.cpp Constructor.cpp Method.cpp Class.cpp Module.cpp
-check_PROGRAMS += tests/testSpirit tests/testWrap
-noinst_PROGRAMS = wrap
+sources += utilities.cpp Argument.cpp ReturnValue.cpp Constructor.cpp Method.cpp StaticMethod.cpp Class.cpp Module.cpp
+check_PROGRAMS += tests/testSpirit tests/testWrap
+if ENABLE_INSTALL_WRAP
+wrap_PROGRAMS += wrap
+else
+noinst_PROGRAMS += wrap
+endif
#----------------------------------------------------------------------------------------------------
# Create a libtool library that is not installed
@@ -25,7 +32,6 @@ noinst_PROGRAMS = wrap
#----------------------------------------------------------------------------------------------------
# Only install the header necessary for wrap interfaces to build with mex
headers += matlab.h
-wrapdir = $(pkgincludedir)/wrap
wrap_HEADERS = $(headers)
noinst_LTLIBRARIES = libwrap.la
libwrap_la_SOURCES = $(sources)
@@ -46,20 +52,79 @@ LDADD = libwrap.la ../CppUnitLite/libCppUnitLite.a
# rule to run executable with valgrind
%.valgrind: % $(LDADD)
valgrind ./$^
-
+
# generate local toolbox dir
interfacePath = $(top_srcdir)
moduleName = gtsam
toolboxpath = ../toolbox
-nameSpace = "gtsam"
-mexFlags = "${BOOST_CPPFLAGS} -DUNSAFE_WRAP -I${prefix}/include -I${prefix}/include/gtsam -I${prefix}/include/gtsam/base -I${prefix}/include/gtsam/geometry -I${prefix}/include/gtsam/linear -I${prefix}/include/gtsam/nonlinear -I${prefix}/include/gtsam/slam -L${exec_prefix}/lib -lgtsam"
-all:
- ./wrap ${interfacePath} ${moduleName} ${toolboxpath} ${nameSpace} ${mexFlags}
-
-# install the headers and matlab toolbox
-install-exec-hook: all
- install -d ${toolbox}/gtsam && \
- cp -rf ../toolbox/* ${toolbox}/gtsam
+
+# Set flags to pass to mex
+mexFlags =
+if ENABLE_UNSAFE_WRAP
+mexFlags += "${BOOST_CPPFLAGS} -DUNSAFE_WRAP -I${prefix}/include -I${prefix}/include/gtsam -I${prefix}/include/gtsam/base -I${prefix}/include/gtsam/geometry -I${prefix}/include/gtsam/linear -I${prefix}/include/gtsam/nonlinear -I${prefix}/include/gtsam/slam -L${exec_prefix}/lib -lgtsam"
+else
+mexFlags += "${BOOST_CPPFLAGS} -I${prefix}/include -I${prefix}/include/gtsam -I${prefix}/include/gtsam/base -I${prefix}/include/gtsam/geometry -I${prefix}/include/gtsam/linear -I${prefix}/include/gtsam/nonlinear -I${prefix}/include/gtsam/slam -L${exec_prefix}/lib -lgtsam"
+endif
+
+# Find the extension for mex binaries
+# this should be done with mexext with matlab
+mexextension =
+if LINUX
+if IS_64BIT
+mexextension += mexa64
+else
+mexextension += mexglx
+endif
+else # Linux
+if DARWIN
+mexextension += mexmaci64
+else
+mexextension += mex_bin
+endif
+endif # Linux
+
+all: generate_toolbox
+
+generate_toolbox: $(top_srcdir)/gtsam.h
+ ./wrap ${mexextension} ${interfacePath} ${moduleName} ${toolboxpath} ${mexFlags}
+
+source_mode = -m 644
+
+wrap-install-matlab-toolbox: generate_toolbox
+ install -d ${toolbox}/gtsam
+ install ${source_mode} -c ../toolbox/*.m ${toolbox}/gtsam
+ install ${source_mode} -c ../toolbox/*.cpp ${toolbox}/gtsam
+ install ${source_mode} -c ../toolbox/Makefile ${toolbox}/gtsam
+ cp -ru ../toolbox/@* ${toolbox}/gtsam
+
+wrap-install-bin: wrap
+ install -d ${wrap}
+ install -c ./wrap ${wrap}
+
+wrap-install-matlab-tests:
+ install -d ${toolbox}/gtsam/tests
+ install ${source_mode} -c ../../tests/matlab/*.m ${toolbox}/gtsam/tests
+
+wrap-install-matlab-examples:
+ install -d ${toolbox}/gtsam/examples
+ install ${source_mode} -c ../../examples/matlab/*.m ${toolbox}/gtsam/examples
+
+wrap_install_targets =
+wrap_install_targets += wrap-install-matlab-toolbox
+
+if ENABLE_INSTALL_WRAP
+wrap_install_targets += wrap-install-bin
+endif
+
+if ENABLE_INSTALL_MATLAB_TESTS
+wrap_install_targets += wrap-install-matlab-tests
+endif
+
+if ENABLE_INSTALL_MATLAB_EXAMPLES
+wrap_install_targets += wrap-install-matlab-examples
+endif
+
+install-exec-hook: ${wrap_install_targets}
# clean local toolbox dir
clean:
diff --git a/wrap/Method.cpp b/wrap/Method.cpp
index 1e0cd134e..0d9ba98e2 100644
--- a/wrap/Method.cpp
+++ b/wrap/Method.cpp
@@ -23,44 +23,24 @@
#include "utilities.h"
using namespace std;
+using namespace wrap;
/* ************************************************************************* */
-// auxiliary function to wrap an argument into a shared_ptr template
-/* ************************************************************************* */
-string maybe_shared_ptr(bool add, const string& type) {
- string str = add? "shared_ptr<" : "";
- str += type;
- if (add) str += ">";
- return str;
-}
-
-/* ************************************************************************* */
-string Method::return_type(bool add_ptr, pairing p) {
- if (p==pair && returns_pair_) {
- string str = "pair< " +
- maybe_shared_ptr(add_ptr && returns_ptr_, returns_) + ", " +
- maybe_shared_ptr(add_ptr && returns_ptr_, returns2_) + " >";
- return str;
- } else
- return maybe_shared_ptr(add_ptr && returns_ptr_, (p==arg2)? returns2_ : returns_);
-}
-
-/* ************************************************************************* */
-void Method::matlab_mfile(const string& classPath) {
+void Method::matlab_mfile(const string& classPath) const {
// open destination m-file
- string wrapperFile = classPath + "/" + name_ + ".m";
+ string wrapperFile = classPath + "/" + name + ".m";
ofstream ofs(wrapperFile.c_str());
if(!ofs) throw CantOpenFile(wrapperFile);
if(verbose_) cerr << "generating " << wrapperFile << endl;
// generate code
- string returnType = returns_pair_? "[first,second]" : "result";
- ofs << "function " << returnType << " = " << name_ << "(obj";
- if (args_.size()) ofs << "," << args_.names();
+ string returnType = returnVal.matlab_returnType();
+ ofs << "function " << returnType << " = " << name << "(obj";
+ if (args.size()) ofs << "," << args.names();
ofs << ")" << endl;
- ofs << "% usage: obj." << name_ << "(" << args_.names() << ")" << endl;
- ofs << " error('need to compile " << name_ << ".cpp');" << endl;
+ ofs << "% usage: obj." << name << "(" << args.names() << ")" << endl;
+ ofs << " error('need to compile " << name << ".cpp');" << endl;
ofs << "end" << endl;
// close file
@@ -70,10 +50,11 @@ void Method::matlab_mfile(const string& classPath) {
/* ************************************************************************* */
void Method::matlab_wrapper(const string& classPath,
const string& className,
- const string& nameSpace)
-{
+ const string& cppClassName,
+ const string& matlabClassName,
+ const vector& using_namespaces, const std::vector& includes) const {
// open destination wrapperFile
- string wrapperFile = classPath + "/" + name_ + ".cpp";
+ string wrapperFile = classPath + "/" + name + ".cpp";
ofstream ofs(wrapperFile.c_str());
if(!ofs) throw CantOpenFile(wrapperFile);
if(verbose_) cerr << "generating " << wrapperFile << endl;
@@ -81,10 +62,9 @@ void Method::matlab_wrapper(const string& classPath,
// generate code
// header
- emit_header_comment(ofs, "//");
- ofs << "#include \n";
- ofs << "#include <" << className << ".h>\n";
- if (!nameSpace.empty()) ofs << "using namespace " << nameSpace << ";" << endl;
+ generateHeaderComment(ofs, "//");
+ generateIncludes(ofs, className, includes);
+ generateUsingNamespace(ofs, using_namespaces);
// call
ofs << "void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n";
@@ -94,39 +74,26 @@ void Method::matlab_wrapper(const string& classPath,
// check arguments
// extra argument obj -> nargin-1 is passed !
// example: checkArguments("equals",nargout,nargin-1,2);
- ofs << " checkArguments(\"" << name_ << "\",nargout,nargin-1," << args_.size() << ");\n";
+ ofs << " checkArguments(\"" << name << "\",nargout,nargin-1," << args.size() << ");\n";
// get class pointer
// example: shared_ptr = unwrap_shared_ptr< Test >(in[0], "Test");
- ofs << " shared_ptr<" << className << "> self = unwrap_shared_ptr< " << className
- << " >(in[0],\"" << className << "\");" << endl;
+ ofs << " shared_ptr<" << cppClassName << "> self = unwrap_shared_ptr< " << cppClassName
+ << " >(in[0],\"" << matlabClassName << "\");" << endl;
// unwrap arguments, see Argument.cpp
- args_.matlab_unwrap(ofs,1);
+ args.matlab_unwrap(ofs,1);
// call method
// example: bool result = self->return_field(t);
ofs << " ";
- if (returns_!="void")
- ofs << return_type(true,pair) << " result = ";
- ofs << "self->" << name_ << "(" << args_.names() << ");\n";
+ if (returnVal.type1!="void")
+ ofs << returnVal.return_type(true,ReturnValue::pair) << " result = ";
+ ofs << "self->" << name << "(" << args.names() << ");\n";
// wrap result
// example: out[0]=wrap(result);
- if (returns_pair_) {
- if (returns_ptr_)
- ofs << " out[0] = wrap_shared_ptr(result.first,\"" << returns_ << "\");\n";
- else
- ofs << " out[0] = wrap< " << return_type(true,arg1) << " >(result.first);\n";
- if (returns_ptr2_)
- ofs << " out[1] = wrap_shared_ptr(result.second,\"" << returns2_ << "\");\n";
- else
- ofs << " out[1] = wrap< " << return_type(true,arg2) << " >(result.second);\n";
- }
- else if (returns_ptr_)
- ofs << " out[0] = wrap_shared_ptr(result,\"" << returns_ << "\");\n";
- else if (returns_!="void")
- ofs << " out[0] = wrap< " << return_type(true,arg1) << " >(result);\n";
+ returnVal.wrap_result(ofs);
// finish
ofs << "}\n";
diff --git a/wrap/Method.h b/wrap/Method.h
index 56679e67b..bcfac82e3 100644
--- a/wrap/Method.h
+++ b/wrap/Method.h
@@ -21,33 +21,35 @@
#include
#include "Argument.h"
+#include "ReturnValue.h"
+
+namespace wrap {
/// Method class
struct Method {
/// Constructor creates empty object
Method(bool verbose = true) :
- returns_ptr_(false), returns_ptr2_(false), returns_pair_(false), verbose_(
- verbose) {
- }
+ verbose_(verbose) {}
// Then the instance variables are set directly by the Module constructor
- bool is_const_;
- ArgumentList args_;
- std::string returns_, returns2_, name_;
- bool returns_ptr_, returns_ptr2_, returns_pair_;
bool verbose_;
-
- enum pairing {
- arg1, arg2, pair
- };
- std::string return_type(bool add_ptr, pairing p);
+ bool is_const_;
+ std::string name;
+ ArgumentList args;
+ ReturnValue returnVal;
// MATLAB code generation
// classPath is class directory, e.g., ../matlab/@Point2
- void matlab_mfile(const std::string& classPath); ///< m-file
+ void matlab_mfile(const std::string& classPath) const; ///< m-file
void matlab_wrapper(const std::string& classPath,
- const std::string& className, const std::string& nameSpace); ///< wrapper
+ const std::string& className,
+ const std::string& cppClassName,
+ const std::string& matlabClassname,
+ const std::vector& using_namespaces,
+ const std::vector& includes) const; ///< cpp wrapper
};
+} // \namespace wrap
+
diff --git a/wrap/Module.cpp b/wrap/Module.cpp
index 7e35b0d2b..120b89f10 100644
--- a/wrap/Module.cpp
+++ b/wrap/Module.cpp
@@ -16,15 +16,19 @@
#include "Module.h"
#include "utilities.h"
+#include "pop_actor.h"
//#define BOOST_SPIRIT_DEBUG
#include
+#include