From 075293cf83d91e0a4391107c588765fdafdddfea Mon Sep 17 00:00:00 2001 From: Milo Knowles Date: Sat, 20 Mar 2021 17:44:03 -0400 Subject: [PATCH 01/21] Three examples of failing PartialPriorFactor Jacobians --- .../slam/tests/testPartialPriorFactor.cpp | 114 ++++++++++++++++++ 1 file changed, 114 insertions(+) create mode 100644 gtsam_unstable/slam/tests/testPartialPriorFactor.cpp diff --git a/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp b/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp new file mode 100644 index 000000000..6cc70ef46 --- /dev/null +++ b/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp @@ -0,0 +1,114 @@ +/* ---------------------------------------------------------------------------- + + * 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 + + * -------------------------------------------------------------------------- */ + +#include +#include +#include +#include +#include +#include + +using namespace std; +using namespace gtsam; + + +// Pose representation is [ Rx Ry Rz Tx Ty Tz ]. +static const int kIndexRx = 0; +static const int kIndexRy = 1; +static const int kIndexRz = 2; +static const int kIndexTx = 3; +static const int kIndexTy = 4; +static const int kIndexTz = 5; + + +typedef PartialPriorFactor TestPartialPriorFactor; + +/// traits +namespace gtsam { +template<> +struct traits : public Testable { +}; +} + +/* ************************************************************************* */ +TEST(PartialPriorFactor, JacobianPartialTranslation) { + Key poseKey(1); + Pose3 measurement(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); + SharedNoiseModel model = noiseModel::Isotropic::Sigma(1, 0.25); + + TestPartialPriorFactor factor(poseKey, kIndexTy, measurement.translation().x(), model); + + // Create a linearization point at the zero-error point + Pose3 pose(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); + + // Calculate numerical derivatives. + Matrix expectedH1 = numericalDerivative11( + boost::bind(&TestPartialPriorFactor::evaluateError, &factor, _1, boost::none), pose); + + // Use the factor to calculate the derivative. + Matrix actualH1; + factor.evaluateError(pose, actualH1); + + // Verify we get the expected error. + CHECK(assert_equal(expectedH1, actualH1, 1e-5)); +} + +/* ************************************************************************* */ +TEST(PartialPriorFactor, JacobianFullTranslation) { + Key poseKey(1); + Pose3 measurement(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); + SharedNoiseModel model = noiseModel::Isotropic::Sigma(3, 0.25); + + std::vector translationIndices = { kIndexTx, kIndexTy, kIndexTz }; + TestPartialPriorFactor factor(poseKey, translationIndices, measurement.translation(), model); + + // Create a linearization point at the zero-error point + Pose3 pose(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); + + // Calculate numerical derivatives. + Matrix expectedH1 = numericalDerivative11( + boost::bind(&TestPartialPriorFactor::evaluateError, &factor, _1, boost::none), pose); + + // Use the factor to calculate the derivative. + Matrix actualH1; + factor.evaluateError(pose, actualH1); + + // Verify we get the expected error. + CHECK(assert_equal(expectedH1, actualH1, 1e-5)); +} + +/* ************************************************************************* */ +TEST(PartialPriorFactor, JacobianFullRotation) { + Key poseKey(1); + Pose3 measurement(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); + SharedNoiseModel model = noiseModel::Isotropic::Sigma(3, 0.25); + + std::vector rotationIndices = { kIndexRx, kIndexRy, kIndexRz }; + TestPartialPriorFactor factor(poseKey, rotationIndices, Rot3::Logmap(measurement.rotation()), model); + + // Create a linearization point at the zero-error point + Pose3 pose(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); + + // Calculate numerical derivatives. + Matrix expectedH1 = numericalDerivative11( + boost::bind(&TestPartialPriorFactor::evaluateError, &factor, _1, boost::none), pose); + + // Use the factor to calculate the derivative. + Matrix actualH1; + factor.evaluateError(pose, actualH1); + + // Verify we get the expected error. + CHECK(assert_equal(expectedH1, actualH1, 1e-5)); +} + +/* ************************************************************************* */ +int main() { TestResult tr; return TestRegistry::runAllTests(tr); } +/* ************************************************************************* */ From e6b7d9f13320ffc49372d50ba17f7fa77d1f2ce7 Mon Sep 17 00:00:00 2001 From: Milo Knowles Date: Sat, 20 Mar 2021 17:57:10 -0400 Subject: [PATCH 02/21] Add successful unit test for identity pose --- .../slam/tests/testPartialPriorFactor.cpp | 26 +++++++++++++++++++ 1 file changed, 26 insertions(+) diff --git a/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp b/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp index 6cc70ef46..8a77bc5b9 100644 --- a/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp +++ b/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp @@ -38,6 +38,32 @@ struct traits : public Testable }; } + +/* ************************************************************************* */ +TEST(PartialPriorFactor, JacobianAtIdentity) +{ + Key poseKey(1); + Pose3 measurement = Pose3::identity(); + SharedNoiseModel model = noiseModel::Isotropic::Sigma(1, 0.25); + + TestPartialPriorFactor factor(poseKey, kIndexTy, measurement.translation().x(), model); + + // Create a linearization point at the zero-error point + Pose3 pose = Pose3::identity(); + + // Calculate numerical derivatives. + Matrix expectedH1 = numericalDerivative11( + boost::bind(&TestPartialPriorFactor::evaluateError, &factor, _1, boost::none), pose); + + // Use the factor to calculate the derivative. + Matrix actualH1; + factor.evaluateError(pose, actualH1); + + // Verify we get the expected error. + CHECK(assert_equal(expectedH1, actualH1, 1e-5)); +} + + /* ************************************************************************* */ TEST(PartialPriorFactor, JacobianPartialTranslation) { Key poseKey(1); From 593e6e975d6fd6e1f7bfc9a19c1d4c84568a19ad Mon Sep 17 00:00:00 2001 From: Milo Knowles Date: Sun, 21 Mar 2021 17:10:00 -0400 Subject: [PATCH 03/21] Correct Jacobian in PartialPriorFactor, modify derived factors for compatibility --- gtsam_unstable/dynamics/DynamicsPriors.h | 32 ++--------- gtsam_unstable/slam/PartialPriorFactor.h | 68 ++++++++++++------------ 2 files changed, 38 insertions(+), 62 deletions(-) diff --git a/gtsam_unstable/dynamics/DynamicsPriors.h b/gtsam_unstable/dynamics/DynamicsPriors.h index 1e768ef2a..e286b5fdc 100644 --- a/gtsam_unstable/dynamics/DynamicsPriors.h +++ b/gtsam_unstable/dynamics/DynamicsPriors.h @@ -50,16 +50,7 @@ struct DRollPrior : public gtsam::PartialPriorFactor { struct VelocityPrior : public gtsam::PartialPriorFactor { typedef gtsam::PartialPriorFactor Base; VelocityPrior(Key key, const gtsam::Vector& vel, const gtsam::SharedNoiseModel& model) - : Base(key, model) { - this->prior_ = vel; - assert(vel.size() == 3); - this->mask_.resize(3); - this->mask_[0] = 6; - this->mask_[1] = 7; - this->mask_[2] = 8; - this->H_ = Matrix::Zero(3, 9); - this->fillH(); - } + : Base(key, {6, 7, 8}, vel, model) {} }; /** @@ -74,31 +65,14 @@ struct DGroundConstraint : public gtsam::PartialPriorFactor { * Primary constructor allows for variable height of the "floor" */ DGroundConstraint(Key key, double height, const gtsam::SharedNoiseModel& model) - : Base(key, model) { - this->prior_ = Vector::Unit(4,0)*height; // [z, vz, roll, pitch] - this->mask_.resize(4); - this->mask_[0] = 5; // z = height - this->mask_[1] = 8; // vz - this->mask_[2] = 0; // roll - this->mask_[3] = 1; // pitch - this->H_ = Matrix::Zero(3, 9); - this->fillH(); - } + : Base(key, {5, 8, 0, 1}, Vector::Unit(4,0)*height, model) {} /** * Fully specify vector - use only for debugging */ DGroundConstraint(Key key, const Vector& constraint, const gtsam::SharedNoiseModel& model) - : Base(key, model) { + : Base(key, {5, 8, 0, 1}, constraint, model) { assert(constraint.size() == 4); - this->prior_ = constraint; // [z, vz, roll, pitch] - this->mask_.resize(4); - this->mask_[0] = 5; // z = height - this->mask_[1] = 8; // vz - this->mask_[2] = 0; // roll - this->mask_[3] = 1; // pitch - this->H_ = Matrix::Zero(3, 9); - this->fillH(); } }; diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index c1984992b..96b0d3147 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -17,6 +17,8 @@ #pragma once +#include + #include #include @@ -43,16 +45,14 @@ namespace gtsam { typedef VALUE T; protected: - // Concept checks on the variable type - currently requires Lie GTSAM_CONCEPT_LIE_TYPE(VALUE) typedef NoiseModelFactor1 Base; typedef PartialPriorFactor This; - Vector prior_; ///< measurement on tangent space parameters, in compressed form - std::vector mask_; ///< indices of values to constrain in compressed prior vector - Matrix H_; ///< Constant Jacobian - computed at creation + Vector prior_; ///< Measurement on tangent space parameters, in compressed form. + std::vector mask_; ///< Indices of the measured tangent space parameters. /** default constructor - only use for serialization */ PartialPriorFactor() {} @@ -68,20 +68,22 @@ namespace gtsam { ~PartialPriorFactor() override {} - /** Single Element Constructor: acts on a single parameter specified by idx */ + /** Single Element Constructor: Prior on a single parameter at index 'idx' in the tangent vector.*/ PartialPriorFactor(Key key, size_t idx, double prior, const SharedNoiseModel& model) : - Base(model, key), prior_((Vector(1) << prior).finished()), mask_(1, idx), H_(Matrix::Zero(1, T::dimension)) { + Base(model, key), + prior_((Vector(1) << prior).finished()), + mask_(1, idx) { assert(model->dim() == 1); - this->fillH(); } - /** Indices Constructor: specify the mask with a set of indices */ - PartialPriorFactor(Key key, const std::vector& mask, const Vector& prior, + /** Indices Constructor: Specify the relevant measured indices in the tangent vector.*/ + PartialPriorFactor(Key key, const std::vector& indices, const Vector& prior, const SharedNoiseModel& model) : - Base(model, key), prior_(prior), mask_(mask), H_(Matrix::Zero(mask.size(), T::dimension)) { - assert((size_t)prior_.size() == mask.size()); - assert(model->dim() == (size_t) prior.size()); - this->fillH(); + Base(model, key), + prior_(prior), + mask_(indices) { + assert((size_t)prior_.size() == mask_.size()); + assert(model->dim() == (size_t)prior.size()); } /// @return a deep copy of this factor @@ -107,30 +109,30 @@ namespace gtsam { /** implement functions needed to derive from Factor */ - /** vector of errors */ + /** Returns a vector of errors for the measured tangent parameters. */ Vector evaluateError(const T& p, boost::optional H = boost::none) const override { - if (H) (*H) = H_; - // FIXME: this was originally the generic retraction - may not produce same results - Vector full_logmap = T::Logmap(p); -// Vector full_logmap = T::identity().localCoordinates(p); // Alternate implementation - Vector masked_logmap = Vector::Zero(this->dim()); - for (size_t i=0; i& mask() const { return mask_; } - const Matrix& H() const { return H_; } - - protected: - - /** Constructs the jacobian matrix in place */ - void fillH() { - for (size_t i=0; i& mask() const { return mask_; } private: /** Serialization function */ @@ -141,7 +143,7 @@ namespace gtsam { boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(prior_); ar & BOOST_SERIALIZATION_NVP(mask_); - ar & BOOST_SERIALIZATION_NVP(H_); + // ar & BOOST_SERIALIZATION_NVP(H_); } }; // \class PartialPriorFactor From 43c9f2ba268c964571b5a96320442c14688a9195 Mon Sep 17 00:00:00 2001 From: Milo Knowles Date: Sun, 21 Mar 2021 17:20:43 -0400 Subject: [PATCH 04/21] Change mask to indices and update factor docstring --- gtsam_unstable/slam/PartialPriorFactor.h | 34 +++++++++++------------- 1 file changed, 16 insertions(+), 18 deletions(-) diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index 96b0d3147..da6e0d535 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -31,11 +31,9 @@ namespace gtsam { * * The prior vector used in this factor is stored in compressed form, such that * it only contains values for measurements that are to be compared, and they are in - * the same order as VALUE::Logmap(). The mask will determine which components to extract - * in the error function. + * the same order as VALUE::Logmap(). The provided indices will determine which components to + * extract in the error function. * - * For practical use, it would be good to subclass this factor and have the class type - * construct the mask. * @tparam VALUE is the type of variable the prior effects */ template @@ -51,8 +49,8 @@ namespace gtsam { typedef NoiseModelFactor1 Base; typedef PartialPriorFactor This; - Vector prior_; ///< Measurement on tangent space parameters, in compressed form. - std::vector mask_; ///< Indices of the measured tangent space parameters. + Vector prior_; ///< Measurement on tangent space parameters, in compressed form. + std::vector indices_; ///< Indices of the measured tangent space parameters. /** default constructor - only use for serialization */ PartialPriorFactor() {} @@ -72,7 +70,7 @@ namespace gtsam { PartialPriorFactor(Key key, size_t idx, double prior, const SharedNoiseModel& model) : Base(model, key), prior_((Vector(1) << prior).finished()), - mask_(1, idx) { + indices_(1, idx) { assert(model->dim() == 1); } @@ -81,8 +79,8 @@ namespace gtsam { const SharedNoiseModel& model) : Base(model, key), prior_(prior), - mask_(indices) { - assert((size_t)prior_.size() == mask_.size()); + indices_(indices) { + assert((size_t)prior_.size() == indices_.size()); assert(model->dim() == (size_t)prior.size()); } @@ -104,7 +102,7 @@ namespace gtsam { const This *e = dynamic_cast (&expected); return e != nullptr && Base::equals(*e, tol) && gtsam::equal_with_abs_tol(this->prior_, e->prior_, tol) && - this->mask_ == e->mask_; + this->indices_ == e->indices_; } /** implement functions needed to derive from Factor */ @@ -114,17 +112,17 @@ namespace gtsam { if (H) { Matrix H_logmap; T::Logmap(p, H_logmap); - (*H) = Matrix::Zero(mask_.size(), T::dimension); - for (size_t i = 0; i < mask_.size(); ++i) { - (*H).row(i) = H_logmap.row(mask_.at(i)); + (*H) = Matrix::Zero(indices_.size(), T::dimension); + for (size_t i = 0; i < indices_.size(); ++i) { + (*H).row(i) = H_logmap.row(indices_.at(i)); } } // FIXME: this was originally the generic retraction - may not produce same results. - // Compute the tangent vector representation of T, and optionally get the Jacobian. + // Compute the tangent vector representation of T. const Vector& full_logmap = T::Logmap(p); Vector partial_logmap = Vector::Zero(T::dimension); - for (size_t i = 0; i < mask_.size(); ++i) { - partial_logmap(i) = full_logmap(mask_.at(i)); + for (size_t i = 0; i < indices_.size(); ++i) { + partial_logmap(i) = full_logmap(indices_.at(i)); } return partial_logmap - prior_; @@ -132,7 +130,7 @@ namespace gtsam { // access const Vector& prior() const { return prior_; } - const std::vector& mask() const { return mask_; } + const std::vector& indices() const { return indices_; } private: /** Serialization function */ @@ -142,7 +140,7 @@ namespace gtsam { ar & boost::serialization::make_nvp("NoiseModelFactor1", boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(prior_); - ar & BOOST_SERIALIZATION_NVP(mask_); + ar & BOOST_SERIALIZATION_NVP(indices_); // ar & BOOST_SERIALIZATION_NVP(H_); } }; // \class PartialPriorFactor From 4b29c0370dacab9fc8cafe12e586a0f7d8715b5f Mon Sep 17 00:00:00 2001 From: Milo Knowles Date: Sun, 21 Mar 2021 20:46:26 -0400 Subject: [PATCH 05/21] Prefer localCoordinates over logmap --- gtsam_unstable/slam/PartialPriorFactor.h | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index da6e0d535..bc28a6830 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -111,15 +111,14 @@ namespace gtsam { Vector evaluateError(const T& p, boost::optional H = boost::none) const override { if (H) { Matrix H_logmap; - T::Logmap(p, H_logmap); + p.localCoordinates(T::identity(), H_logmap); (*H) = Matrix::Zero(indices_.size(), T::dimension); for (size_t i = 0; i < indices_.size(); ++i) { (*H).row(i) = H_logmap.row(indices_.at(i)); } } - // FIXME: this was originally the generic retraction - may not produce same results. - // Compute the tangent vector representation of T. - const Vector& full_logmap = T::Logmap(p); + // Compute the tangent vector representation of T and select relevant parameters. + const Vector& full_logmap = p.localCoordinates(T::identity()); Vector partial_logmap = Vector::Zero(T::dimension); for (size_t i = 0; i < indices_.size(); ++i) { partial_logmap(i) = full_logmap(indices_.at(i)); From 73b04367556b2aaff821605e1104421c24959e63 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Mar 2021 00:33:25 -0400 Subject: [PATCH 06/21] fix numpy deprecation warnings --- python/gtsam/examples/ImuFactorISAM2Example.py | 2 +- python/gtsam/examples/PlanarManipulatorExample.py | 12 ++++++------ python/gtsam/examples/Pose2SLAMExample.py | 2 +- python/gtsam/examples/Pose2SLAMExample_g2o.py | 2 +- python/gtsam/examples/Pose3SLAMExample_g2o.py | 2 +- python/gtsam/examples/PreintegrationExample.py | 6 +++--- python/gtsam/tests/test_SO4.py | 4 ++-- python/gtsam/tests/test_SOn.py | 4 ++-- 8 files changed, 17 insertions(+), 17 deletions(-) diff --git a/python/gtsam/examples/ImuFactorISAM2Example.py b/python/gtsam/examples/ImuFactorISAM2Example.py index bb90b95bf..a350011de 100644 --- a/python/gtsam/examples/ImuFactorISAM2Example.py +++ b/python/gtsam/examples/ImuFactorISAM2Example.py @@ -24,7 +24,7 @@ from gtsam.utils import plot def vector3(x, y, z): """Create 3d double numpy array.""" - return np.array([x, y, z], dtype=np.float) + return np.array([x, y, z], dtype=float) g = 9.81 diff --git a/python/gtsam/examples/PlanarManipulatorExample.py b/python/gtsam/examples/PlanarManipulatorExample.py index 9af4f7fcc..96cb3362f 100644 --- a/python/gtsam/examples/PlanarManipulatorExample.py +++ b/python/gtsam/examples/PlanarManipulatorExample.py @@ -29,7 +29,7 @@ from gtsam.utils.test_case import GtsamTestCase def vector3(x, y, z): """Create 3D double numpy array.""" - return np.array([x, y, z], dtype=np.float) + return np.array([x, y, z], dtype=float) def compose(*poses): @@ -94,7 +94,7 @@ class ThreeLinkArm(object): [-self.L1*math.sin(q[0]) - self.L2*math.sin(a)-self.L3*math.sin(b), -self.L1*math.sin(a)-self.L3*math.sin(b), - self.L3*math.sin(b)], - [1, 1, 1]], np.float) + [1, 1, 1]], float) def poe(self, q): """ Forward kinematics. @@ -230,12 +230,12 @@ class TestPose2SLAMExample(GtsamTestCase): def test_jacobian(self): """Test Jacobian calculation.""" # at rest - expected = np.array([[-9.5, -6, -2.5], [0, 0, 0], [1, 1, 1]], np.float) + expected = np.array([[-9.5, -6, -2.5], [0, 0, 0], [1, 1, 1]], float) J = self.arm.jacobian(Q0) np.testing.assert_array_almost_equal(J, expected) # at -90, 90, 0 - expected = np.array([[-6, -6, -2.5], [3.5, 0, 0], [1, 1, 1]], np.float) + expected = np.array([[-6, -6, -2.5], [3.5, 0, 0], [1, 1, 1]], float) J = self.arm.jacobian(Q2) np.testing.assert_array_almost_equal(J, expected) @@ -280,13 +280,13 @@ class TestPose2SLAMExample(GtsamTestCase): def test_manipulator_jacobian(self): """Test Jacobian calculation.""" # at rest - expected = np.array([[0, 3.5, 7], [0, 0, 0], [1, 1, 1]], np.float) + expected = np.array([[0, 3.5, 7], [0, 0, 0], [1, 1, 1]], float) J = self.arm.manipulator_jacobian(Q0) np.testing.assert_array_almost_equal(J, expected) # at -90, 90, 0 expected = np.array( - [[0, 0, 3.5], [0, -3.5, -3.5], [1, 1, 1]], np.float) + [[0, 0, 3.5], [0, -3.5, -3.5], [1, 1, 1]], float) J = self.arm.manipulator_jacobian(Q2) np.testing.assert_array_almost_equal(J, expected) diff --git a/python/gtsam/examples/Pose2SLAMExample.py b/python/gtsam/examples/Pose2SLAMExample.py index 2569f0953..2ec190d73 100644 --- a/python/gtsam/examples/Pose2SLAMExample.py +++ b/python/gtsam/examples/Pose2SLAMExample.py @@ -25,7 +25,7 @@ import gtsam.utils.plot as gtsam_plot def vector3(x, y, z): """Create 3d double numpy array.""" - return np.array([x, y, z], dtype=np.float) + return np.array([x, y, z], dtype=float) # Create noise models PRIOR_NOISE = gtsam.noiseModel.Diagonal.Sigmas(vector3(0.3, 0.3, 0.1)) diff --git a/python/gtsam/examples/Pose2SLAMExample_g2o.py b/python/gtsam/examples/Pose2SLAMExample_g2o.py index b2ba9c5bc..97fb46c5f 100644 --- a/python/gtsam/examples/Pose2SLAMExample_g2o.py +++ b/python/gtsam/examples/Pose2SLAMExample_g2o.py @@ -23,7 +23,7 @@ from gtsam.utils import plot def vector3(x, y, z): """Create 3d double numpy array.""" - return np.array([x, y, z], dtype=np.float) + return np.array([x, y, z], dtype=float) parser = argparse.ArgumentParser( diff --git a/python/gtsam/examples/Pose3SLAMExample_g2o.py b/python/gtsam/examples/Pose3SLAMExample_g2o.py index 82b3bda98..501a75dc1 100644 --- a/python/gtsam/examples/Pose3SLAMExample_g2o.py +++ b/python/gtsam/examples/Pose3SLAMExample_g2o.py @@ -19,7 +19,7 @@ from gtsam.utils import plot def vector6(x, y, z, a, b, c): """Create 6d double numpy array.""" - return np.array([x, y, z, a, b, c], dtype=np.float) + return np.array([x, y, z, a, b, c], dtype=float) parser = argparse.ArgumentParser( diff --git a/python/gtsam/examples/PreintegrationExample.py b/python/gtsam/examples/PreintegrationExample.py index b54919bec..458248c30 100644 --- a/python/gtsam/examples/PreintegrationExample.py +++ b/python/gtsam/examples/PreintegrationExample.py @@ -29,11 +29,11 @@ class PreintegrationExample(object): kGyroSigma = math.radians(0.5) / 60 # 0.5 degree ARW kAccelSigma = 0.1 / 60 # 10 cm VRW params.setGyroscopeCovariance( - kGyroSigma ** 2 * np.identity(3, np.float)) + kGyroSigma ** 2 * np.identity(3, float)) params.setAccelerometerCovariance( - kAccelSigma ** 2 * np.identity(3, np.float)) + kAccelSigma ** 2 * np.identity(3, float)) params.setIntegrationCovariance( - 0.0000001 ** 2 * np.identity(3, np.float)) + 0.0000001 ** 2 * np.identity(3, float)) return params def __init__(self, twist=None, bias=None, dt=1e-2): diff --git a/python/gtsam/tests/test_SO4.py b/python/gtsam/tests/test_SO4.py index 648bd1710..226913de8 100644 --- a/python/gtsam/tests/test_SO4.py +++ b/python/gtsam/tests/test_SO4.py @@ -32,13 +32,13 @@ class TestSO4(unittest.TestCase): def test_retract(self): """Test retraction to manifold.""" - v = np.zeros((6,), np.float) + v = np.zeros((6,), float) actual = I4.retract(v) self.assertTrue(actual.equals(I4, 1e-9)) def test_local(self): """Check localCoordinates for trivial case.""" - v0 = np.zeros((6,), np.float) + v0 = np.zeros((6,), float) actual = I4.localCoordinates(I4) np.testing.assert_array_almost_equal(actual, v0) diff --git a/python/gtsam/tests/test_SOn.py b/python/gtsam/tests/test_SOn.py index 7599363e2..3bceccc55 100644 --- a/python/gtsam/tests/test_SOn.py +++ b/python/gtsam/tests/test_SOn.py @@ -32,13 +32,13 @@ class TestSO4(unittest.TestCase): def test_retract(self): """Test retraction to manifold.""" - v = np.zeros((6,), np.float) + v = np.zeros((6,), float) actual = I4.retract(v) self.assertTrue(actual.equals(I4, 1e-9)) def test_local(self): """Check localCoordinates for trivial case.""" - v0 = np.zeros((6,), np.float) + v0 = np.zeros((6,), float) actual = I4.localCoordinates(I4) np.testing.assert_array_almost_equal(actual, v0) From 8db1eed2d3113f8a489ac750cd51359bd7e0f106 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Mar 2021 00:35:43 -0400 Subject: [PATCH 07/21] more specific version of python to test against --- .github/scripts/python.sh | 1 - .github/workflows/build-python.yml | 2 +- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/.github/scripts/python.sh b/.github/scripts/python.sh index b9c8a25f5..22098ec08 100644 --- a/.github/scripts/python.sh +++ b/.github/scripts/python.sh @@ -58,7 +58,6 @@ PATH=$PATH:$($PYTHON -c "import site; print(site.USER_BASE)")/bin BUILD_PYBIND="ON" -TYPEDEF_POINTS_TO_VECTORS="ON" sudo $PYTHON -m pip install -r $GITHUB_WORKSPACE/python/requirements.txt diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index 089ee3246..fa7327faf 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -29,7 +29,7 @@ jobs: #TODO update wrapper to prevent OOM # build_type: [Debug, Release] build_type: [Release] - python_version: [3] + python_version: [3.6] include: - name: ubuntu-18.04-gcc-5 os: ubuntu-18.04 From 58a96227774b15808ea6fc8259b202469910007e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Mar 2021 00:36:02 -0400 Subject: [PATCH 08/21] Squashed 'wrap/' changes from aae9b4605..3eff76f60 3eff76f60 Merge pull request #53 from borglab/feature/refactor 13215dfa7 Merge pull request #52 from borglab/fix/tests 696913b11 install setuptools 9523328ba Merge branch 'master' into fix/tests 7c630b361 some more cleanup 656993a71 cleaned up Typename a16f6f38e move qualified and basis type outside to their own class scope 72ead8bd7 Merge pull request #51 from borglab/fix/test-interface-parser 6deefd4fc added tests for interface_parser 50d490a85 Merge pull request #50 from borglab/feature/refs-all-types be4511290 updated docs for BasisType 0e80b0d8c update MATLAB tests 0015d7397 added support for shared pointer and ref for basis types 86d2158f1 remove std::string from list of Basis types 94f928441 ignore code coverage reports 2033dd345 replace prints with log.debug statements ae98091b3 fix deprecation in doc tests 13a2f66c4 Merge pull request #46 from borglab/feature/new-shared-pointer 3c7d85865 updated docs 6d7897088 use @ for raw pointer, go back to * for shared pointer 1d6194c57 updated matlab wrapper to handle both raw and shared pointers 1448f6924 fix some failing tests 2ab1dae32 Merge branch 'master' into feature/new-shared-pointer 96f8a56bd Merge pull request #47 from borglab/fix/ci 6003203f3 run CI only for pull requests a8f29ead1 fix the python version yml key fcae17227 check if directory exists when testing f592f08c9 explicit pip3 so that we don't use Python2 d49c2f3c2 correct call for pip dfe360526 fix the CI 149b7c523 docs for templated functions f2189acc6 support typedefing for templated functions 965458a2b added test for templated functions eaff6e6ab made is_const common for all types 3d9c70b32 added tests and cleaned up a bit 010b89626 support for simple pointers on basis types 6b98fd80c new syntax for shared_ptr ff7ad0b78 support for templated functions a1a443c8d Merge pull request #43 from borglab/fix/cmake-and-matlab 2f3a055e4 remove accidentally committed file 770d055e2 set proper paths for cmake and eschew relative paths 773d01ae1 fix bug in matlab wrapper 721ef740f Merge pull request #41 from borglab/feature/type-hints 67aac9758 minor refactor of CI yml e6a63ae0c fix all mypy issues a3aaa3e7c remove a lot of linter issues from matlab_wrapper a96db522f static typing for interface_parser git-subtree-dir: wrap git-subtree-split: 3eff76f604b5ba9e71cf4947654e288142ed7a94 --- .github/workflows/ci.yml | 52 - .github/workflows/linux-ci.yml | 38 + .github/workflows/macos-ci.yml | 36 + .gitignore | 3 + CMakeLists.txt | 8 +- DOCS.md | 17 +- cmake/gtwrapConfig.cmake | 29 +- docs/parser/{conf_doxygen.py => doxygen.conf} | 415 +++++--- docs/parser/parse_doxygen_xml.py | 2 +- docs/parser/parse_xml.py | 2 +- gtwrap/interface_parser.py | 600 ++++++------ gtwrap/matlab_wrapper.py | 886 +++++++++++------- gtwrap/pybind_wrapper.py | 57 +- gtwrap/template_instantiator.py | 99 +- requirements.txt | 2 + tests/expected-matlab/+gtsam/Point2.m | 56 +- tests/expected-matlab/+gtsam/Point3.m | 16 +- tests/expected-matlab/MyBase.m | 6 +- tests/expected-matlab/MyFactorPosePoint2.m | 6 +- tests/expected-matlab/MyTemplateMatrix.m | 32 +- tests/expected-matlab/MyTemplatePoint2.m | 32 +- tests/expected-matlab/MyVector12.m | 6 +- tests/expected-matlab/MyVector3.m | 6 +- tests/expected-matlab/Test.m | 48 +- tests/expected-matlab/aGlobalFunction.m | 2 +- tests/expected-matlab/geometry_wrapper.cpp | 483 ++++++---- tests/expected-matlab/load2D.m | 6 +- .../overloadedGlobalFunction.m | 4 +- tests/expected-python/geometry_pybind.cpp | 141 ++- tests/expected-python/testNamespaces_py.cpp | 62 ++ tests/geometry.h | 24 +- tests/interface_parser_test.py | 258 ----- tests/test_docs.py | 58 +- tests/test_interface_parser.py | 372 ++++++++ tests/test_matlab_wrapper.py | 34 +- tests/test_pybind_wrapper.py | 48 +- 36 files changed, 2386 insertions(+), 1560 deletions(-) delete mode 100644 .github/workflows/ci.yml create mode 100644 .github/workflows/linux-ci.yml create mode 100644 .github/workflows/macos-ci.yml rename docs/parser/{conf_doxygen.py => doxygen.conf} (87%) create mode 100644 tests/expected-python/testNamespaces_py.cpp delete mode 100644 tests/interface_parser_test.py create mode 100644 tests/test_interface_parser.py diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml deleted file mode 100644 index 2e38bc3dd..000000000 --- a/.github/workflows/ci.yml +++ /dev/null @@ -1,52 +0,0 @@ -name: Python CI - -on: [push, pull_request] - -jobs: - build: - name: ${{ matrix.name }} 🐍 ${{ matrix.python_version }} - runs-on: ${{ matrix.os }} - - env: - PYTHON_VERSION: ${{ matrix.python_version }} - strategy: - fail-fast: false - matrix: - # Github Actions requires a single row to be added to the build matrix. - # See https://help.github.com/en/articles/workflow-syntax-for-github-actions. - name: [ - ubuntu-18.04 - ] - - python_version: [3] - include: - - name: ubuntu-18.04 - os: ubuntu-18.04 - - steps: - - name: Checkout - uses: actions/checkout@master - - name: Install (Linux) - if: runner.os == 'Linux' - run: | - sudo apt-get -y update - - sudo apt install cmake build-essential pkg-config libpython-dev python-numpy libboost-all-dev - - name: Install (macOS) - if: runner.os == 'macOS' - run: | - brew install cmake ninja boost - - name: Build (Linux) - if: runner.os == 'Linux' - run: | - sudo pip$PYTHON_VERSION install -r requirements.txt - cd tests - python$PYTHON_VERSION test_pybind_wrapper.py - python$PYTHON_VERSION test_matlab_wrapper.py - - name: Build (macOS) - if: runner.os == 'macOS' - run: | - pip$PYTHON_VERSION install -r requirements.txt - cd tests - python$PYTHON_VERSION test_pybind_wrapper.py - python$PYTHON_VERSION test_matlab_wrapper.py \ No newline at end of file diff --git a/.github/workflows/linux-ci.yml b/.github/workflows/linux-ci.yml new file mode 100644 index 000000000..3d7232acd --- /dev/null +++ b/.github/workflows/linux-ci.yml @@ -0,0 +1,38 @@ +name: Wrap CI for Linux + +on: [pull_request] + +jobs: + build: + name: Tests for 🐍 ${{ matrix.python-version }} + runs-on: ubuntu-18.04 + + strategy: + fail-fast: false + matrix: + python-version: [3.6, 3.7, 3.8, 3.9] + + steps: + - name: Checkout + uses: actions/checkout@v2 + + - name: Install Dependencies + run: | + sudo apt-get -y update + sudo apt install cmake build-essential pkg-config libpython-dev python-numpy libboost-all-dev + + - name: Set up Python ${{ matrix.python-version }} + uses: actions/setup-python@v2 + with: + python-version: ${{ matrix.python-version }} + + - name: Python Dependencies + run: | + sudo pip3 install -U pip setuptools + sudo pip3 install -r requirements.txt + + - name: Build and Test + run: | + cd tests + # Use Pytest to run all the tests. + pytest diff --git a/.github/workflows/macos-ci.yml b/.github/workflows/macos-ci.yml new file mode 100644 index 000000000..cd0571b34 --- /dev/null +++ b/.github/workflows/macos-ci.yml @@ -0,0 +1,36 @@ +name: Wrap CI for macOS + +on: [pull_request] + +jobs: + build: + name: Tests for 🐍 ${{ matrix.python-version }} + runs-on: macos-10.15 + + strategy: + fail-fast: false + matrix: + python-version: [3.6, 3.7, 3.8, 3.9] + + steps: + - name: Checkout + uses: actions/checkout@v2 + + - name: Install Dependencies + run: | + brew install cmake ninja boost + + - name: Set up Python ${{ matrix.python-version }} + uses: actions/setup-python@v2 + with: + python-version: ${{ matrix.python-version }} + + - name: Python Dependencies + run: | + pip3 install -r requirements.txt + + - name: Build and Test + run: | + cd tests + # Use Pytest to run all the tests. + pytest diff --git a/.gitignore b/.gitignore index 4fd660b95..4bc4f119e 100644 --- a/.gitignore +++ b/.gitignore @@ -3,3 +3,6 @@ __pycache__/ *build* *dist* *.egg-info + +# Files related to code coverage stats +**/.coverage \ No newline at end of file diff --git a/CMakeLists.txt b/CMakeLists.txt index 163165d98..3b1bbc1fe 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -31,17 +31,17 @@ include(GNUInstallDirs) # Install the gtwrap python package as a directory so it can be found by CMake # for wrapping. -install(DIRECTORY gtwrap DESTINATION "${CMAKE_INSTALL_DATADIR}/gtwrap") +install(DIRECTORY gtwrap DESTINATION "${CMAKE_INSTALL_FULL_LIBDIR}/gtwrap") # Install wrapping scripts as binaries to `CMAKE_INSTALL_PREFIX/bin` so they can # be invoked for wrapping. We use DESTINATION (instead of TYPE) so we can # support older CMake versions. install(PROGRAMS scripts/pybind_wrap.py scripts/matlab_wrap.py - DESTINATION ${CMAKE_INSTALL_BINDIR}) + DESTINATION ${CMAKE_INSTALL_FULL_BINDIR}) # Install pybind11 directory to `CMAKE_INSTALL_PREFIX/lib/gtwrap/pybind11` This # will allow the gtwrapConfig.cmake file to load it later. -install(DIRECTORY pybind11 DESTINATION "${CMAKE_INSTALL_LIBDIR}/gtwrap") +install(DIRECTORY pybind11 DESTINATION "${CMAKE_INSTALL_FULL_LIBDIR}/gtwrap") # Install the matlab.h file to `CMAKE_INSTALL_PREFIX/lib/gtwrap/matlab.h`. -install(FILES matlab.h DESTINATION "${CMAKE_INSTALL_INCLUDEDIR}/gtwrap") +install(FILES matlab.h DESTINATION "${CMAKE_INSTALL_FULL_INCLUDEDIR}/gtwrap") diff --git a/DOCS.md b/DOCS.md index 3acb7df4f..a7e8d8e3e 100644 --- a/DOCS.md +++ b/DOCS.md @@ -52,8 +52,8 @@ The python wrapper supports keyword arguments for functions/methods. Hence, the - Class variables are read-write so they can be updated directly in Python. - Pointer types - - To declare a pointer type (including shared pointers), simply add an asterisk (i.e. `*`) to the class name. - - E.g. `gtsam::noiseModel::Base*` to define the wrapping for the `Base` noise model shared pointer. + - To declare a simple/raw pointer, simply add an `@` to the class name, e.g.`Pose3@`. + - To declare a shared pointer (e.g. `gtsam::noiseModel::Base::shared_ptr`), use an asterisk (i.e. `*`). E.g. `gtsam::noiseModel::Base*` to define the wrapping for the `Base` noise model shared pointer. - Comments can use either C++ or C style, with multiple lines. @@ -76,9 +76,13 @@ The python wrapper supports keyword arguments for functions/methods. Hence, the - Functions specified outside of a class are **global**. - Can be overloaded with different arguments. - Can have multiple functions of the same name in different namespaces. + - Functions can be templated and have multiple template arguments, e.g. + ```cpp + template + ``` - Using classes defined in other modules - - If you are using a class `OtherClass` not wrapped in an interface file, add `class OtherClass;` as a forward declaration to avoid a dependency error. + - If you are using a class `OtherClass` not wrapped in an interface file, add `class OtherClass;` as a forward declaration to avoid a dependency error. `OtherClass` should be in the same project. - Virtual inheritance - Specify fully-qualified base classes, i.e. `virtual class Derived : ns::Base {` where `ns` is the namespace. @@ -140,9 +144,9 @@ The python wrapper supports keyword arguments for functions/methods. Hence, the - Forward declarations and class definitions for **Pybind**: - Need to specify the base class (both this forward class and base class are declared in an external Pybind header) - This is so that Pybind can generate proper inheritance. + - This is so that Pybind can generate proper inheritance. - Example when wrapping a gtsam-based project: + - Example for when wrapping a gtsam-based project: ```cpp // forward declarations @@ -153,8 +157,7 @@ The python wrapper supports keyword arguments for functions/methods. Hence, the virtual class MyFactor : gtsam::NoiseModelFactor {...}; ``` - - **DO NOT** re-define an overriden function already declared in the external (forward-declared) base class - - This will cause an ambiguity problem in Pybind header file. + - **DO NOT** re-define an overriden function already declared in the external (forward-declared) base class. This will cause an ambiguity problem in the Pybind header file. ### TODO diff --git a/cmake/gtwrapConfig.cmake b/cmake/gtwrapConfig.cmake index 15c5ea921..d64efa048 100644 --- a/cmake/gtwrapConfig.cmake +++ b/cmake/gtwrapConfig.cmake @@ -1,24 +1,25 @@ # This config file modifies CMAKE_MODULE_PATH so that the wrap cmake files may # be included This file also allows the use of `find_package(gtwrap)` in CMake. -set(GTWRAP_DIR "${CMAKE_CURRENT_LIST_DIR}") -list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}") - -if(WIN32 AND NOT CYGWIN) - set(GTWRAP_CMAKE_DIR "${GTWRAP_DIR}") - set(GTWRAP_SCRIPT_DIR ${GTWRAP_CMAKE_DIR}/../../../bin) - set(GTWRAP_PYTHON_PACKAGE_DIR ${GTWRAP_CMAKE_DIR}/../../../share/gtwrap) -else() - set(GTWRAP_CMAKE_DIR "${GTWRAP_DIR}") - set(GTWRAP_SCRIPT_DIR ${GTWRAP_CMAKE_DIR}/../../../bin) - set(GTWRAP_PYTHON_PACKAGE_DIR ${GTWRAP_CMAKE_DIR}/../../../share/gtwrap) -endif() - # Standard includes include(GNUInstallDirs) include(CMakePackageConfigHelpers) include(CMakeDependentOption) +set(GTWRAP_DIR "${CMAKE_CURRENT_LIST_DIR}") + +list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}") + +if(WIN32 AND NOT CYGWIN) + set(GTWRAP_CMAKE_DIR "${GTWRAP_DIR}") + set(GTWRAP_SCRIPT_DIR ${CMAKE_INSTALL_FULL_BINDIR}) + set(GTWRAP_PYTHON_PACKAGE_DIR ${CMAKE_INSTALL_FULL_LIBDIR}/gtwrap) +else() + set(GTWRAP_CMAKE_DIR "${GTWRAP_DIR}") + set(GTWRAP_SCRIPT_DIR ${CMAKE_INSTALL_FULL_BINDIR}) + set(GTWRAP_PYTHON_PACKAGE_DIR ${CMAKE_INSTALL_FULL_LIBDIR}/gtwrap) +endif() + # Load all the CMake scripts from the standard location include(${GTWRAP_CMAKE_DIR}/PybindWrap.cmake) include(${GTWRAP_CMAKE_DIR}/GtwrapUtils.cmake) @@ -28,4 +29,4 @@ set(PYBIND_WRAP_SCRIPT "${GTWRAP_SCRIPT_DIR}/pybind_wrap.py") set(MATLAB_WRAP_SCRIPT "${GTWRAP_SCRIPT_DIR}/matlab_wrap.py") # Load the pybind11 code from the library installation path -add_subdirectory(${GTWRAP_CMAKE_DIR}/../../gtwrap/pybind11 pybind11) +add_subdirectory(${CMAKE_INSTALL_FULL_LIBDIR}/gtwrap/pybind11 pybind11) diff --git a/docs/parser/conf_doxygen.py b/docs/parser/doxygen.conf similarity index 87% rename from docs/parser/conf_doxygen.py rename to docs/parser/doxygen.conf index 2cf66c07f..669e2323b 100644 --- a/docs/parser/conf_doxygen.py +++ b/docs/parser/doxygen.conf @@ -1,4 +1,4 @@ -# Doxyfile 1.8.11 +# Doxyfile 1.9.1 # This file describes the settings to be used by the documentation system # doxygen (www.doxygen.org) for a project. @@ -17,11 +17,11 @@ # Project related configuration options #--------------------------------------------------------------------------- -# This tag specifies the encoding used for all characters in the config file -# that follow. The default is UTF-8 which is also the encoding used for all text -# before the first occurrence of this tag. Doxygen uses libiconv (or the iconv -# built into libc) for the transcoding. See http://www.gnu.org/software/libiconv -# for the list of possible encodings. +# This tag specifies the encoding used for all characters in the configuration +# file that follow. The default is UTF-8 which is also the encoding used for all +# text before the first occurrence of this tag. Doxygen uses libiconv (or the +# iconv built into libc) for the transcoding. See +# https://www.gnu.org/software/libiconv/ for the list of possible encodings. # The default value is: UTF-8. DOXYFILE_ENCODING = UTF-8 @@ -32,7 +32,7 @@ DOXYFILE_ENCODING = UTF-8 # title of most generated pages and in a few other places. # The default value is: My Project. -PROJECT_NAME = "GTSAM" +PROJECT_NAME = GTSAM # The PROJECT_NUMBER tag can be used to enter a project or revision number. This # could be handy for archiving the generated documentation or if some version @@ -44,7 +44,7 @@ PROJECT_NUMBER = 0.0 # for a project that appears at the top of each page and should give viewer a # quick idea about the purpose of the project. Keep the description short. -PROJECT_BRIEF = +PROJECT_BRIEF = # With the PROJECT_LOGO tag one can specify a logo or an icon that is included # in the documentation. The maximum height of the logo should not exceed 55 @@ -93,6 +93,14 @@ ALLOW_UNICODE_NAMES = NO OUTPUT_LANGUAGE = English +# The OUTPUT_TEXT_DIRECTION tag is used to specify the direction in which all +# documentation generated by doxygen is written. Doxygen will use this +# information to generate all generated output in the proper direction. +# Possible values are: None, LTR, RTL and Context. +# The default value is: None. + +OUTPUT_TEXT_DIRECTION = None + # If the BRIEF_MEMBER_DESC tag is set to YES, doxygen will include brief member # descriptions after the members that are listed in the file and class # documentation (similar to Javadoc). Set to NO to disable this. @@ -179,6 +187,16 @@ SHORT_NAMES = NO JAVADOC_AUTOBRIEF = NO +# If the JAVADOC_BANNER tag is set to YES then doxygen will interpret a line +# such as +# /*************** +# as being the beginning of a Javadoc-style comment "banner". If set to NO, the +# Javadoc-style will behave just like regular comments and it will not be +# interpreted by doxygen. +# The default value is: NO. + +JAVADOC_BANNER = NO + # If the QT_AUTOBRIEF tag is set to YES then doxygen will interpret the first # line (until the first dot) of a Qt-style comment as the brief description. If # set to NO, the Qt-style will behave just like regular Qt-style comments (thus @@ -199,6 +217,14 @@ QT_AUTOBRIEF = NO MULTILINE_CPP_IS_BRIEF = NO +# By default Python docstrings are displayed as preformatted text and doxygen's +# special commands cannot be used. By setting PYTHON_DOCSTRING to NO the +# doxygen's special commands can be used and the contents of the docstring +# documentation blocks is shown as doxygen documentation. +# The default value is: YES. + +PYTHON_DOCSTRING = YES + # If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the # documentation from any documented member that it re-implements. # The default value is: YES. @@ -226,16 +252,15 @@ TAB_SIZE = 4 # will allow you to put the command \sideeffect (or @sideeffect) in the # documentation, which will result in a user-defined paragraph with heading # "Side Effects:". You can put \n's in the value part of an alias to insert -# newlines. +# newlines (in the resulting output). You can put ^^ in the value part of an +# alias to insert a newline as if a physical newline was in the original file. +# When you need a literal { or } or , in the value part of an alias you have to +# escape them by means of a backslash (\), this can lead to conflicts with the +# commands \{ and \} for these it is advised to use the version @{ and @} or use +# a double escape (\\{ and \\}) ALIASES = -# This tag can be used to specify a number of word-keyword mappings (TCL only). -# A mapping has the form "name=value". For example adding "class=itcl::class" -# will allow you to use the command class in the itcl::class meaning. - -TCL_SUBST = - # Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources # only. Doxygen will then generate output that is more tailored for C. For # instance, some of the names that are used will be different. The list of all @@ -264,28 +289,40 @@ OPTIMIZE_FOR_FORTRAN = NO OPTIMIZE_OUTPUT_VHDL = NO +# Set the OPTIMIZE_OUTPUT_SLICE tag to YES if your project consists of Slice +# sources only. Doxygen will then generate output that is more tailored for that +# language. For instance, namespaces will be presented as modules, types will be +# separated into more groups, etc. +# The default value is: NO. + +OPTIMIZE_OUTPUT_SLICE = NO + # Doxygen selects the parser to use depending on the extension of the files it # parses. With this tag you can assign which parser to use for a given # extension. Doxygen has a built-in mapping, but you can override or extend it # using this tag. The format is ext=language, where ext is a file extension, and -# language is one of the parsers supported by doxygen: IDL, Java, Javascript, -# C#, C, C++, D, PHP, Objective-C, Python, Fortran (fixed format Fortran: -# FortranFixed, free formatted Fortran: FortranFree, unknown formatted Fortran: -# Fortran. In the later case the parser tries to guess whether the code is fixed -# or free formatted code, this is the default for Fortran type files), VHDL. For -# instance to make doxygen treat .inc files as Fortran files (default is PHP), -# and .f files as C (default is Fortran), use: inc=Fortran f=C. +# language is one of the parsers supported by doxygen: IDL, Java, JavaScript, +# Csharp (C#), C, C++, D, PHP, md (Markdown), Objective-C, Python, Slice, VHDL, +# Fortran (fixed format Fortran: FortranFixed, free formatted Fortran: +# FortranFree, unknown formatted Fortran: Fortran. In the later case the parser +# tries to guess whether the code is fixed or free formatted code, this is the +# default for Fortran type files). For instance to make doxygen treat .inc files +# as Fortran files (default is PHP), and .f files as C (default is Fortran), +# use: inc=Fortran f=C. # # Note: For files without extension you can use no_extension as a placeholder. # # Note that for custom extensions you also need to set FILE_PATTERNS otherwise -# the files are not read by doxygen. +# the files are not read by doxygen. When specifying no_extension you should add +# * to the FILE_PATTERNS. +# +# Note see also the list of default file extension mappings. EXTENSION_MAPPING = # If the MARKDOWN_SUPPORT tag is enabled then doxygen pre-processes all comments # according to the Markdown format, which allows for more readable -# documentation. See http://daringfireball.net/projects/markdown/ for details. +# documentation. See https://daringfireball.net/projects/markdown/ for details. # The output of markdown processing is further processed by doxygen, so you can # mix doxygen, HTML, and XML commands with Markdown formatting. Disable only in # case of backward compatibilities issues. @@ -293,6 +330,15 @@ EXTENSION_MAPPING = MARKDOWN_SUPPORT = YES +# When the TOC_INCLUDE_HEADINGS tag is set to a non-zero value, all headings up +# to that level are automatically included in the table of contents, even if +# they do not have an id attribute. +# Note: This feature currently applies only to Markdown headings. +# Minimum value: 0, maximum value: 99, default value: 5. +# This tag requires that the tag MARKDOWN_SUPPORT is set to YES. + +TOC_INCLUDE_HEADINGS = 5 + # When enabled doxygen tries to link words that correspond to documented # classes, or namespaces to their corresponding documentation. Such a link can # be prevented in individual cases by putting a % sign in front of the word or @@ -318,7 +364,7 @@ BUILTIN_STL_SUPPORT = NO CPP_CLI_SUPPORT = NO # Set the SIP_SUPPORT tag to YES if your project consists of sip (see: -# http://www.riverbankcomputing.co.uk/software/sip/intro) sources only. Doxygen +# https://www.riverbankcomputing.com/software/sip/intro) sources only. Doxygen # will parse them like normal C++ but will assume all classes use public instead # of private inheritance when no explicit protection keyword is present. # The default value is: NO. @@ -404,6 +450,19 @@ TYPEDEF_HIDES_STRUCT = NO LOOKUP_CACHE_SIZE = 0 +# The NUM_PROC_THREADS specifies the number threads doxygen is allowed to use +# during processing. When set to 0 doxygen will based this on the number of +# cores available in the system. You can set it explicitly to a value larger +# than 0 to get more control over the balance between CPU load and processing +# speed. At this moment only the input processing can be done using multiple +# threads. Since this is still an experimental feature the default is set to 1, +# which efficively disables parallel processing. Please report any issues you +# encounter. Generating dot graphs in parallel is controlled by the +# DOT_NUM_THREADS setting. +# Minimum value: 0, maximum value: 32, default value: 1. + +NUM_PROC_THREADS = 1 + #--------------------------------------------------------------------------- # Build related configuration options #--------------------------------------------------------------------------- @@ -416,7 +475,7 @@ LOOKUP_CACHE_SIZE = 0 # normally produced when WARNINGS is set to YES. # The default value is: NO. -EXTRACT_ALL = +EXTRACT_ALL = NO # If the EXTRACT_PRIVATE tag is set to YES, all private members of a class will # be included in the documentation. @@ -424,6 +483,12 @@ EXTRACT_ALL = EXTRACT_PRIVATE = NO +# If the EXTRACT_PRIV_VIRTUAL tag is set to YES, documented private virtual +# methods of a class will be included in the documentation. +# The default value is: NO. + +EXTRACT_PRIV_VIRTUAL = NO + # If the EXTRACT_PACKAGE tag is set to YES, all members with package or internal # scope will be included in the documentation. # The default value is: NO. @@ -461,6 +526,13 @@ EXTRACT_LOCAL_METHODS = NO EXTRACT_ANON_NSPACES = NO +# If this flag is set to YES, the name of an unnamed parameter in a declaration +# will be determined by the corresponding definition. By default unnamed +# parameters remain unnamed in the output. +# The default value is: YES. + +RESOLVE_UNNAMED_PARAMS = YES + # If the HIDE_UNDOC_MEMBERS tag is set to YES, doxygen will hide all # undocumented members inside documented classes or files. If set to NO these # members will be included in the various overviews, but no documentation @@ -478,8 +550,8 @@ HIDE_UNDOC_MEMBERS = NO HIDE_UNDOC_CLASSES = NO # If the HIDE_FRIEND_COMPOUNDS tag is set to YES, doxygen will hide all friend -# (class|struct|union) declarations. If set to NO, these declarations will be -# included in the documentation. +# declarations. If set to NO, these declarations will be included in the +# documentation. # The default value is: NO. HIDE_FRIEND_COMPOUNDS = NO @@ -498,11 +570,18 @@ HIDE_IN_BODY_DOCS = NO INTERNAL_DOCS = NO -# If the CASE_SENSE_NAMES tag is set to NO then doxygen will only generate file -# names in lower-case letters. If set to YES, upper-case letters are also -# allowed. This is useful if you have classes or files whose names only differ -# in case and if your file system supports case sensitive file names. Windows -# and Mac users are advised to set this option to NO. +# With the correct setting of option CASE_SENSE_NAMES doxygen will better be +# able to match the capabilities of the underlying filesystem. In case the +# filesystem is case sensitive (i.e. it supports files in the same directory +# whose names only differ in casing), the option must be set to YES to properly +# deal with such files in case they appear in the input. For filesystems that +# are not case sensitive the option should be be set to NO to properly deal with +# output files written for symbols that only differ in casing, such as for two +# classes, one named CLASS and the other named Class, and to also support +# references to files without having to specify the exact matching casing. On +# Windows (including Cygwin) and MacOS, users should typically set this option +# to NO, whereas on Linux or other Unix flavors it should typically be set to +# YES. # The default value is: system dependent. CASE_SENSE_NAMES = YES @@ -689,7 +768,7 @@ LAYOUT_FILE = # The CITE_BIB_FILES tag can be used to specify one or more bib files containing # the reference definitions. This must be a list of .bib files. The .bib # extension is automatically appended if omitted. This requires the bibtex tool -# to be installed. See also http://en.wikipedia.org/wiki/BibTeX for more info. +# to be installed. See also https://en.wikipedia.org/wiki/BibTeX for more info. # For LaTeX the style of the bibliography can be controlled using # LATEX_BIB_STYLE. To use this feature you need bibtex and perl available in the # search path. See also \cite for info how to create references. @@ -734,13 +813,17 @@ WARN_IF_DOC_ERROR = YES # This WARN_NO_PARAMDOC option can be enabled to get warnings for functions that # are documented, but have no documentation for their parameters or return # value. If set to NO, doxygen will only warn about wrong or incomplete -# parameter documentation, but not about the absence of documentation. +# parameter documentation, but not about the absence of documentation. If +# EXTRACT_ALL is set to YES then this flag will automatically be disabled. # The default value is: NO. WARN_NO_PARAMDOC = NO # If the WARN_AS_ERROR tag is set to YES then doxygen will immediately stop when -# a warning is encountered. +# a warning is encountered. If the WARN_AS_ERROR tag is set to FAIL_ON_WARNINGS +# then doxygen will continue running as if WARN_AS_ERROR tag is set to NO, but +# at the end of the doxygen process doxygen will return with a non-zero status. +# Possible values are: NO, YES and FAIL_ON_WARNINGS. # The default value is: NO. WARN_AS_ERROR = NO @@ -771,13 +854,13 @@ WARN_LOGFILE = # spaces. See also FILE_PATTERNS and EXTENSION_MAPPING # Note: If this tag is empty the current directory is searched. -INPUT = +INPUT = # This tag can be used to specify the character encoding of the source files # that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses # libiconv (or the iconv built into libc) for the transcoding. See the libiconv -# documentation (see: http://www.gnu.org/software/libiconv) for the list of -# possible encodings. +# documentation (see: +# https://www.gnu.org/software/libiconv/) for the list of possible encodings. # The default value is: UTF-8. INPUT_ENCODING = UTF-8 @@ -790,11 +873,15 @@ INPUT_ENCODING = UTF-8 # need to set EXTENSION_MAPPING for the extension otherwise the files are not # read by doxygen. # +# Note the list of default checked file patterns might differ from the list of +# default file extension mappings. +# # If left blank the following patterns are tested:*.c, *.cc, *.cxx, *.cpp, # *.c++, *.java, *.ii, *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h, # *.hh, *.hxx, *.hpp, *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc, -# *.m, *.markdown, *.md, *.mm, *.dox, *.py, *.pyw, *.f90, *.f, *.for, *.tcl, -# *.vhd, *.vhdl, *.ucf, *.qsf, *.as and *.js. +# *.m, *.markdown, *.md, *.mm, *.dox (to be provided as doxygen C comment), +# *.py, *.pyw, *.f90, *.f95, *.f03, *.f08, *.f18, *.f, *.for, *.vhd, *.vhdl, +# *.ucf, *.qsf and *.ice. FILE_PATTERNS = @@ -949,7 +1036,7 @@ INLINE_SOURCES = NO STRIP_CODE_COMMENTS = YES # If the REFERENCED_BY_RELATION tag is set to YES then for each documented -# function all documented functions referencing it will be listed. +# entity all documented functions referencing it will be listed. # The default value is: NO. REFERENCED_BY_RELATION = NO @@ -981,12 +1068,12 @@ SOURCE_TOOLTIPS = YES # If the USE_HTAGS tag is set to YES then the references to source code will # point to the HTML generated by the htags(1) tool instead of doxygen built-in # source browser. The htags tool is part of GNU's global source tagging system -# (see http://www.gnu.org/software/global/global.html). You will need version +# (see https://www.gnu.org/software/global/global.html). You will need version # 4.8.6 or higher. # # To use it do the following: # - Install the latest version of global -# - Enable SOURCE_BROWSER and USE_HTAGS in the config file +# - Enable SOURCE_BROWSER and USE_HTAGS in the configuration file # - Make sure the INPUT points to the root of the source tree # - Run doxygen as normal # @@ -1008,25 +1095,6 @@ USE_HTAGS = NO VERBATIM_HEADERS = YES -# If the CLANG_ASSISTED_PARSING tag is set to YES then doxygen will use the -# clang parser (see: http://clang.llvm.org/) for more accurate parsing at the -# cost of reduced performance. This can be particularly helpful with template -# rich C++ code for which doxygen's built-in parser lacks the necessary type -# information. -# Note: The availability of this option depends on whether or not doxygen was -# generated with the -Duse-libclang=ON option for CMake. -# The default value is: NO. - -CLANG_ASSISTED_PARSING = NO - -# If clang assisted parsing is enabled you can provide the compiler with command -# line options that you would normally use when invoking the compiler. Note that -# the include paths will already be set by doxygen for the files and directories -# specified with INPUT and INCLUDE_PATH. -# This tag requires that the tag CLANG_ASSISTED_PARSING is set to YES. - -CLANG_OPTIONS = - #--------------------------------------------------------------------------- # Configuration options related to the alphabetical class index #--------------------------------------------------------------------------- @@ -1038,13 +1106,6 @@ CLANG_OPTIONS = ALPHABETICAL_INDEX = YES -# The COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns in -# which the alphabetical index list will be split. -# Minimum value: 1, maximum value: 20, default value: 5. -# This tag requires that the tag ALPHABETICAL_INDEX is set to YES. - -COLS_IN_ALPHA_INDEX = 5 - # In case all classes in a project start with a common prefix, all classes will # be put under the same header in the alphabetical index. The IGNORE_PREFIX tag # can be used to specify a prefix (or a list of prefixes) that should be ignored @@ -1145,7 +1206,7 @@ HTML_EXTRA_FILES = # The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen # will adjust the colors in the style sheet and background images according to # this color. Hue is specified as an angle on a colorwheel, see -# http://en.wikipedia.org/wiki/Hue for more information. For instance the value +# https://en.wikipedia.org/wiki/Hue for more information. For instance the value # 0 represents red, 60 is yellow, 120 is green, 180 is cyan, 240 is blue, 300 # purple, and 360 is red again. # Minimum value: 0, maximum value: 359, default value: 220. @@ -1181,6 +1242,17 @@ HTML_COLORSTYLE_GAMMA = 80 HTML_TIMESTAMP = NO +# If the HTML_DYNAMIC_MENUS tag is set to YES then the generated HTML +# documentation will contain a main index with vertical navigation menus that +# are dynamically created via JavaScript. If disabled, the navigation index will +# consists of multiple levels of tabs that are statically embedded in every HTML +# page. Disable this option to support browsers that do not have JavaScript, +# like the Qt help browser. +# The default value is: YES. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_DYNAMIC_MENUS = YES + # If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML # documentation will contain sections that can be hidden and shown after the # page has loaded. @@ -1204,13 +1276,14 @@ HTML_INDEX_NUM_ENTRIES = 100 # If the GENERATE_DOCSET tag is set to YES, additional index files will be # generated that can be used as input for Apple's Xcode 3 integrated development -# environment (see: http://developer.apple.com/tools/xcode/), introduced with -# OSX 10.5 (Leopard). To create a documentation set, doxygen will generate a -# Makefile in the HTML output directory. Running make will produce the docset in -# that directory and running make install will install the docset in +# environment (see: +# https://developer.apple.com/xcode/), introduced with OSX 10.5 (Leopard). To +# create a documentation set, doxygen will generate a Makefile in the HTML +# output directory. Running make will produce the docset in that directory and +# running make install will install the docset in # ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at -# startup. See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html -# for more information. +# startup. See https://developer.apple.com/library/archive/featuredarticles/Doxy +# genXcode/_index.html for more information. # The default value is: NO. # This tag requires that the tag GENERATE_HTML is set to YES. @@ -1249,8 +1322,8 @@ DOCSET_PUBLISHER_NAME = Publisher # If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three # additional HTML index files: index.hhp, index.hhc, and index.hhk. The # index.hhp is a project file that can be read by Microsoft's HTML Help Workshop -# (see: http://www.microsoft.com/en-us/download/details.aspx?id=21138) on -# Windows. +# (see: +# https://www.microsoft.com/en-us/download/details.aspx?id=21138) on Windows. # # The HTML Help Workshop contains a compiler that can convert all HTML output # generated by doxygen into a single compiled HTML file (.chm). Compiled HTML @@ -1280,7 +1353,7 @@ CHM_FILE = HHC_LOCATION = # The GENERATE_CHI flag controls if a separate .chi index file is generated -# (YES) or that it should be included in the master .chm file (NO). +# (YES) or that it should be included in the main .chm file (NO). # The default value is: NO. # This tag requires that the tag GENERATE_HTMLHELP is set to YES. @@ -1325,7 +1398,8 @@ QCH_FILE = # The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help # Project output. For more information please see Qt Help Project / Namespace -# (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#namespace). +# (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#namespace). # The default value is: org.doxygen.Project. # This tag requires that the tag GENERATE_QHP is set to YES. @@ -1333,8 +1407,8 @@ QHP_NAMESPACE = org.doxygen.Project # The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt # Help Project output. For more information please see Qt Help Project / Virtual -# Folders (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#virtual- -# folders). +# Folders (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#virtual-folders). # The default value is: doc. # This tag requires that the tag GENERATE_QHP is set to YES. @@ -1342,30 +1416,30 @@ QHP_VIRTUAL_FOLDER = doc # If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom # filter to add. For more information please see Qt Help Project / Custom -# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom- -# filters). +# Filters (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom-filters). # This tag requires that the tag GENERATE_QHP is set to YES. QHP_CUST_FILTER_NAME = # The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the # custom filter to add. For more information please see Qt Help Project / Custom -# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom- -# filters). +# Filters (see: +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#custom-filters). # This tag requires that the tag GENERATE_QHP is set to YES. QHP_CUST_FILTER_ATTRS = # The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this # project's filter section matches. Qt Help Project / Filter Attributes (see: -# http://qt-project.org/doc/qt-4.8/qthelpproject.html#filter-attributes). +# https://doc.qt.io/archives/qt-4.8/qthelpproject.html#filter-attributes). # This tag requires that the tag GENERATE_QHP is set to YES. QHP_SECT_FILTER_ATTRS = -# The QHG_LOCATION tag can be used to specify the location of Qt's -# qhelpgenerator. If non-empty doxygen will try to run qhelpgenerator on the -# generated .qhp file. +# The QHG_LOCATION tag can be used to specify the location (absolute path +# including file name) of Qt's qhelpgenerator. If non-empty doxygen will try to +# run qhelpgenerator on the generated .qhp file. # This tag requires that the tag GENERATE_QHP is set to YES. QHG_LOCATION = @@ -1442,6 +1516,17 @@ TREEVIEW_WIDTH = 250 EXT_LINKS_IN_WINDOW = NO +# If the HTML_FORMULA_FORMAT option is set to svg, doxygen will use the pdf2svg +# tool (see https://github.com/dawbarton/pdf2svg) or inkscape (see +# https://inkscape.org) to generate formulas as SVG images instead of PNGs for +# the HTML output. These images will generally look nicer at scaled resolutions. +# Possible values are: png (the default) and svg (looks nicer but requires the +# pdf2svg or inkscape tool). +# The default value is: png. +# This tag requires that the tag GENERATE_HTML is set to YES. + +HTML_FORMULA_FORMAT = png + # Use this tag to change the font size of LaTeX formulas included as images in # the HTML documentation. When you change the font size after a successful # doxygen run you need to manually remove any form_*.png images from the HTML @@ -1451,7 +1536,7 @@ EXT_LINKS_IN_WINDOW = NO FORMULA_FONTSIZE = 10 -# Use the FORMULA_TRANPARENT tag to determine whether or not the images +# Use the FORMULA_TRANSPARENT tag to determine whether or not the images # generated for formulas are transparent PNGs. Transparent PNGs are not # supported properly for IE 6.0, but are supported on all modern browsers. # @@ -1462,8 +1547,14 @@ FORMULA_FONTSIZE = 10 FORMULA_TRANSPARENT = YES +# The FORMULA_MACROFILE can contain LaTeX \newcommand and \renewcommand commands +# to create new LaTeX commands to be used in formulas as building blocks. See +# the section "Including formulas" for details. + +FORMULA_MACROFILE = + # Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see -# http://www.mathjax.org) which uses client side Javascript for the rendering +# https://www.mathjax.org) which uses client side JavaScript for the rendering # instead of using pre-rendered bitmaps. Use this if you do not have LaTeX # installed or if you want to formulas look prettier in the HTML output. When # enabled you may also need to install MathJax separately and configure the path @@ -1475,7 +1566,7 @@ USE_MATHJAX = NO # When MathJax is enabled you can set the default output format to be used for # the MathJax output. See the MathJax site (see: -# http://docs.mathjax.org/en/latest/output.html) for more details. +# http://docs.mathjax.org/en/v2.7-latest/output.html) for more details. # Possible values are: HTML-CSS (which is slower, but has the best # compatibility), NativeMML (i.e. MathML) and SVG. # The default value is: HTML-CSS. @@ -1490,8 +1581,8 @@ MATHJAX_FORMAT = HTML-CSS # MATHJAX_RELPATH should be ../mathjax. The default value points to the MathJax # Content Delivery Network so you can quickly see the result without installing # MathJax. However, it is strongly recommended to install a local copy of -# MathJax from http://www.mathjax.org before deployment. -# The default value is: http://cdn.mathjax.org/mathjax/latest. +# MathJax from https://www.mathjax.org before deployment. +# The default value is: https://cdn.jsdelivr.net/npm/mathjax@2. # This tag requires that the tag USE_MATHJAX is set to YES. MATHJAX_RELPATH = http://cdn.mathjax.org/mathjax/latest @@ -1505,7 +1596,8 @@ MATHJAX_EXTENSIONS = # The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces # of code that will be used on startup of the MathJax code. See the MathJax site -# (see: http://docs.mathjax.org/en/latest/output.html) for more details. For an +# (see: +# http://docs.mathjax.org/en/v2.7-latest/output.html) for more details. For an # example see the documentation. # This tag requires that the tag USE_MATHJAX is set to YES. @@ -1533,7 +1625,7 @@ MATHJAX_CODEFILE = SEARCHENGINE = YES # When the SERVER_BASED_SEARCH tag is enabled the search engine will be -# implemented using a web server instead of a web client using Javascript. There +# implemented using a web server instead of a web client using JavaScript. There # are two flavors of web server based searching depending on the EXTERNAL_SEARCH # setting. When disabled, doxygen will generate a PHP script for searching and # an index file used by the script. When EXTERNAL_SEARCH is enabled the indexing @@ -1552,7 +1644,8 @@ SERVER_BASED_SEARCH = NO # # Doxygen ships with an example indexer (doxyindexer) and search engine # (doxysearch.cgi) which are based on the open source search engine library -# Xapian (see: http://xapian.org/). +# Xapian (see: +# https://xapian.org/). # # See the section "External Indexing and Searching" for details. # The default value is: NO. @@ -1565,8 +1658,9 @@ EXTERNAL_SEARCH = NO # # Doxygen ships with an example indexer (doxyindexer) and search engine # (doxysearch.cgi) which are based on the open source search engine library -# Xapian (see: http://xapian.org/). See the section "External Indexing and -# Searching" for details. +# Xapian (see: +# https://xapian.org/). See the section "External Indexing and Searching" for +# details. # This tag requires that the tag SEARCHENGINE is set to YES. SEARCHENGINE_URL = @@ -1617,21 +1711,35 @@ LATEX_OUTPUT = latex # The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be # invoked. # -# Note that when enabling USE_PDFLATEX this option is only used for generating -# bitmaps for formulas in the HTML output, but not in the Makefile that is -# written to the output directory. -# The default file is: latex. +# Note that when not enabling USE_PDFLATEX the default is latex when enabling +# USE_PDFLATEX the default is pdflatex and when in the later case latex is +# chosen this is overwritten by pdflatex. For specific output languages the +# default can have been set differently, this depends on the implementation of +# the output language. # This tag requires that the tag GENERATE_LATEX is set to YES. LATEX_CMD_NAME = latex # The MAKEINDEX_CMD_NAME tag can be used to specify the command name to generate # index for LaTeX. +# Note: This tag is used in the Makefile / make.bat. +# See also: LATEX_MAKEINDEX_CMD for the part in the generated output file +# (.tex). # The default file is: makeindex. # This tag requires that the tag GENERATE_LATEX is set to YES. MAKEINDEX_CMD_NAME = makeindex +# The LATEX_MAKEINDEX_CMD tag can be used to specify the command name to +# generate index for LaTeX. In case there is no backslash (\) as first character +# it will be automatically added in the LaTeX code. +# Note: This tag is used in the generated output file (.tex). +# See also: MAKEINDEX_CMD_NAME for the part in the Makefile / make.bat. +# The default value is: makeindex. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_MAKEINDEX_CMD = makeindex + # If the COMPACT_LATEX tag is set to YES, doxygen generates more compact LaTeX # documents. This may be useful for small projects and may help to save some # trees in general. @@ -1716,9 +1824,11 @@ LATEX_EXTRA_FILES = PDF_HYPERLINKS = YES -# If the USE_PDFLATEX tag is set to YES, doxygen will use pdflatex to generate -# the PDF file directly from the LaTeX files. Set this option to YES, to get a -# higher quality PDF documentation. +# If the USE_PDFLATEX tag is set to YES, doxygen will use the engine as +# specified with LATEX_CMD_NAME to generate the PDF file directly from the LaTeX +# files. Set this option to YES, to get a higher quality PDF documentation. +# +# See also section LATEX_CMD_NAME for selecting the engine. # The default value is: YES. # This tag requires that the tag GENERATE_LATEX is set to YES. @@ -1752,7 +1862,7 @@ LATEX_SOURCE_CODE = NO # The LATEX_BIB_STYLE tag can be used to specify the style to use for the # bibliography, e.g. plainnat, or ieeetr. See -# http://en.wikipedia.org/wiki/BibTeX and \cite for more info. +# https://en.wikipedia.org/wiki/BibTeX and \cite for more info. # The default value is: plain. # This tag requires that the tag GENERATE_LATEX is set to YES. @@ -1766,6 +1876,14 @@ LATEX_BIB_STYLE = plain LATEX_TIMESTAMP = NO +# The LATEX_EMOJI_DIRECTORY tag is used to specify the (relative or absolute) +# path from which the emoji images will be read. If a relative path is entered, +# it will be relative to the LATEX_OUTPUT directory. If left blank the +# LATEX_OUTPUT directory will be used. +# This tag requires that the tag GENERATE_LATEX is set to YES. + +LATEX_EMOJI_DIRECTORY = + #--------------------------------------------------------------------------- # Configuration options related to the RTF output #--------------------------------------------------------------------------- @@ -1805,9 +1923,9 @@ COMPACT_RTF = NO RTF_HYPERLINKS = NO -# Load stylesheet definitions from file. Syntax is similar to doxygen's config -# file, i.e. a series of assignments. You only have to provide replacements, -# missing definitions are set to their default value. +# Load stylesheet definitions from file. Syntax is similar to doxygen's +# configuration file, i.e. a series of assignments. You only have to provide +# replacements, missing definitions are set to their default value. # # See also section "Doxygen usage" for information on how to generate the # default style sheet that doxygen normally uses. @@ -1816,8 +1934,8 @@ RTF_HYPERLINKS = NO RTF_STYLESHEET_FILE = # Set optional variables used in the generation of an RTF document. Syntax is -# similar to doxygen's config file. A template extensions file can be generated -# using doxygen -e rtf extensionFile. +# similar to doxygen's configuration file. A template extensions file can be +# generated using doxygen -e rtf extensionFile. # This tag requires that the tag GENERATE_RTF is set to YES. RTF_EXTENSIONS_FILE = @@ -1903,6 +2021,13 @@ XML_OUTPUT = xml XML_PROGRAMLISTING = YES +# If the XML_NS_MEMB_FILE_SCOPE tag is set to YES, doxygen will include +# namespace members in file scope as well, matching the HTML output. +# The default value is: NO. +# This tag requires that the tag GENERATE_XML is set to YES. + +XML_NS_MEMB_FILE_SCOPE = NO + #--------------------------------------------------------------------------- # Configuration options related to the DOCBOOK output #--------------------------------------------------------------------------- @@ -1935,9 +2060,9 @@ DOCBOOK_PROGRAMLISTING = NO #--------------------------------------------------------------------------- # If the GENERATE_AUTOGEN_DEF tag is set to YES, doxygen will generate an -# AutoGen Definitions (see http://autogen.sf.net) file that captures the -# structure of the code including all documentation. Note that this feature is -# still experimental and incomplete at the moment. +# AutoGen Definitions (see http://autogen.sourceforge.net/) file that captures +# the structure of the code including all documentation. Note that this feature +# is still experimental and incomplete at the moment. # The default value is: NO. GENERATE_AUTOGEN_DEF = NO @@ -2104,12 +2229,6 @@ EXTERNAL_GROUPS = YES EXTERNAL_PAGES = YES -# The PERL_PATH should be the absolute path and name of the perl script -# interpreter (i.e. the result of 'which perl'). -# The default file (with absolute path) is: /usr/bin/perl. - -PERL_PATH = /usr/bin/perl - #--------------------------------------------------------------------------- # Configuration options related to the dot tool #--------------------------------------------------------------------------- @@ -2123,15 +2242,6 @@ PERL_PATH = /usr/bin/perl CLASS_DIAGRAMS = YES -# You can define message sequence charts within doxygen comments using the \msc -# command. Doxygen will then run the mscgen tool (see: -# http://www.mcternan.me.uk/mscgen/)) to produce the chart and insert it in the -# documentation. The MSCGEN_PATH tag allows you to specify the directory where -# the mscgen tool resides. If left empty the tool is assumed to be found in the -# default search path. - -MSCGEN_PATH = - # You can include diagrams made with dia in doxygen documentation. Doxygen will # then run dia to produce the diagram and insert it in the documentation. The # DIA_PATH tag allows you to specify the directory where the dia binary resides. @@ -2150,7 +2260,7 @@ HIDE_UNDOC_RELATIONS = YES # http://www.graphviz.org/), a graph visualization toolkit from AT&T and Lucent # Bell Labs. The other options in this section have no effect if this option is # set to NO -# The default value is: YES. +# The default value is: NO. HAVE_DOT = YES @@ -2229,10 +2339,32 @@ UML_LOOK = NO # but if the number exceeds 15, the total amount of fields shown is limited to # 10. # Minimum value: 0, maximum value: 100, default value: 10. -# This tag requires that the tag HAVE_DOT is set to YES. +# This tag requires that the tag UML_LOOK is set to YES. UML_LIMIT_NUM_FIELDS = 10 +# If the DOT_UML_DETAILS tag is set to NO, doxygen will show attributes and +# methods without types and arguments in the UML graphs. If the DOT_UML_DETAILS +# tag is set to YES, doxygen will add type and arguments for attributes and +# methods in the UML graphs. If the DOT_UML_DETAILS tag is set to NONE, doxygen +# will not generate fields with class member information in the UML graphs. The +# class diagrams will look similar to the default class diagrams but using UML +# notation for the relationships. +# Possible values are: NO, YES and NONE. +# The default value is: NO. +# This tag requires that the tag UML_LOOK is set to YES. + +DOT_UML_DETAILS = NO + +# The DOT_WRAP_THRESHOLD tag can be used to set the maximum number of characters +# to display on a single line. If the actual line length exceeds this threshold +# significantly it will wrapped across multiple lines. Some heuristics are apply +# to avoid ugly line breaks. +# Minimum value: 0, maximum value: 1000, default value: 17. +# This tag requires that the tag HAVE_DOT is set to YES. + +DOT_WRAP_THRESHOLD = 17 + # If the TEMPLATE_RELATIONS tag is set to YES then the inheritance and # collaboration graphs will show the relations between templates and their # instances. @@ -2306,9 +2438,7 @@ DIRECTORY_GRAPH = YES # Note: If you choose svg you need to set HTML_FILE_EXTENSION to xhtml in order # to make the SVG files visible in IE 9+ (other browsers do not have this # requirement). -# Possible values are: png, png:cairo, png:cairo:cairo, png:cairo:gd, png:gd, -# png:gd:gd, jpg, jpg:cairo, jpg:cairo:gd, jpg:gd, jpg:gd:gd, gif, gif:cairo, -# gif:cairo:gd, gif:gd, gif:gd:gd, svg, png:gd, png:gd:gd, png:cairo, +# Possible values are: png, jpg, gif, svg, png:gd, png:gd:gd, png:cairo, # png:cairo:gd, png:cairo:cairo, png:cairo:gdiplus, png:gdiplus and # png:gdiplus:gdiplus. # The default value is: png. @@ -2361,6 +2491,11 @@ DIAFILE_DIRS = PLANTUML_JAR_PATH = +# When using plantuml, the PLANTUML_CFG_FILE tag can be used to specify a +# configuration file for plantuml. + +PLANTUML_CFG_FILE = + # When using plantuml, the specified paths are searched for files specified by # the !include statement in a plantuml block. @@ -2419,9 +2554,11 @@ DOT_MULTI_TARGETS = NO GENERATE_LEGEND = YES -# If the DOT_CLEANUP tag is set to YES, doxygen will remove the intermediate dot +# If the DOT_CLEANUP tag is set to YES, doxygen will remove the intermediate # files that are used to generate the various graphs. +# +# Note: This setting is not only used for dot files but also for msc and +# plantuml temporary files. # The default value is: YES. -# This tag requires that the tag HAVE_DOT is set to YES. DOT_CLEANUP = YES diff --git a/docs/parser/parse_doxygen_xml.py b/docs/parser/parse_doxygen_xml.py index 54e9cbcbf..fd267b48f 100644 --- a/docs/parser/parse_doxygen_xml.py +++ b/docs/parser/parse_doxygen_xml.py @@ -4,7 +4,7 @@ import xml.etree.ElementTree as ET from docs.docs import ClassDoc, Doc, Docs, FreeDoc -DOXYGEN_CONF = 'conf_doxygen.py' +DOXYGEN_CONF = 'doxygen.conf' class ParseDoxygenXML(): diff --git a/docs/parser/parse_xml.py b/docs/parser/parse_xml.py index 813608ec8..5bee4ad1a 100644 --- a/docs/parser/parse_xml.py +++ b/docs/parser/parse_xml.py @@ -4,7 +4,7 @@ from docs.doc_template import ClassDoc, Doc, Docs, FreeDoc import os.path as path import xml.etree.ElementTree as ET -DOXYGEN_CONF = 'conf_doxygen.py' +DOXYGEN_CONF = 'doxygen.conf' def parse(input_path, output_path, quiet=False, generate_xml_flag=True): diff --git a/gtwrap/interface_parser.py b/gtwrap/interface_parser.py index b4328327f..157de555a 100644 --- a/gtwrap/interface_parser.py +++ b/gtwrap/interface_parser.py @@ -12,11 +12,11 @@ Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellae # pylint: disable=unnecessary-lambda, unused-import, expression-not-assigned, no-else-return, protected-access, too-few-public-methods, too-many-arguments import sys -import typing +from typing import Iterable, Union, Tuple, List -import pyparsing +import pyparsing # type: ignore from pyparsing import (CharsNotIn, Forward, Group, Keyword, Literal, OneOrMore, - Optional, Or, ParseException, ParserElement, Suppress, + Optional, Or, ParseException, ParseResults, ParserElement, Suppress, Word, ZeroOrMore, alphanums, alphas, cppStyleComment, delimitedList, empty, nums, stringEnd) @@ -43,7 +43,8 @@ ParserElement.enablePackrat() # rule for identifiers (e.g. variable names) IDENT = Word(alphas + '_', alphanums + '_') ^ Word(nums) -POINTER, REF = map(Literal, "*&") +RAW_POINTER, SHARED_POINTER, REF = map(Literal, "@*&") + LPAREN, RPAREN, LBRACE, RBRACE, COLON, SEMI_COLON = map(Suppress, "(){}:;") LOPBRACK, ROPBRACK, COMMA, EQUAL = map(Suppress, "<>,=") CONST, VIRTUAL, CLASS, STATIC, PAIR, TEMPLATE, TYPEDEF, INCLUDE = map( @@ -71,36 +72,50 @@ BASIS_TYPES = map( "size_t", "double", "float", - "string", ], ) class Typename: """ - Type's name with full namespaces, used in Type class. + Generic type which can be either a basic type or a class type, + similar to C++'s `typename` aka a qualified dependent type. + Contains type name with full namespace and template arguments. + + E.g. + ``` + gtsam::PinholeCamera + ``` + + will give the name as `PinholeCamera`, namespace as `gtsam`, + and template instantiations as `[gtsam::Cal3S2]`. + + Args: + namespaces_and_name: A list representing the namespaces of the type + with the type being the last element. + instantiations: Template parameters to the type. """ namespaces_name_rule = delimitedList(IDENT, "::") instantiation_name_rule = delimitedList(IDENT, "::") rule = Forward() - rule << ( - namespaces_name_rule("namespaces_name") + namespaces_name_rule("namespaces_and_name") # + Optional( - (LOPBRACK + delimitedList(rule, ",")("instantiations") + ROPBRACK) - ) - ).setParseAction(lambda t: Typename(t.namespaces_name, t.instantiations)) + (LOPBRACK + delimitedList(rule, ",")("instantiations") + ROPBRACK)) + ).setParseAction(lambda t: Typename(t.namespaces_and_name, t.instantiations)) - def __init__(self, namespaces_name, instantiations=()): - self.namespaces = namespaces_name[:-1] - self.name = namespaces_name[-1] + def __init__(self, + namespaces_and_name: ParseResults, + instantiations: Union[tuple, list, str, ParseResults] = ()): + self.name = namespaces_and_name[-1] # the name is the last element in this list + self.namespaces = namespaces_and_name[:-1] if instantiations: - if not isinstance(instantiations, typing.Iterable): - self.instantiations = instantiations.asList() + if isinstance(instantiations, Iterable): + self.instantiations = instantiations # type: ignore else: - self.instantiations = instantiations + self.instantiations = instantiations.asList() else: self.instantiations = [] @@ -108,21 +123,21 @@ class Typename: self.namespaces = ["gtsam"] @staticmethod - def from_parse_result(parse_result): - """Return the typename from the parsed result.""" + def from_parse_result(parse_result: Union[str, list]): + """Unpack the parsed result to get the Typename instance.""" return parse_result[0] - def __repr__(self): + def __repr__(self) -> str: return self.to_cpp() - def instantiated_name(self): + def instantiated_name(self) -> str: """Get the instantiated name of the type.""" res = self.name for instantiation in self.instantiations: res += instantiation.instantiated_name() return res - def to_cpp(self): + def to_cpp(self) -> str: """Generate the C++ code for wrapping.""" idx = 1 if self.namespaces and not self.namespaces[0] else 0 if self.instantiations: @@ -137,93 +152,111 @@ class Typename: cpp_name, ) - def __eq__(self, other): + def __eq__(self, other) -> bool: if isinstance(other, Typename): return str(self) == str(other) else: - return NotImplemented + return False - def __ne__(self, other): + def __ne__(self, other) -> bool: res = self.__eq__(other) - if res is NotImplemented: - return res return not res -class Type: - """ - The type value that is parsed, e.g. void, string, size_t. - """ - class _QualifiedType: - """ - Type with qualifiers. - """ - - rule = ( - Optional(CONST("is_const")) - + Typename.rule("typename") - + Optional(POINTER("is_ptr") | REF("is_ref")) - ).setParseAction( - lambda t: Type._QualifiedType( - Typename.from_parse_result(t.typename), - t.is_const, - t.is_ptr, - t.is_ref, - ) - ) - - def __init__(self, typename, is_const, is_ptr, is_ref): - self.typename = typename - self.is_const = is_const - self.is_ptr = is_ptr - self.is_ref = is_ref - - class _BasisType: - """ - Basis types don't have qualifiers and only allow copy-by-value. - """ - - rule = Or(BASIS_TYPES).setParseAction(lambda t: Typename(t)) +class QualifiedType: + """Type with qualifiers, such as `const`.""" rule = ( - _BasisType.rule("basis") | _QualifiedType.rule("qualified") # BR + Typename.rule("typename") # + + Optional(SHARED_POINTER("is_shared_ptr") | RAW_POINTER("is_ptr") | REF("is_ref")) + ).setParseAction( + lambda t: QualifiedType(t) + ) + + def __init__(self, t: ParseResults): + self.typename = Typename.from_parse_result(t.typename) + self.is_shared_ptr = t.is_shared_ptr + self.is_ptr = t.is_ptr + self.is_ref = t.is_ref + +class BasisType: + """ + Basis types are the built-in types in C++ such as double, int, char, etc. + + When using templates, the basis type will take on the same form as the template. + + E.g. + ``` + template + void func(const T& x); + ``` + + will give + + ``` + m_.def("CoolFunctionDoubleDouble",[](const double& s) { + return wrap_example::CoolFunction(s); + }, py::arg("s")); + ``` + """ + + rule = ( + Or(BASIS_TYPES)("typename") # + + Optional(SHARED_POINTER("is_shared_ptr") | RAW_POINTER("is_ptr") | REF("is_ref")) # + ).setParseAction(lambda t: BasisType(t)) + + def __init__(self, t: ParseResults): + self.typename = Typename([t.typename]) + self.is_ptr = t.is_ptr + self.is_shared_ptr = t.is_shared_ptr + self.is_ref = t.is_ref + +class Type: + """The type value that is parsed, e.g. void, string, size_t.""" + rule = ( + Optional(CONST("is_const")) # + + (BasisType.rule("basis") | QualifiedType.rule("qualified")) # BR ).setParseAction(lambda t: Type.from_parse_result(t)) - def __init__(self, typename, is_const, is_ptr, is_ref, is_basis): + def __init__(self, typename: Typename, is_const: str, is_shared_ptr: str, + is_ptr: str, is_ref: str, is_basis: bool): self.typename = typename self.is_const = is_const + self.is_shared_ptr = is_shared_ptr self.is_ptr = is_ptr self.is_ref = is_ref self.is_basis = is_basis @staticmethod - def from_parse_result(t): + def from_parse_result(t: ParseResults): """Return the resulting Type from parsing the source.""" if t.basis: return Type( - typename=t.basis, - is_const='', - is_ptr='', - is_ref='', + typename=t.basis.typename, + is_const=t.is_const, + is_shared_ptr=t.basis.is_shared_ptr, + is_ptr=t.basis.is_ptr, + is_ref=t.basis.is_ref, is_basis=True, ) elif t.qualified: return Type( typename=t.qualified.typename, - is_const=t.qualified.is_const, + is_const=t.is_const, + is_shared_ptr=t.qualified.is_shared_ptr, is_ptr=t.qualified.is_ptr, is_ref=t.qualified.is_ref, is_basis=False, ) else: - raise ValueError("Parse result is not a Type?") + raise ValueError("Parse result is not a Type") - def __repr__(self): - return '{} {}{}{}'.format( - self.typename, self.is_const, self.is_ptr, self.is_ref - ) + def __repr__(self) -> str: + return "{self.typename} " \ + "{self.is_const}{self.is_shared_ptr}{self.is_ptr}{self.is_ref}".format( + self=self) - def to_cpp(self, use_boost): + def to_cpp(self, use_boost: bool) -> str: """ Generate the C++ code for wrapping. @@ -231,26 +264,24 @@ class Type: Treat Matrix and Vector as "const Matrix&" and "const Vector&" resp. """ shared_ptr_ns = "boost" if use_boost else "std" - return ( - "{const} {shared_ptr}{typename}" - "{shared_ptr_ropbracket}{ref}".format( - const="const" - if self.is_const - or self.is_ptr - or self.typename.name in ["Matrix", "Vector"] - else "", - typename=self.typename.to_cpp(), - shared_ptr="{}::shared_ptr<".format(shared_ptr_ns) - if self.is_ptr - else "", - shared_ptr_ropbracket=">" if self.is_ptr else "", - ref="&" - if self.is_ref - or self.is_ptr - or self.typename.name in ["Matrix", "Vector"] - else "", - ) - ) + + if self.is_shared_ptr: + # always pass by reference: https://stackoverflow.com/a/8741626/1236990 + typename = "{ns}::shared_ptr<{typename}>&".format( + ns=shared_ptr_ns, typename=self.typename.to_cpp()) + elif self.is_ptr: + typename = "{typename}*".format(typename=self.typename.to_cpp()) + elif self.is_ref or self.typename.name in ["Matrix", "Vector"]: + typename = typename = "{typename}&".format( + typename=self.typename.to_cpp()) + else: + typename = self.typename.to_cpp() + + return ("{const}{typename}".format( + const="const " if + (self.is_const + or self.typename.name in ["Matrix", "Vector"]) else "", + typename=typename)) class Argument: @@ -259,18 +290,18 @@ class Argument: E.g. ``` - void sayHello(/*s is the method argument with type `const string&`*/ const string& s); + void sayHello(/*`s` is the method argument with type `const string&`*/ const string& s); ``` """ - rule = (Type.rule("ctype") + IDENT("name")).setParseAction( - lambda t: Argument(t.ctype, t.name) - ) + rule = (Type.rule("ctype") + + IDENT("name")).setParseAction(lambda t: Argument(t.ctype, t.name)) - def __init__(self, ctype, name): + def __init__(self, ctype: Type, name: str): self.ctype = ctype self.name = name + self.parent: Union[ArgumentList, None] = None - def __repr__(self): + def __repr__(self) -> str: return '{} {}'.format(self.ctype.__repr__(), self.name) @@ -282,27 +313,32 @@ class ArgumentList: lambda t: ArgumentList.from_parse_result(t.args_list) ) - def __init__(self, args_list): + def __init__(self, args_list: List[Argument]): self.args_list = args_list for arg in args_list: arg.parent = self + self.parent: Union[Method, StaticMethod, Template, Constructor, + GlobalFunction, None] = None @staticmethod - def from_parse_result(parse_result): + def from_parse_result(parse_result: ParseResults): """Return the result of parsing.""" if parse_result: return ArgumentList(parse_result.asList()) else: return ArgumentList([]) - def __repr__(self): + def __repr__(self) -> str: return self.args_list.__repr__() - def args_names(self): + def __len__(self) -> int: + return len(self.args_list) + + def args_names(self) -> List[str]: """Return a list of the names of all the arguments.""" return [arg.name for arg in self.args_list] - def to_cpp(self, use_boost): + def to_cpp(self, use_boost: bool) -> List[str]: """Generate the C++ code for wrapping.""" return [arg.ctype.to_cpp(use_boost) for arg in self.args_list] @@ -314,40 +350,44 @@ class ReturnType: The return type can either be a single type or a pair such as . """ _pair = ( - PAIR.suppress() - + LOPBRACK - + Type.rule("type1") - + COMMA - + Type.rule("type2") - + ROPBRACK + PAIR.suppress() # + + LOPBRACK # + + Type.rule("type1") # + + COMMA # + + Type.rule("type2") # + + ROPBRACK # ) rule = (_pair ^ Type.rule("type1")).setParseAction( # BR - lambda t: ReturnType(t.type1, t.type2) - ) + lambda t: ReturnType(t.type1, t.type2)) - def __init__(self, type1, type2): + def __init__(self, type1: Type, type2: Type): self.type1 = type1 self.type2 = type2 + self.parent: Union[Method, StaticMethod, GlobalFunction, None] = None - def is_void(self): + def is_void(self) -> bool: """ Check if the return type is void. """ return self.type1.typename.name == "void" and not self.type2 - def __repr__(self): + def __repr__(self) -> str: return "{}{}".format( - self.type1, (', ' + self.type2.__repr__()) if self.type2 else '' - ) + self.type1, (', ' + self.type2.__repr__()) if self.type2 else '') - def to_cpp(self): - """Generate the C++ code for wrapping.""" + def to_cpp(self, use_boost: bool) -> str: + """ + Generate the C++ code for wrapping. + + If there are two return types, we return a pair<>, + otherwise we return the regular return type. + """ if self.type2: return "std::pair<{type1},{type2}>".format( - type1=self.type1.to_cpp(), type2=self.type2.to_cpp() - ) + type1=self.type1.to_cpp(use_boost), + type2=self.type2.to_cpp(use_boost)) else: - return self.type1.to_cpp() + return self.type1.to_cpp(use_boost) class Template: @@ -365,20 +405,16 @@ class Template: template // POSE is the Instantiation. """ rule = ( - IDENT("typename") - + Optional( - EQUAL - + LBRACE - + ((delimitedList(Typename.rule)("instantiations"))) - + RBRACE - ) - ).setParseAction( - lambda t: Template.TypenameAndInstantiations( - t.typename, t.instantiations - ) - ) + IDENT("typename") # + + Optional( # + EQUAL # + + LBRACE # + + ((delimitedList(Typename.rule)("instantiations"))) # + + RBRACE # + )).setParseAction(lambda t: Template.TypenameAndInstantiations( + t.typename, t.instantiations)) - def __init__(self, typename, instantiations): + def __init__(self, typename: str, instantiations: ParseResults): self.typename = typename if instantiations: @@ -387,22 +423,20 @@ class Template: self.instantiations = [] rule = ( # BR - TEMPLATE - + LOPBRACK + TEMPLATE # + + LOPBRACK # + delimitedList(TypenameAndInstantiations.rule)( - "typename_and_instantiations_list" - ) + "typename_and_instantiations_list") # + ROPBRACK # BR ).setParseAction( - lambda t: Template(t.typename_and_instantiations_list.asList()) - ) + lambda t: Template(t.typename_and_instantiations_list.asList())) - def __init__(self, typename_and_instantiations_list): + def __init__(self, typename_and_instantiations_list: List[TypenameAndInstantiations]): ti_list = typename_and_instantiations_list self.typenames = [ti.typename for ti in ti_list] self.instantiations = [ti.instantiations for ti in ti_list] - def __repr__(self): + def __repr__(self) -> str: return "<{0}>".format(", ".join(self.typenames)) @@ -418,21 +452,24 @@ class Method: ``` """ rule = ( - Optional(Template.rule("template")) - + ReturnType.rule("return_type") - + IDENT("name") - + LPAREN - + ArgumentList.rule("args_list") - + RPAREN - + Optional(CONST("is_const")) + Optional(Template.rule("template")) # + + ReturnType.rule("return_type") # + + IDENT("name") # + + LPAREN # + + ArgumentList.rule("args_list") # + + RPAREN # + + Optional(CONST("is_const")) # + SEMI_COLON # BR - ).setParseAction( - lambda t: Method( - t.template, t.name, t.return_type, t.args_list, t.is_const - ) - ) + ).setParseAction(lambda t: Method(t.template, t.name, t.return_type, t. + args_list, t.is_const)) - def __init__(self, template, name, return_type, args, is_const, parent=''): + def __init__(self, + template: str, + name: str, + return_type: ReturnType, + args: ArgumentList, + is_const: str, + parent: Union[str, "Class"] = ''): self.template = template self.name = name self.return_type = return_type @@ -441,7 +478,7 @@ class Method: self.parent = parent - def __repr__(self): + def __repr__(self) -> str: return "Method: {} {} {}({}){}".format( self.template, self.return_type, @@ -463,28 +500,31 @@ class StaticMethod: ``` """ rule = ( - STATIC - + ReturnType.rule("return_type") - + IDENT("name") - + LPAREN - + ArgumentList.rule("args_list") - + RPAREN + STATIC # + + ReturnType.rule("return_type") # + + IDENT("name") # + + LPAREN # + + ArgumentList.rule("args_list") # + + RPAREN # + SEMI_COLON # BR ).setParseAction( - lambda t: StaticMethod(t.name, t.return_type, t.args_list) - ) + lambda t: StaticMethod(t.name, t.return_type, t.args_list)) - def __init__(self, name, return_type, args, parent=''): + def __init__(self, + name: str, + return_type: ReturnType, + args: ArgumentList, + parent: Union[str, "Class"] = ''): self.name = name self.return_type = return_type self.args = args self.parent = parent - def __repr__(self): + def __repr__(self) -> str: return "static {} {}{}".format(self.return_type, self.name, self.args) - def to_cpp(self): + def to_cpp(self) -> str: """Generate the C++ code for wrapping.""" return self.name @@ -495,20 +535,20 @@ class Constructor: Can have 0 or more arguments. """ rule = ( - IDENT("name") - + LPAREN - + ArgumentList.rule("args_list") - + RPAREN + IDENT("name") # + + LPAREN # + + ArgumentList.rule("args_list") # + + RPAREN # + SEMI_COLON # BR ).setParseAction(lambda t: Constructor(t.name, t.args_list)) - def __init__(self, name, args, parent=''): + def __init__(self, name: str, args: ArgumentList, parent: Union["Class", str] =''): self.name = name self.args = args self.parent = parent - def __repr__(self): + def __repr__(self) -> str: return "Constructor: {}".format(self.name) @@ -523,21 +563,28 @@ class Property: }; ```` """ - rule = (Type.rule("ctype") + IDENT("name") + SEMI_COLON).setParseAction( - lambda t: Property(t.ctype, t.name) - ) + rule = ( + Type.rule("ctype") # + + IDENT("name") # + + SEMI_COLON # + ).setParseAction(lambda t: Property(t.ctype, t.name)) - def __init__(self, ctype, name, parent=''): + def __init__(self, ctype: Type, name: str, parent=''): self.ctype = ctype self.name = name self.parent = parent - def __repr__(self): + def __repr__(self) -> str: return '{} {}'.format(self.ctype.__repr__(), self.name) def collect_namespaces(obj): - """Get the chain of namespaces from the lowest to highest for the given object.""" + """ + Get the chain of namespaces from the lowest to highest for the given object. + + Args: + obj: Object of type Namespace, Class or InstantiatedClass. + """ namespaces = [] ancestor = obj.parent while ancestor and ancestor.name: @@ -565,7 +612,8 @@ class Class: Constructor.rule ^ StaticMethod.rule ^ Method.rule ^ Property.rule ).setParseAction(lambda t: Class.MethodsAndProperties(t.asList())) - def __init__(self, methods_props): + def __init__(self, methods_props: List[Union[Constructor, Method, + StaticMethod, Property]]): self.ctors = [] self.methods = [] self.static_methods = [] @@ -582,39 +630,37 @@ class Class: _parent = COLON + Typename.rule("parent_class") rule = ( - Optional(Template.rule("template")) - + Optional(VIRTUAL("is_virtual")) - + CLASS - + IDENT("name") - + Optional(_parent) - + LBRACE - + MethodsAndProperties.rule("methods_props") - + RBRACE + Optional(Template.rule("template")) # + + Optional(VIRTUAL("is_virtual")) # + + CLASS # + + IDENT("name") # + + Optional(_parent) # + + LBRACE # + + MethodsAndProperties.rule("methods_props") # + + RBRACE # + SEMI_COLON # BR - ).setParseAction( - lambda t: Class( - t.template, - t.is_virtual, - t.name, - t.parent_class, - t.methods_props.ctors, - t.methods_props.methods, - t.methods_props.static_methods, - t.methods_props.properties, - ) - ) + ).setParseAction(lambda t: Class( + t.template, + t.is_virtual, + t.name, + t.parent_class, + t.methods_props.ctors, + t.methods_props.methods, + t.methods_props.static_methods, + t.methods_props.properties, + )) def __init__( self, - template, - is_virtual, - name, - parent_class, - ctors, - methods, - static_methods, - properties, - parent='', + template: Template, + is_virtual: str, + name: str, + parent_class: list, + ctors: List[Constructor], + methods: List[Method], + static_methods: List[StaticMethod], + properties: List[Property], + parent: str = '', ): self.template = template self.is_virtual = is_virtual @@ -647,10 +693,13 @@ class Class: for _property in self.properties: _property.parent = self - def namespaces(self): + def namespaces(self) -> list: """Get the namespaces which this class is nested under as a list.""" return collect_namespaces(self) + def __repr__(self): + return "Class: {self.name}".format(self=self) + class TypedefTemplateInstantiation: """ @@ -669,7 +718,7 @@ class TypedefTemplateInstantiation: ) ) - def __init__(self, typename, new_name, parent=''): + def __init__(self, typename: Typename, new_name: str, parent: str=''): self.typename = typename self.new_name = new_name self.parent = parent @@ -683,11 +732,11 @@ class Include: INCLUDE + LOPBRACK + CharsNotIn('>')("header") + ROPBRACK ).setParseAction(lambda t: Include(t.header)) - def __init__(self, header, parent=''): + def __init__(self, header: CharsNotIn, parent: str = ''): self.header = header self.parent = parent - def __repr__(self): + def __repr__(self) -> str: return "#include <{}>".format(self.header) @@ -702,22 +751,26 @@ class ForwardDeclaration: + Optional(COLON + Typename.rule("parent_type")) + SEMI_COLON ).setParseAction( - lambda t: ForwardDeclaration(t.is_virtual, t.name, t.parent_type) + lambda t: ForwardDeclaration(t.name, t.parent_type, t.is_virtual) ) - def __init__(self, is_virtual, name, parent_type, parent=''): - self.is_virtual = is_virtual + def __init__(self, + name: Typename, + parent_type: str, + is_virtual: str, + parent: str = ''): self.name = name if parent_type: self.parent_type = Typename.from_parse_result(parent_type) else: self.parent_type = '' + + self.is_virtual = is_virtual self.parent = parent - def __repr__(self): - return "ForwardDeclaration: {} {}({})".format( - self.is_virtual, self.name, self.parent - ) + def __repr__(self) -> str: + return "ForwardDeclaration: {} {}({})".format(self.is_virtual, + self.name, self.parent) class GlobalFunction: @@ -725,37 +778,43 @@ class GlobalFunction: Rule to parse functions defined in the global scope. """ rule = ( - ReturnType.rule("return_type") - + IDENT("name") - + LPAREN - + ArgumentList.rule("args_list") - + RPAREN - + SEMI_COLON - ).setParseAction( - lambda t: GlobalFunction(t.name, t.return_type, t.args_list) - ) + Optional(Template.rule("template")) + + ReturnType.rule("return_type") # + + IDENT("name") # + + LPAREN # + + ArgumentList.rule("args_list") # + + RPAREN # + + SEMI_COLON # + ).setParseAction(lambda t: GlobalFunction(t.name, t.return_type, t. + args_list, t.template)) - def __init__(self, name, return_type, args_list, parent=''): + def __init__(self, + name: str, + return_type: ReturnType, + args_list: ArgumentList, + template: Template, + parent: str = ''): self.name = name self.return_type = return_type self.args = args_list - self.is_const = None + self.template = template self.parent = parent self.return_type.parent = self self.args.parent = self - def __repr__(self): + def __repr__(self) -> str: return "GlobalFunction: {}{}({})".format( self.return_type, self.name, self.args ) - def to_cpp(self): + def to_cpp(self) -> str: """Generate the C++ code for wrapping.""" return self.name -def find_sub_namespace(namespace, str_namespaces): +def find_sub_namespace(namespace: "Namespace", + str_namespaces: List["Namespace"]) -> list: """ Get the namespaces nested under `namespace`, filtered by a list of namespace strings. @@ -774,7 +833,7 @@ def find_sub_namespace(namespace, str_namespaces): ns for ns in sub_namespaces if ns.name == str_namespaces[0] ] if not found_namespaces: - return None + return [] res = [] for found_namespace in found_namespaces: @@ -786,25 +845,24 @@ def find_sub_namespace(namespace, str_namespaces): class Namespace: """Rule for parsing a namespace in the interface file.""" + rule = Forward() rule << ( - NAMESPACE - + IDENT("name") - + LBRACE + NAMESPACE # + + IDENT("name") # + + LBRACE # + ZeroOrMore( # BR - ForwardDeclaration.rule - ^ Include.rule - ^ Class.rule - ^ TypedefTemplateInstantiation.rule - ^ GlobalFunction.rule - ^ rule - )( - "content" - ) # BR - + RBRACE + ForwardDeclaration.rule # + ^ Include.rule # + ^ Class.rule # + ^ TypedefTemplateInstantiation.rule # + ^ GlobalFunction.rule # + ^ rule # + )("content") # BR + + RBRACE # ).setParseAction(lambda t: Namespace.from_parse_result(t)) - def __init__(self, name, content, parent=''): + def __init__(self, name: str, content: ZeroOrMore, parent=''): self.name = name self.content = content self.parent = parent @@ -812,7 +870,7 @@ class Namespace: child.parent = self @staticmethod - def from_parse_result(t): + def from_parse_result(t: ParseResults): """Return the result of parsing.""" if t.content: content = t.content.asList() @@ -820,16 +878,18 @@ class Namespace: content = [] return Namespace(t.name, content) - def find_class(self, typename): + def find_class_or_function( + self, typename: Typename) -> Union[Class, GlobalFunction]: """ - Find the Class object given its typename. + Find the Class or GlobalFunction object given its typename. We have to traverse the tree of namespaces. """ found_namespaces = find_sub_namespace(self, typename.namespaces) res = [] for namespace in found_namespaces: - classes = (c for c in namespace.content if isinstance(c, Class)) - res += [c for c in classes if c.name == typename.name] + classes_and_funcs = (c for c in namespace.content + if isinstance(c, (Class, GlobalFunction))) + res += [c for c in classes_and_funcs if c.name == typename.name] if not res: raise ValueError( "Cannot find class {} in module!".format(typename.name) @@ -843,17 +903,17 @@ class Namespace: else: return res[0] - def top_level(self): + def top_level(self) -> "Namespace": """Return the top leve namespace.""" if self.name == '' or self.parent == '': return self else: return self.parent.top_level() - def __repr__(self): + def __repr__(self) -> str: return "Namespace: {}\n\t{}".format(self.name, self.content) - def full_namespaces(self): + def full_namespaces(self) -> List["Namespace"]: """Get the full namespace list.""" ancestors = collect_namespaces(self) if self.name: @@ -874,20 +934,18 @@ class Module: """ rule = ( - ZeroOrMore( - ForwardDeclaration.rule - ^ Include.rule - ^ Class.rule - ^ TypedefTemplateInstantiation.rule - ^ GlobalFunction.rule - ^ Namespace.rule - ).setParseAction(lambda t: Namespace('', t.asList())) - + stringEnd - ) + ZeroOrMore(ForwardDeclaration.rule # + ^ Include.rule # + ^ Class.rule # + ^ TypedefTemplateInstantiation.rule # + ^ GlobalFunction.rule # + ^ Namespace.rule # + ).setParseAction(lambda t: Namespace('', t.asList())) + + stringEnd) rule.ignore(cppStyleComment) @staticmethod - def parseString(s: str): + def parseString(s: str) -> ParseResults: """Parse the source string and apply the rules.""" return Module.rule.parseString(s)[0] diff --git a/gtwrap/matlab_wrapper.py b/gtwrap/matlab_wrapper.py index aeaf221bd..439a61fb4 100755 --- a/gtwrap/matlab_wrapper.py +++ b/gtwrap/matlab_wrapper.py @@ -1,13 +1,20 @@ +""" +Code to use the parsed results and convert it to a format +that Matlab's MEX compiler can use. +""" + +# pylint: disable=too-many-lines, no-self-use, too-many-arguments, too-many-branches, too-many-statements + import os -import argparse +import os.path as osp +import sys import textwrap +from functools import partial, reduce +from typing import Dict, Iterable, List, Union import gtwrap.interface_parser as parser import gtwrap.template_instantiator as instantiator -from functools import reduce -from functools import partial - class MatlabWrapper(object): """ Wrap the given C++ code into Matlab. @@ -18,9 +25,8 @@ class MatlabWrapper(object): top_module_namespace: C++ namespace for the top module (default '') ignore_classes: A list of classes to ignore (default []) """ - """Map the data type to its Matlab class. - Found in Argument.cpp in old wrapper - """ + # Map the data type to its Matlab class. + # Found in Argument.cpp in old wrapper data_type = { 'string': 'char', 'char': 'char', @@ -31,9 +37,8 @@ class MatlabWrapper(object): 'size_t': 'numeric', 'bool': 'logical' } - """Map the data type into the type used in Matlab methods. - Found in matlab.h in old wrapper - """ + # Map the data type into the type used in Matlab methods. + # Found in matlab.h in old wrapper data_type_param = { 'string': 'char', 'char': 'char', @@ -47,34 +52,35 @@ class MatlabWrapper(object): 'Matrix': 'double', 'bool': 'bool' } - """Methods that should not be wrapped directly""" + # Methods that should not be wrapped directly whitelist = ['serializable', 'serialize'] - """Methods that should be ignored""" + # Methods that should be ignored ignore_methods = ['pickle'] - """Datatypes that do not need to be checked in methods""" - not_check_type = [] - """Data types that are primitive types""" + # Datatypes that do not need to be checked in methods + not_check_type: list = [] + # Data types that are primitive types not_ptr_type = ['int', 'double', 'bool', 'char', 'unsigned char', 'size_t'] - """Ignore the namespace for these datatypes""" + # Ignore the namespace for these datatypes ignore_namespace = ['Matrix', 'Vector', 'Point2', 'Point3'] - """The amount of times the wrapper has created a call to - geometry_wrapper - """ + # The amount of times the wrapper has created a call to geometry_wrapper wrapper_id = 0 - """Map each wrapper id to what its collector function namespace, class, - type, and string format""" - wrapper_map = {} - """Set of all the includes in the namespace""" - includes = {} - """Set of all classes in the namespace""" - classes = [] - classes_elems = {} - """Id for ordering global functions in the wrapper""" + # Map each wrapper id to what its collector function namespace, class, type, and string format + wrapper_map: dict = {} + # Set of all the includes in the namespace + includes: Dict[parser.Include, int] = {} + # Set of all classes in the namespace + classes: List[Union[parser.Class, instantiator.InstantiatedClass]] = [] + classes_elems: Dict[Union[parser.Class, instantiator.InstantiatedClass], int] = {} + # Id for ordering global functions in the wrapper global_function_id = 0 - """Files and their content""" - content = [] + # Files and their content + content: List[str] = [] - def __init__(self, module, module_name, top_module_namespace='', ignore_classes=[]): + def __init__(self, + module, + module_name, + top_module_namespace='', + ignore_classes=()): self.module = module self.module_name = module_name self.top_module_namespace = top_module_namespace @@ -84,7 +90,6 @@ class MatlabWrapper(object): def _debug(self, message): if not self.verbose: return - import sys print(message, file=sys.stderr) def _add_include(self, include): @@ -110,7 +115,8 @@ class MatlabWrapper(object): the current wrapper id """ if collector_function is not None: - is_instantiated_class = isinstance(collector_function[1], instantiator.InstantiatedClass) + is_instantiated_class = isinstance(collector_function[1], + instantiator.InstantiatedClass) if is_instantiated_class: function_name = collector_function[0] + \ @@ -118,9 +124,10 @@ class MatlabWrapper(object): else: function_name = collector_function[1].name - self.wrapper_map[self.wrapper_id] = (collector_function[0], collector_function[1], collector_function[2], - function_name + '_' + str(self.wrapper_id + id_diff), - collector_function[3]) + self.wrapper_map[self.wrapper_id] = ( + collector_function[0], collector_function[1], + collector_function[2], function_name + '_' + + str(self.wrapper_id + id_diff), collector_function[3]) self.wrapper_id += 1 @@ -138,13 +145,25 @@ class MatlabWrapper(object): """ return x + '\n' + ('' if y == '' else ' ') + y - def _is_ptr(self, arg_type): - """Determine if the interface_parser.Type should be treated as a - pointer in the wrapper. + def _is_shared_ptr(self, arg_type): """ - return arg_type.is_ptr or (arg_type.typename.name not in self.not_ptr_type - and arg_type.typename.name not in self.ignore_namespace - and arg_type.typename.name != 'string') + Determine if the `interface_parser.Type` should be treated as a + shared pointer in the wrapper. + """ + return arg_type.is_shared_ptr or ( + arg_type.typename.name not in self.not_ptr_type + and arg_type.typename.name not in self.ignore_namespace + and arg_type.typename.name != 'string') + + def _is_ptr(self, arg_type): + """ + Determine if the `interface_parser.Type` should be treated as a + raw pointer in the wrapper. + """ + return arg_type.is_ptr or ( + arg_type.typename.name not in self.not_ptr_type + and arg_type.typename.name not in self.ignore_namespace + and arg_type.typename.name != 'string') def _is_ref(self, arg_type): """Determine if the interface_parser.Type should be treated as a @@ -166,7 +185,8 @@ class MatlabWrapper(object): method_map[method.name] = len(method_out) method_out.append([method]) else: - self._debug("[_group_methods] Merging {} with {}".format(method_index, method.name)) + self._debug("[_group_methods] Merging {} with {}".format( + method_index, method.name)) method_out[method_index].append(method) return method_out @@ -181,7 +201,12 @@ class MatlabWrapper(object): return instantiated_class.name @classmethod - def _format_type_name(cls, type_name, separator='::', include_namespace=True, constructor=False, method=False): + def _format_type_name(cls, + type_name, + separator='::', + include_namespace=True, + constructor=False, + method=False): """ Args: type_name: an interface_parser.Typename to reformat @@ -194,7 +219,8 @@ class MatlabWrapper(object): constructor and method cannot both be true """ if constructor and method: - raise Exception('Constructor and method parameters cannot both be True') + raise Exception( + 'Constructor and method parameters cannot both be True') formatted_type_name = '' name = type_name.name @@ -204,7 +230,7 @@ class MatlabWrapper(object): if name not in cls.ignore_namespace and namespace != '': formatted_type_name += namespace + separator - #self._debug("formatted_ns: {}, ns: {}".format(formatted_type_name, type_name.namespaces)) + #self._debug("formatted_ns: {}, ns: {}".format(formatted_type_name, type_name.namespaces)) if constructor: formatted_type_name += cls.data_type.get(name) or name elif method: @@ -215,9 +241,11 @@ class MatlabWrapper(object): if separator == "::": # C++ templates = [] for idx in range(len(type_name.instantiations)): - template = '{}'.format(cls._format_type_name(type_name.instantiations[idx], - include_namespace=include_namespace, - constructor=constructor, method=method)) + template = '{}'.format( + cls._format_type_name(type_name.instantiations[idx], + include_namespace=include_namespace, + constructor=constructor, + method=method)) templates.append(template) if len(templates) > 0: # If there are no templates @@ -225,17 +253,20 @@ class MatlabWrapper(object): else: for idx in range(len(type_name.instantiations)): - formatted_type_name += '{}'.format(cls._format_type_name( - type_name.instantiations[idx], - separator=separator, - include_namespace=False, - constructor=constructor, method=method - )) + formatted_type_name += '{}'.format( + cls._format_type_name(type_name.instantiations[idx], + separator=separator, + include_namespace=False, + constructor=constructor, + method=method)) return formatted_type_name @classmethod - def _format_return_type(cls, return_type, include_namespace=False, separator="::"): + def _format_return_type(cls, + return_type, + include_namespace=False, + separator="::"): """Format return_type. Args: @@ -248,16 +279,17 @@ class MatlabWrapper(object): return_wrap = cls._format_type_name( return_type.type1.typename, separator=separator, - include_namespace=include_namespace - ) + include_namespace=include_namespace) else: return_wrap = 'pair< {type1}, {type2} >'.format( type1=cls._format_type_name( - return_type.type1.typename, separator=separator, include_namespace=include_namespace - ), + return_type.type1.typename, + separator=separator, + include_namespace=include_namespace), type2=cls._format_type_name( - return_type.type2.typename, separator=separator, include_namespace=include_namespace - )) + return_type.type2.typename, + separator=separator, + include_namespace=include_namespace)) return return_wrap @@ -273,7 +305,8 @@ class MatlabWrapper(object): # class_name += separator # # class_name += instantiated_class.name - parentname = "".join([separator + x for x in parent_full_ns]) + separator + parentname = "".join([separator + x + for x in parent_full_ns]) + separator class_name = parentname[2 * len(separator):] @@ -302,11 +335,16 @@ class MatlabWrapper(object): method = '' if isinstance(instance_method, instantiator.InstantiatedMethod): - method += "".join([separator + x for x in instance_method.parent.parent.full_namespaces()]) + \ - separator + method_list = [ + separator + x + for x in instance_method.parent.parent.full_namespaces() + ] + method += "".join(method_list) + separator + + method += instance_method.parent.name + separator + method += instance_method.original.name + method += "<" + instance_method.instantiation.to_cpp() + ">" - method += instance_method.parent.name + separator + \ - instance_method.original.name + "<" + instance_method.instantiation.to_cpp() + ">" return method[2 * len(separator):] def _format_global_method(self, static_method, separator=''): @@ -332,11 +370,13 @@ class MatlabWrapper(object): arg_wrap = '' for i, arg in enumerate(args.args_list, 1): - c_type = self._format_type_name(arg.ctype.typename, include_namespace=False) + c_type = self._format_type_name(arg.ctype.typename, + include_namespace=False) - arg_wrap += '{c_type} {arg_name}{comma}'.format(c_type=c_type, - arg_name=arg.name, - comma='' if i == len(args.args_list) else ', ') + arg_wrap += '{c_type} {arg_name}{comma}'.format( + c_type=c_type, + arg_name=arg.name, + comma='' if i == len(args.args_list) else ', ') return arg_wrap @@ -362,17 +402,26 @@ class MatlabWrapper(object): check_type = self.data_type[check_type] if check_type is None: - check_type = self._format_type_name(arg.ctype.typename, separator='.', constructor=not wrap_datatypes) + check_type = self._format_type_name( + arg.ctype.typename, + separator='.', + constructor=not wrap_datatypes) - var_arg_wrap += " && isa(varargin{{{num}}},'{data_type}')".format(num=i, data_type=check_type) + var_arg_wrap += " && isa(varargin{{{num}}},'{data_type}')".format( + num=i, data_type=check_type) if name == 'Vector': - var_arg_wrap += ' && size(varargin{{{num}}},2)==1'.format(num=i) + var_arg_wrap += ' && size(varargin{{{num}}},2)==1'.format( + num=i) if name == 'Point2': - var_arg_wrap += ' && size(varargin{{{num}}},1)==2'.format(num=i) - var_arg_wrap += ' && size(varargin{{{num}}},2)==1'.format(num=i) + var_arg_wrap += ' && size(varargin{{{num}}},1)==2'.format( + num=i) + var_arg_wrap += ' && size(varargin{{{num}}},2)==1'.format( + num=i) if name == 'Point3': - var_arg_wrap += ' && size(varargin{{{num}}},1)==3'.format(num=i) - var_arg_wrap += ' && size(varargin{{{num}}},2)==1'.format(num=i) + var_arg_wrap += ' && size(varargin{{{num}}},1)==3'.format( + num=i) + var_arg_wrap += ' && size(varargin{{{num}}},2)==1'.format( + num=i) return var_arg_wrap @@ -398,7 +447,8 @@ class MatlabWrapper(object): return var_list_wrap def _wrap_method_check_statement(self, args): - """Wrap the given arguments into either just a varargout call or a + """ + Wrap the given arguments into either just a varargout call or a call in an if statement that checks if the parameters are accurate. """ check_statement = '' @@ -409,7 +459,7 @@ class MatlabWrapper(object): 'if length(varargin) == {param_count}'.format( param_count=len(args.args_list)) - for i, arg in enumerate(args.args_list): + for _, arg in enumerate(args.args_list): name = arg.ctype.typename.name if name in self.not_check_type: @@ -422,18 +472,25 @@ class MatlabWrapper(object): check_type = self.data_type[check_type] if check_type is None: - check_type = self._format_type_name(arg.ctype.typename, separator='.') + check_type = self._format_type_name(arg.ctype.typename, + separator='.') - check_statement += " && isa(varargin{{{id}}},'{ctype}')".format(id=arg_id, ctype=check_type) + check_statement += " && isa(varargin{{{id}}},'{ctype}')".format( + id=arg_id, ctype=check_type) if name == 'Vector': - check_statement += ' && size(varargin{{{num}}},2)==1'.format(num=arg_id) + check_statement += ' && size(varargin{{{num}}},2)==1'.format( + num=arg_id) if name == 'Point2': - check_statement += ' && size(varargin{{{num}}},1)==2'.format(num=arg_id) - check_statement += ' && size(varargin{{{num}}},2)==1'.format(num=arg_id) + check_statement += ' && size(varargin{{{num}}},1)==2'.format( + num=arg_id) + check_statement += ' && size(varargin{{{num}}},2)==1'.format( + num=arg_id) if name == 'Point3': - check_statement += ' && size(varargin{{{num}}},1)==3'.format(num=arg_id) - check_statement += ' && size(varargin{{{num}}},2)==1'.format(num=arg_id) + check_statement += ' && size(varargin{{{num}}},1)==3'.format( + num=arg_id) + check_statement += ' && size(varargin{{{num}}},2)==1'.format( + num=arg_id) arg_id += 1 @@ -458,10 +515,9 @@ class MatlabWrapper(object): if params != '': params += ',' - # import sys - # print("type: {}, is_ref: {}, is_ref: {}".format(arg.ctype, self._is_ref(arg.ctype), arg.ctype.is_ref), file=sys.stderr) if self._is_ref(arg.ctype): # and not constructor: - ctype_camel = self._format_type_name(arg.ctype.typename, separator='') + ctype_camel = self._format_type_name(arg.ctype.typename, + separator='') body_args += textwrap.indent(textwrap.dedent('''\ {ctype}& {name} = *unwrap_shared_ptr< {ctype} >(in[{id}], "ptr_{ctype_camel}"); '''.format(ctype=self._format_type_name(arg.ctype.typename), @@ -469,23 +525,33 @@ class MatlabWrapper(object): name=arg.name, id=arg_id)), prefix=' ') - elif self._is_ptr(arg.ctype) and \ + + elif (self._is_shared_ptr(arg.ctype) or self._is_ptr(arg.ctype)) and \ arg.ctype.typename.name not in self.ignore_namespace: - call_type = arg.ctype.is_ptr + if arg.ctype.is_shared_ptr: + call_type = arg.ctype.is_shared_ptr + else: + call_type = arg.ctype.is_ptr + body_args += textwrap.indent(textwrap.dedent('''\ {std_boost}::shared_ptr<{ctype_sep}> {name} = unwrap_shared_ptr< {ctype_sep} >(in[{id}], "ptr_{ctype}"); '''.format(std_boost='boost' if constructor else 'boost', - ctype_sep=self._format_type_name(arg.ctype.typename), - ctype=self._format_type_name(arg.ctype.typename, separator=''), + ctype_sep=self._format_type_name( + arg.ctype.typename), + ctype=self._format_type_name(arg.ctype.typename, + separator=''), name=arg.name, id=arg_id)), prefix=' ') if call_type == "": params += "*" + else: body_args += textwrap.indent(textwrap.dedent('''\ {ctype} {name} = unwrap< {ctype} >(in[{id}]); - '''.format(ctype=arg.ctype.typename.name, name=arg.name, id=arg_id)), + '''.format(ctype=arg.ctype.typename.name, + name=arg.name, + id=arg_id)), prefix=' ') params += arg.name @@ -514,11 +580,11 @@ class MatlabWrapper(object): if comment_wrap == '': comment_wrap = '%-------Static Methods-------\n' - comment_wrap += '%{name}({args}) : returns {return_type}\n'.format(name=static_method.name, - args=self._wrap_args(static_method.args), - return_type=self._format_return_type( - static_method.return_type, - include_namespace=True)) + comment_wrap += '%{name}({args}) : returns {return_type}\n'.format( + name=static_method.name, + args=self._wrap_args(static_method.args), + return_type=self._format_return_type(static_method.return_type, + include_namespace=True)) comment_wrap += textwrap.dedent('''\ % @@ -553,7 +619,9 @@ class MatlabWrapper(object): # Write constructors for ctor in ctors: - comment += '%{ctor_name}({args})\n'.format(ctor_name=ctor.name, args=self._wrap_args(ctor.args)) + comment += '%{ctor_name}({args})\n'.format(ctor_name=ctor.name, + args=self._wrap_args( + ctor.args)) if len(methods) != 0: comment += '%\n' \ @@ -568,16 +636,22 @@ class MatlabWrapper(object): if method.name in self.ignore_methods: continue - comment += '%{name}({args})'.format(name=method.name, args=self._wrap_args(method.args)) + comment += '%{name}({args})'.format(name=method.name, + args=self._wrap_args( + method.args)) if method.return_type.type2 == '': - return_type = self._format_type_name(method.return_type.type1.typename) + return_type = self._format_type_name( + method.return_type.type1.typename) else: return_type = 'pair< {type1}, {type2} >'.format( - type1=self._format_type_name(method.return_type.type1.typename), - type2=self._format_type_name(method.return_type.type2.typename)) + type1=self._format_type_name( + method.return_type.type1.typename), + type2=self._format_type_name( + method.return_type.type2.typename)) - comment += ' : returns {return_type}\n'.format(return_type=return_type) + comment += ' : returns {return_type}\n'.format( + return_type=return_type) comment += '%\n' @@ -602,15 +676,16 @@ class MatlabWrapper(object): if not isinstance(methods, list): methods = [methods] - for method in methods: - output = '' + # for method in methods: + # output = '' return '' - def wrap_methods(self, methods, globals=False, global_ns=None): - """Wrap a sequence of methods. Groups methods with the same names - together. If globals is True then output every method into its own - file. + def wrap_methods(self, methods, global_funcs=False, global_ns=None): + """ + Wrap a sequence of methods. Groups methods with the same names + together. + If global_funcs is True then output every method into its own file. """ output = '' methods = self._group_methods(methods) @@ -619,14 +694,15 @@ class MatlabWrapper(object): if method in self.ignore_methods: continue - if globals: - self._debug("[wrap_methods] wrapping: {}..{}={}".format(method[0].parent.name, method[0].name, - type(method[0].parent.name))) + if global_funcs: + self._debug("[wrap_methods] wrapping: {}..{}={}".format( + method[0].parent.name, method[0].name, + type(method[0].parent.name))) method_text = self.wrap_global_function(method) - self.content.append( - ("".join(['+' + x + '/' - for x in global_ns.full_namespaces()[1:]])[:-1], [(method[0].name + '.m', method_text)])) + self.content.append(("".join([ + '+' + x + '/' for x in global_ns.full_namespaces()[1:] + ])[:-1], [(method[0].name + '.m', method_text)])) else: method_text = self.wrap_method(method) output += '' @@ -655,17 +731,18 @@ class MatlabWrapper(object): # Determine format of return and varargout statements return_type_formatted = self._format_return_type( - overload.return_type, - include_namespace=True, - separator="." - ) - varargout = self._format_varargout(overload.return_type, return_type_formatted) + overload.return_type, include_namespace=True, separator=".") + varargout = self._format_varargout(overload.return_type, + return_type_formatted) param_wrap += textwrap.indent(textwrap.dedent('''\ {varargout}{module_name}_wrapper({num}, varargin{{:}}); - ''').format(varargout=varargout, module_name=self.module_name, - num=self._update_wrapper_id(collector_function=(function[0].parent.name, function[i], - 'global_function', None))), + ''').format(varargout=varargout, + module_name=self.module_name, + num=self._update_wrapper_id( + collector_function=(function[0].parent.name, + function[i], 'global_function', + None))), prefix=' ') param_wrap += textwrap.indent(textwrap.dedent('''\ @@ -682,7 +759,8 @@ class MatlabWrapper(object): return global_function - def wrap_class_constructors(self, namespace_name, inst_class, parent_name, ctors, is_virtual): + def wrap_class_constructors(self, namespace_name, inst_class, parent_name, + ctors, is_virtual): """Wrap class constructor. Args: @@ -697,17 +775,9 @@ class MatlabWrapper(object): class_name = inst_class.name if has_parent: parent_name = self._format_type_name(parent_name, separator=".") - if type(ctors) != list: + if not isinstance(ctors, Iterable): ctors = [ctors] - # import sys - # if class_name: - # print("[Constructor] class: {} ns: {}" - # .format(class_name, - # inst_class.namespaces()) - # , file=sys.stderr) - # full_name = "".join(obj_type.full_namespaces()) + obj_type.name - methods_wrap = textwrap.indent(textwrap.dedent("""\ methods function obj = {class_name}(varargin) @@ -719,7 +789,8 @@ class MatlabWrapper(object): else: methods_wrap += ' if nargin == 2' - methods_wrap += " && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682)\n" + methods_wrap += " && isa(varargin{1}, 'uint64')" + methods_wrap += " && varargin{1} == uint64(5139824614673773682)\n" if is_virtual: methods_wrap += textwrap.indent(textwrap.dedent('''\ @@ -728,13 +799,15 @@ class MatlabWrapper(object): else my_ptr = {wrapper_name}({id}, varargin{{2}}); end - ''').format(wrapper_name=self._wrapper_name(), id=self._update_wrapper_id() + 1), + ''').format(wrapper_name=self._wrapper_name(), + id=self._update_wrapper_id() + 1), prefix=' ') else: methods_wrap += ' my_ptr = varargin{2};\n' - collector_base_id = self._update_wrapper_id((namespace_name, inst_class, 'collectorInsertAndMakeBase', None), - id_diff=-1 if is_virtual else 0) + collector_base_id = self._update_wrapper_id( + (namespace_name, inst_class, 'collectorInsertAndMakeBase', None), + id_diff=-1 if is_virtual else 0) methods_wrap += ' {ptr}{wrapper_name}({id}, my_ptr);\n' \ .format( @@ -751,10 +824,12 @@ class MatlabWrapper(object): elseif nargin == {len}{varargin} {ptr}{wrapper}({num}{comma}{var_arg}); ''').format(len=len(ctor.args.args_list), - varargin=self._wrap_variable_arguments(ctor.args, False), + varargin=self._wrap_variable_arguments( + ctor.args, False), ptr=wrapper_return, wrapper=self._wrapper_name(), - num=self._update_wrapper_id((namespace_name, inst_class, 'constructor', ctor)), + num=self._update_wrapper_id( + (namespace_name, inst_class, 'constructor', ctor)), comma='' if len(ctor.args.args_list) == 0 else ', ', var_arg=self._wrap_list_variable_arguments(ctor.args)), prefix=' ') @@ -762,8 +837,9 @@ class MatlabWrapper(object): base_obj = '' if has_parent: - self._debug("class: {} ns: {}".format(parent_name, self._format_class_name(inst_class.parent, - separator="."))) + self._debug("class: {} ns: {}".format( + parent_name, + self._format_class_name(inst_class.parent, separator="."))) if has_parent: base_obj = ' obj = obj@{parent_name}(uint64(5139824614673773682), base_ptr);'.format( @@ -772,7 +848,9 @@ class MatlabWrapper(object): if base_obj: base_obj = '\n' + base_obj - self._debug("class: {}, name: {}".format(inst_class.name, self._format_class_name(inst_class, separator="."))) + self._debug("class: {}, name: {}".format( + inst_class.name, self._format_class_name(inst_class, + separator="."))) methods_wrap += textwrap.indent(textwrap.dedent('''\ else error('Arguments do not match any overload of {class_name_doc} constructor'); @@ -781,8 +859,10 @@ class MatlabWrapper(object): end\n ''').format(namespace=namespace_name, d='' if namespace_name == '' else '.', - class_name_doc=self._format_class_name(inst_class, separator="."), - class_name=self._format_class_name(inst_class, separator=""), + class_name_doc=self._format_class_name(inst_class, + separator="."), + class_name=self._format_class_name(inst_class, + separator=""), base_obj=base_obj), prefix=' ') @@ -804,9 +884,11 @@ class MatlabWrapper(object): function delete(obj) {wrapper}({num}, obj.ptr_{class_name}); end\n - """).format(num=self._update_wrapper_id((namespace_name, inst_class, 'deconstructor', None)), + """).format(num=self._update_wrapper_id( + (namespace_name, inst_class, 'deconstructor', None)), wrapper=self._wrapper_name(), - class_name="".join(inst_class.parent.full_namespaces()) + class_name), + class_name="".join(inst_class.parent.full_namespaces()) + + class_name), prefix=' ') return methods_text @@ -833,7 +915,6 @@ class MatlabWrapper(object): method_map[method.name] = len(method_out) method_out.append([method]) else: - # import sys # print("[_group_methods] Merging {} with {}".format(method_index, method.name)) method_out[method_index].append(method) @@ -851,7 +932,11 @@ class MatlabWrapper(object): return varargout - def wrap_class_methods(self, namespace_name, inst_class, methods, serialize=[False]): + def wrap_class_methods(self, + namespace_name, + inst_class, + methods, + serialize=(False,)): """Wrap the methods in the class. Args: @@ -864,6 +949,10 @@ class MatlabWrapper(object): methods = self._group_class_methods(methods) + # Convert to list so that it is mutable + if isinstance(serialize, tuple): + serialize = list(serialize) + for method in methods: method_name = method[0].name if method_name in self.whitelist and method_name != 'serialize': @@ -873,30 +962,35 @@ class MatlabWrapper(object): if method_name == 'serialize': serialize[0] = True - method_text += self.wrap_class_serialize_method(namespace_name, inst_class) + method_text += self.wrap_class_serialize_method( + namespace_name, inst_class) else: # Generate method code method_text += textwrap.indent(textwrap.dedent("""\ function varargout = {method_name}(this, varargin) - """).format(caps_name=method_name.upper(), method_name=method_name), + """).format(caps_name=method_name.upper(), + method_name=method_name), prefix='') for overload in method: method_text += textwrap.indent(textwrap.dedent("""\ - % {caps_name} usage: {method_name}(""").format(caps_name=method_name.upper(), - method_name=method_name), + % {caps_name} usage: {method_name}(""").format( + caps_name=method_name.upper(), + method_name=method_name), prefix=' ') # Determine format of return and varargout statements return_type_formatted = self._format_return_type( overload.return_type, include_namespace=True, - separator="." - ) - varargout = self._format_varargout(overload.return_type, return_type_formatted) + separator=".") + varargout = self._format_varargout(overload.return_type, + return_type_formatted) - check_statement = self._wrap_method_check_statement(overload.args) - class_name = namespace_name + ('' if namespace_name == '' else '.') + inst_class.name + check_statement = self._wrap_method_check_statement( + overload.args) + class_name = namespace_name + ('' if namespace_name == '' + else '.') + inst_class.name end_statement = '' \ if check_statement == '' \ @@ -911,15 +1005,17 @@ class MatlabWrapper(object): {method_args}) : returns {return_type} % Doxygen can be found at https://gtsam.org/doxygen/ {check_statement}{spacing}{varargout}{wrapper}({num}, this, varargin{{:}}); - {end_statement}""").format(method_args=self._wrap_args(overload.args), - return_type=return_type_formatted, - num=self._update_wrapper_id( - (namespace_name, inst_class, overload.original.name, overload)), - check_statement=check_statement, - spacing='' if check_statement == '' else ' ', - varargout=varargout, - wrapper=self._wrapper_name(), - end_statement=end_statement) + {end_statement}""").format( + method_args=self._wrap_args(overload.args), + return_type=return_type_formatted, + num=self._update_wrapper_id( + (namespace_name, inst_class, + overload.original.name, overload)), + check_statement=check_statement, + spacing='' if check_statement == '' else ' ', + varargout=varargout, + wrapper=self._wrapper_name(), + end_statement=end_statement) final_statement = textwrap.indent(textwrap.dedent("""\ error('Arguments do not match any overload of function {class_name}.{method_name}'); @@ -929,11 +1025,16 @@ class MatlabWrapper(object): return method_text - def wrap_static_methods(self, namespace_name, instantiated_class, serialize): + def wrap_static_methods(self, namespace_name, instantiated_class, + serialize): + """ + Wrap the static methods in the class. + """ class_name = instantiated_class.name method_text = 'methods(Static = true)\n' - static_methods = sorted(instantiated_class.static_methods, key=lambda name: name.name) + static_methods = sorted(instantiated_class.static_methods, + key=lambda name: name.name) static_methods = self._group_class_methods(static_methods) @@ -950,7 +1051,8 @@ class MatlabWrapper(object): prefix=" ") for static_overload in static_method: - check_statement = self._wrap_method_check_statement(static_overload.args) + check_statement = self._wrap_method_check_statement( + static_overload.args) end_statement = '' \ if check_statement == '' \ @@ -962,34 +1064,41 @@ class MatlabWrapper(object): % {name_caps} usage: {name_upper_case}({args}) : returns {return_type} % Doxygen can be found at https://gtsam.org/doxygen/ {check_statement}{spacing}varargout{{1}} = {wrapper}({id}, varargin{{:}});{end_statement} - ''').format(name=''.join(format_name), - name_caps=static_overload.name.upper(), - name_upper_case=static_overload.name, - args=self._wrap_args(static_overload.args), - return_type=self._format_return_type(static_overload.return_type, - include_namespace=True, separator="."), - length=len(static_overload.args.args_list), - var_args_list=self._wrap_variable_arguments(static_overload.args), - check_statement=check_statement, - spacing='' if check_statement == '' else ' ', - wrapper=self._wrapper_name(), - id=self._update_wrapper_id( - (namespace_name, instantiated_class, static_overload.name, static_overload)), - class_name=instantiated_class.name, - end_statement=end_statement), + ''').format( + name=''.join(format_name), + name_caps=static_overload.name.upper(), + name_upper_case=static_overload.name, + args=self._wrap_args(static_overload.args), + return_type=self._format_return_type( + static_overload.return_type, + include_namespace=True, + separator="."), + length=len(static_overload.args.args_list), + var_args_list=self._wrap_variable_arguments( + static_overload.args), + check_statement=check_statement, + spacing='' if check_statement == '' else ' ', + wrapper=self._wrapper_name(), + id=self._update_wrapper_id( + (namespace_name, instantiated_class, + static_overload.name, static_overload)), + class_name=instantiated_class.name, + end_statement=end_statement), prefix=' ') + #TODO Figure out what is static_overload doing here. method_text += textwrap.indent(textwrap.dedent("""\ error('Arguments do not match any overload of function {class_name}.{method_name}'); - """.format(class_name=class_name, method_name=static_overload.name)), + """.format(class_name=class_name, + method_name=static_overload.name)), prefix=' ') - method_text += textwrap.indent(textwrap.dedent('''\ + + method_text += textwrap.indent(textwrap.dedent("""\ end\n - '''.format(name=''.join(format_name))), - prefix=" ") + """), prefix=" ") if serialize: - method_text += textwrap.indent(textwrap.dedent('''\ + method_text += textwrap.indent(textwrap.dedent("""\ function varargout = string_deserialize(varargin) % STRING_DESERIALIZE usage: string_deserialize() : returns {class_name} % Doxygen can be found at https://gtsam.org/doxygen/ @@ -1003,10 +1112,12 @@ class MatlabWrapper(object): % LOADOBJ Saves the object to a matlab-readable format obj = {class_name}.string_deserialize(sobj); end - ''').format(class_name=namespace_name + '.' + instantiated_class.name, - wrapper=self._wrapper_name(), - id=self._update_wrapper_id( - (namespace_name, instantiated_class, 'string_deserialize', 'deserialize'))), + """).format( + class_name=namespace_name + '.' + instantiated_class.name, + wrapper=self._wrapper_name(), + id=self._update_wrapper_id( + (namespace_name, instantiated_class, 'string_deserialize', + 'deserialize'))), prefix=' ') return method_text @@ -1022,7 +1133,8 @@ class MatlabWrapper(object): file_name = self._clean_class_name(instantiated_class) namespace_file_name = namespace_name + file_name - uninstantiated_name = "::".join(instantiated_class.namespaces()[1:]) + "::" + instantiated_class.name + uninstantiated_name = "::".join(instantiated_class.namespaces() + [1:]) + "::" + instantiated_class.name if uninstantiated_name in self.ignore_classes: return None @@ -1031,18 +1143,21 @@ class MatlabWrapper(object): content_text += self.wrap_methods(instantiated_class.methods) # Class definition - # import sys # if namespace_name: # print("nsname: {}, file_name_: {}, filename: {}" # .format(namespace_name, # self._clean_class_name(instantiated_class), file_name) # , file=sys.stderr) content_text += 'classdef {class_name} < {parent}\n'.format( - class_name=file_name, parent=str(self._qualified_name(instantiated_class.parent_class)).replace("::", ".")) + class_name=file_name, + parent=str(self._qualified_name( + instantiated_class.parent_class)).replace("::", ".")) # Class properties - content_text += ' ' + reduce(self._insert_spaces, - self.wrap_class_properties(namespace_file_name).splitlines()) + '\n' + content_text += ' ' + reduce( + self._insert_spaces, + self.wrap_class_properties( + namespace_file_name).splitlines()) + '\n' # Class constructor content_text += ' ' + reduce( @@ -1056,31 +1171,37 @@ class MatlabWrapper(object): ).splitlines()) + '\n' # Delete function - content_text += ' ' + reduce(self._insert_spaces, - self.wrap_class_deconstructor(namespace_name, - instantiated_class).splitlines()) + '\n' + content_text += ' ' + reduce( + self._insert_spaces, + self.wrap_class_deconstructor( + namespace_name, instantiated_class).splitlines()) + '\n' # Display function - content_text += ' ' + reduce(self._insert_spaces, self.wrap_class_display().splitlines()) + '\n' + content_text += ' ' + reduce( + self._insert_spaces, + self.wrap_class_display().splitlines()) + '\n' # Class methods serialize = [False] if len(instantiated_class.methods) != 0: - methods = sorted(instantiated_class.methods, key=lambda name: name.name) - class_methods_wrapped = self.wrap_class_methods(namespace_name, - instantiated_class, - methods, - serialize=serialize).splitlines() + methods = sorted(instantiated_class.methods, + key=lambda name: name.name) + class_methods_wrapped = self.wrap_class_methods( + namespace_name, + instantiated_class, + methods, + serialize=serialize).splitlines() if len(class_methods_wrapped) > 0: - content_text += ' ' + reduce(lambda x, y: x + '\n' + - ('' if y == '' else ' ') + y, - class_methods_wrapped) + '\n' + content_text += ' ' + reduce( + lambda x, y: x + '\n' + ('' if y == '' else ' ') + y, + class_methods_wrapped) + '\n' # Static class methods content_text += ' end\n\n ' + reduce( self._insert_spaces, - self.wrap_static_methods(namespace_name, instantiated_class, serialize[0]).splitlines()) + '\n' + self.wrap_static_methods(namespace_name, instantiated_class, + serialize[0]).splitlines()) + '\n' content_text += textwrap.dedent('''\ end @@ -1089,7 +1210,7 @@ class MatlabWrapper(object): return file_name + '.m', content_text - def wrap_namespace(self, namespace, parent=[]): + def wrap_namespace(self, namespace, parent=()): """Wrap a namespace by wrapping all of its components. Args: @@ -1100,7 +1221,8 @@ class MatlabWrapper(object): namespaces = namespace.full_namespaces() inner_namespace = namespace.name != '' wrapped = [] - self._debug("wrapping ns: {}, parent: {}".format(namespace.full_namespaces(), parent)) + self._debug("wrapping ns: {}, parent: {}".format( + namespace.full_namespaces(), parent)) matlab_wrapper = self.generate_matlab_wrapper() self.content.append((matlab_wrapper[0], matlab_wrapper[1])) @@ -1117,11 +1239,14 @@ class MatlabWrapper(object): self._add_class(element) if inner_namespace: - class_text = self.wrap_instantiated_class(element, "".join(namespace.full_namespaces())) + class_text = self.wrap_instantiated_class( + element, "".join(namespace.full_namespaces())) if not class_text is None: - namespace_scope.append(("".join(['+' + x + '/' for x in namespace.full_namespaces()[1:]])[:-1], - [(class_text[0], class_text[1])])) + namespace_scope.append(("".join([ + '+' + x + '/' + for x in namespace.full_namespaces()[1:] + ])[:-1], [(class_text[0], class_text[1])])) else: class_text = self.wrap_instantiated_class(element) current_scope.append((class_text[0], class_text[1])) @@ -1132,58 +1257,70 @@ class MatlabWrapper(object): self.content.append(namespace_scope) # Global functions - all_funcs = [func for func in namespace.content if isinstance(func, parser.GlobalFunction)] + all_funcs = [ + func for func in namespace.content + if isinstance(func, parser.GlobalFunction) + ] test_output += self.wrap_methods(all_funcs, True, global_ns=namespace) return wrapped - def wrap_collector_function_shared_return(self, return_type_name, shared_obj, id, new_line=True): + def wrap_collector_function_shared_return(self, + return_type_name, + shared_obj, + func_id, + new_line=True): + """Wrap the collector function which returns a shared pointer.""" new_line = '\n' if new_line else '' return textwrap.indent(textwrap.dedent('''\ {{ boost::shared_ptr<{name}> shared({shared_obj}); out[{id}] = wrap_shared_ptr(shared,"{name}"); - }}{new_line}''').format(name=self._format_type_name(return_type_name, include_namespace=False), + }}{new_line}''').format(name=self._format_type_name( + return_type_name, include_namespace=False), shared_obj=shared_obj, - id=id, + id=func_id, new_line=new_line), prefix=' ') - def wrap_collector_function_return_types(self, return_type, id): - return_type_text = ' out[' + str(id) + '] = ' - pair_value = 'first' if id == 0 else 'second' - new_line = '\n' if id == 0 else '' + def wrap_collector_function_return_types(self, return_type, func_id): + """ + Wrap the return type of the collector function. + """ + return_type_text = ' out[' + str(func_id) + '] = ' + pair_value = 'first' if func_id == 0 else 'second' + new_line = '\n' if func_id == 0 else '' - if self._is_ptr(return_type): + if self._is_shared_ptr(return_type) or self._is_ptr(return_type): shared_obj = 'pairResult.' + pair_value - if not return_type.is_ptr: + if not (return_type.is_shared_ptr or return_type.is_ptr): shared_obj = 'boost::make_shared<{name}>({shared_obj})' \ - .format( - name=self._format_type_name(return_type.typename), - formatted_name=self._format_type_name( - return_type.typename), - shared_obj='pairResult.' + pair_value) + .format(name=self._format_type_name(return_type.typename), + shared_obj='pairResult.' + pair_value) if return_type.typename.name in self.ignore_namespace: - return_type_text = self.wrap_collector_function_shared_return(return_type.typename, shared_obj, id, - True if id == 0 else False) + return_type_text = self.wrap_collector_function_shared_return( + return_type.typename, shared_obj, func_id, func_id == 0) else: - return_type_text += 'wrap_shared_ptr({},"{}", false);{new_line}' \ - .format( - shared_obj, - self._format_type_name( - return_type.typename, separator='.'), - new_line=new_line) + return_type_text += 'wrap_shared_ptr({0},"{1}", false);{new_line}' \ + .format(shared_obj, + self._format_type_name(return_type.typename, + separator='.'), + new_line=new_line) else: - return_type_text += 'wrap< {} >(pairResult.{});{}'.format( - self._format_type_name(return_type.typename, separator='.'), pair_value, new_line) + return_type_text += 'wrap< {0} >(pairResult.{1});{2}'.format( + self._format_type_name(return_type.typename, separator='.'), + pair_value, new_line) return return_type_text def wrap_collector_function_return(self, method): + """ + Wrap the complete return type of the function. + """ expanded = '' params = self._wrapper_unwrap_arguments(method.args, arg_id=1)[0] @@ -1203,9 +1340,11 @@ class MatlabWrapper(object): # self._format_type_name(method.instantiation)) # method_name = self._format_instance_method(method, '::') method = method.to_cpp() + elif isinstance(method, parser.GlobalFunction): method_name = self._format_global_method(method, '::') method_name += method.name + else: if isinstance(method.parent, instantiator.InstantiatedClass): method_name = method.parent.cpp_class() + "::" @@ -1214,53 +1353,67 @@ class MatlabWrapper(object): method_name += method.name if "MeasureRange" in method_name: - self._debug("method: {}, method: {}, inst: {}".format(method_name, method.name, method.parent.cpp_class())) + self._debug("method: {}, method: {}, inst: {}".format( + method_name, method.name, method.parent.cpp_class())) obj = ' ' if return_1_name == 'void' else '' obj += '{}{}({})'.format(obj_start, method_name, params) if return_1_name != 'void': if return_count == 1: - if self._is_ptr(return_1): - sep_method_name = partial(self._format_type_name, return_1.typename, include_namespace=True) + if self._is_shared_ptr(return_1) or self._is_ptr(return_1): + sep_method_name = partial(self._format_type_name, + return_1.typename, + include_namespace=True) if return_1.typename.name in self.ignore_namespace: - expanded += self.wrap_collector_function_shared_return(return_1.typename, - obj, - 0, - new_line=False) + expanded += self.wrap_collector_function_shared_return( + return_1.typename, obj, 0, new_line=False) - if return_1.is_ptr: - shared_obj = '{obj},"{method_name_sep}"'.format(obj=obj, method_name_sep=sep_method_name('.')) + if return_1.is_shared_ptr or return_1.is_ptr: + shared_obj = '{obj},"{method_name_sep}"'.format( + obj=obj, method_name_sep=sep_method_name('.')) else: - self._debug("Non-PTR: {}, {}".format(return_1, type(return_1))) - self._debug("Inner type is: {}, {}".format(return_1.typename.name, sep_method_name('.'))) - self._debug("Inner type instantiations: {}".format(return_1.typename.instantiations)) + self._debug("Non-PTR: {}, {}".format( + return_1, type(return_1))) + self._debug("Inner type is: {}, {}".format( + return_1.typename.name, sep_method_name('.'))) + self._debug("Inner type instantiations: {}".format( + return_1.typename.instantiations)) method_name_sep_dot = sep_method_name('.') - shared_obj = 'boost::make_shared<{method_name_sep_col}>({obj}),"{method_name_sep_dot}"' \ - .format( - method_name=return_1.typename.name, - method_name_sep_col=sep_method_name(), - method_name_sep_dot=method_name_sep_dot, - obj=obj) + shared_obj_template = 'boost::make_shared<{method_name_sep_col}>({obj}),' \ + '"{method_name_sep_dot}"' + shared_obj = shared_obj_template \ + .format(method_name_sep_col=sep_method_name(), + method_name_sep_dot=method_name_sep_dot, + obj=obj) if return_1.typename.name not in self.ignore_namespace: - expanded += textwrap.indent('out[0] = wrap_shared_ptr({}, false);'.format(shared_obj), - prefix=' ') + expanded += textwrap.indent( + 'out[0] = wrap_shared_ptr({}, false);'.format( + shared_obj), + prefix=' ') else: - expanded += ' out[0] = wrap< {} >({});'.format(return_1.typename.name, obj) + expanded += ' out[0] = wrap< {} >({});'.format( + return_1.typename.name, obj) elif return_count == 2: return_2 = method.return_type.type2 expanded += ' auto pairResult = {};\n'.format(obj) - expanded += self.wrap_collector_function_return_types(return_1, 0) - expanded += self.wrap_collector_function_return_types(return_2, 1) + expanded += self.wrap_collector_function_return_types( + return_1, 0) + expanded += self.wrap_collector_function_return_types( + return_2, 1) else: expanded += obj + ';' return expanded - def wrap_collector_function_upcast_from_void(self, class_name, id, cpp_name): + def wrap_collector_function_upcast_from_void(self, class_name, func_id, + cpp_name): + """ + Add function to upcast type from void type. + """ return textwrap.dedent('''\ void {class_name}_upcastFromVoid_{id}(int nargout, mxArray *out[], int nargin, const mxArray *in[]) {{ mexAtExit(&_deleteAllObjects); @@ -1270,20 +1423,21 @@ class MatlabWrapper(object): Shared *self = new Shared(boost::static_pointer_cast<{cpp_name}>(*asVoid)); *reinterpret_cast(mxGetData(out[0])) = self; }}\n - ''').format(class_name=class_name, cpp_name=cpp_name, id=id) + ''').format(class_name=class_name, cpp_name=cpp_name, id=func_id) - def generate_collector_function(self, id): - collector_func = self.wrapper_map.get(id) + def generate_collector_function(self, func_id): + """ + Generate the complete collector function. + """ + collector_func = self.wrapper_map.get(func_id) if collector_func is None: return '' method_name = collector_func[3] - # import sys - # print("[Collector Gen] id: {}, obj: {}".format(id, method_name), file=sys.stderr) - collector_function = 'void {}(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n' \ - .format(method_name) + collector_function = "void {}" \ + "(int nargout, mxArray *out[], int nargin, const mxArray *in[])\n".format(method_name) if isinstance(collector_func[1], instantiator.InstantiatedClass): body = '{\n' @@ -1301,7 +1455,8 @@ class MatlabWrapper(object): typedef boost::shared_ptr<{class_name_sep}> Shared;\n Shared *self = *reinterpret_cast (mxGetData(in[0])); collector_{class_name}.insert(self); - ''').format(class_name_sep=class_name_separated, class_name=class_name), + ''').format(class_name_sep=class_name_separated, + class_name=class_name), prefix=' ') if collector_func[1].parent_class: @@ -1313,7 +1468,8 @@ class MatlabWrapper(object): prefix=' ') elif collector_func[2] == 'constructor': base = '' - params, body_args = self._wrapper_unwrap_arguments(extra.args, constructor=True) + params, body_args = self._wrapper_unwrap_arguments( + extra.args, constructor=True) if collector_func[1].parent_class: base += textwrap.indent(textwrap.dedent(''' @@ -1346,16 +1502,19 @@ class MatlabWrapper(object): delete self; collector_{class_name}.erase(item); }} - ''').format(class_name_sep=class_name_separated, class_name=class_name), + ''').format(class_name_sep=class_name_separated, + class_name=class_name), prefix=' ') elif extra == 'serialize': - body += self.wrap_collector_function_serialize(collector_func[1].name, - full_name=collector_func[1].cpp_class(), - namespace=collector_func[0]) + body += self.wrap_collector_function_serialize( + collector_func[1].name, + full_name=collector_func[1].cpp_class(), + namespace=collector_func[0]) elif extra == 'deserialize': - body += self.wrap_collector_function_deserialize(collector_func[1].name, - full_name=collector_func[1].cpp_class(), - namespace=collector_func[0]) + body += self.wrap_collector_function_deserialize( + collector_func[1].name, + full_name=collector_func[1].cpp_class(), + namespace=collector_func[0]) elif is_method or is_static_method: method_name = '' @@ -1364,39 +1523,30 @@ class MatlabWrapper(object): method_name += extra.name - return_type = extra.return_type - return_count = self._return_count(return_type) + # return_type = extra.return_type + # return_count = self._return_count(return_type) return_body = self.wrap_collector_function_return(extra) - params, body_args = self._wrapper_unwrap_arguments(extra.args, arg_id=1 if is_method else 0) + params, body_args = self._wrapper_unwrap_arguments( + extra.args, arg_id=1 if is_method else 0) shared_obj = '' if is_method: - shared_obj = \ - ' auto obj = unwrap_shared_ptr<{class_name_sep}>(in[0], "ptr_{class_name}");\n'.format( - class_name_sep=class_name_separated, - class_name=class_name) - """ - body += textwrap.dedent('''\ - typedef std::shared_ptr<{class_name_sep}> Shared; - checkArguments("{method_name}",nargout,nargin{min1},{num_args}); - {shared_obj} - {body_args} - {return_body} - ''') - """ + shared_obj = ' auto obj = unwrap_shared_ptr<{class_name_sep}>' \ + '(in[0], "ptr_{class_name}");\n'.format( + class_name_sep=class_name_separated, + class_name=class_name) + body += ' checkArguments("{method_name}",nargout,nargin{min1},' \ '{num_args});\n' \ '{shared_obj}' \ '{body_args}' \ '{return_body}\n'.format( - class_name_sep=class_name_separated, min1='-1' if is_method else '', shared_obj=shared_obj, method_name=method_name, num_args=len(extra.args.args_list), - class_name=class_name, body_args=body_args, return_body=return_body) @@ -1406,9 +1556,8 @@ class MatlabWrapper(object): body += '\n' collector_function += body + else: - # import sys - # print("other func: {}".format(collector_func[1]), file=sys.stderr) body = textwrap.dedent('''\ {{ checkArguments("{function_name}",nargout,nargin,{len}); @@ -1426,6 +1575,9 @@ class MatlabWrapper(object): return collector_function def mex_function(self): + """ + Generate the wrapped MEX function. + """ cases = '' next_case = None @@ -1449,7 +1601,8 @@ class MatlabWrapper(object): prefix=' ') if set_next_case: - next_case = '{}_upcastFromVoid_{}'.format(id_val[1].name, wrapper_id + 1) + next_case = '{}_upcastFromVoid_{}'.format( + id_val[1].name, wrapper_id + 1) else: next_case = None @@ -1483,7 +1636,10 @@ class MatlabWrapper(object): #include \n ''') - includes_list = sorted(list(self.includes.keys()), key=lambda include: include.header) + assert namespace + + includes_list = sorted(list(self.includes.keys()), + key=lambda include: include.header) # Check the number of includes. # If no includes, do nothing, if 1 then just append newline. @@ -1493,7 +1649,8 @@ class MatlabWrapper(object): elif len(includes_list) == 1: wrapper_file += (str(includes_list[0]) + '\n') else: - wrapper_file += reduce(lambda x, y: str(x) + '\n' + str(y), includes_list) + wrapper_file += reduce(lambda x, y: str(x) + '\n' + str(y), + includes_list) wrapper_file += '\n' typedef_instances = '\n' @@ -1513,7 +1670,8 @@ class MatlabWrapper(object): std::map types; ''').format(module_name=self.module_name) rtti_reg_mid = '' - rtti_reg_end = textwrap.indent(textwrap.dedent(''' + rtti_reg_end = textwrap.indent( + textwrap.dedent(''' mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); if(!registry) registry = mxCreateStructMatrix(1, 1, 0, NULL); @@ -1529,7 +1687,7 @@ class MatlabWrapper(object): mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); mxDestroyArray(registry); '''), - prefix=' ') + ' \n' + textwrap.dedent('''\ + prefix=' ') + ' \n' + textwrap.dedent('''\ mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL); if(mexPutVariable("global", "gtsam_geometry_rttiRegistry_created", newAlreadyCreated) != 0) mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); @@ -1540,11 +1698,13 @@ class MatlabWrapper(object): ptr_ctor_frag = '' for cls in self.classes: - uninstantiated_name = "::".join(cls.namespaces()[1:]) + "::" + cls.name + uninstantiated_name = "::".join( + cls.namespaces()[1:]) + "::" + cls.name self._debug("Cls: {} -> {}".format(cls.name, uninstantiated_name)) if uninstantiated_name in self.ignore_classes: - self._debug("Ignoring: {} -> {}".format(cls.name, uninstantiated_name)) + self._debug("Ignoring: {} -> {}".format( + cls.name, uninstantiated_name)) continue def _has_serialization(cls): @@ -1553,7 +1713,7 @@ class MatlabWrapper(object): return True return False - if len(cls.instantiations): + if cls.instantiations: cls_insts = '' for i, inst in enumerate(cls.instantiations): @@ -1562,20 +1722,25 @@ class MatlabWrapper(object): cls_insts += self._format_type_name(inst) - typedef_instances += 'typedef {original_class_name} {class_name_sep};\n'.format( - namespace_name=namespace.name, original_class_name=cls.cpp_class(), class_name_sep=cls.name) + typedef_instances += 'typedef {original_class_name} {class_name_sep};\n' \ + .format(original_class_name=cls.cpp_class(), + class_name_sep=cls.name) class_name_sep = cls.name class_name = self._format_class_name(cls) - if len(cls.original.namespaces()) > 1 and _has_serialization(cls): - boost_class_export_guid += 'BOOST_CLASS_EXPORT_GUID({}, "{}");\n'.format(class_name_sep, class_name) + if len(cls.original.namespaces()) > 1 and _has_serialization( + cls): + boost_class_export_guid += 'BOOST_CLASS_EXPORT_GUID({}, "{}");\n'.format( + class_name_sep, class_name) else: class_name_sep = cls.cpp_class() class_name = self._format_class_name(cls) - if len(cls.original.namespaces()) > 1 and _has_serialization(cls): - boost_class_export_guid += 'BOOST_CLASS_EXPORT_GUID({}, "{}");\n'.format(class_name_sep, class_name) + if len(cls.original.namespaces()) > 1 and _has_serialization( + cls): + boost_class_export_guid += 'BOOST_CLASS_EXPORT_GUID({}, "{}");\n'.format( + class_name_sep, class_name) typedef_collectors += textwrap.dedent('''\ typedef std::set*> Collector_{class_name}; @@ -1592,30 +1757,30 @@ class MatlabWrapper(object): prefix=' ') if cls.is_virtual: - rtti_reg_mid += ' types.insert(std::make_pair(typeid({}).name(), "{}"));\n'.format( - class_name_sep, class_name) + rtti_reg_mid += ' types.insert(std::make_pair(typeid({}).name(), "{}"));\n' \ + .format(class_name_sep, class_name) set_next_case = False - for id in range(self.wrapper_id): - id_val = self.wrapper_map.get(id) + for idx in range(self.wrapper_id): + id_val = self.wrapper_map.get(idx) queue_set_next_case = set_next_case set_next_case = False if id_val is None: - id_val = self.wrapper_map.get(id + 1) + id_val = self.wrapper_map.get(idx + 1) if id_val is None: continue set_next_case = True - ptr_ctor_frag += self.generate_collector_function(id) + ptr_ctor_frag += self.generate_collector_function(idx) if queue_set_next_case: - ptr_ctor_frag += self.wrap_collector_function_upcast_from_void(id_val[1].name, id, - id_val[1].cpp_class()) + ptr_ctor_frag += self.wrap_collector_function_upcast_from_void( + id_val[1].name, idx, id_val[1].cpp_class()) wrapper_file += textwrap.dedent('''\ {typedef_instances} @@ -1641,8 +1806,12 @@ class MatlabWrapper(object): self.content.append((self._wrapper_name() + '.cpp', wrapper_file)) def wrap_class_serialize_method(self, namespace_name, inst_class): + """ + Wrap the serizalize method of the class. + """ class_name = inst_class.name - wrapper_id = self._update_wrapper_id((namespace_name, inst_class, 'string_serialize', 'serialize')) + wrapper_id = self._update_wrapper_id( + (namespace_name, inst_class, 'string_serialize', 'serialize')) return textwrap.dedent('''\ function varargout = string_serialize(this, varargin) @@ -1658,10 +1827,18 @@ class MatlabWrapper(object): % SAVEOBJ Saves the object to a matlab-readable format sobj = obj.string_serialize(); end - ''').format(wrapper=self._wrapper_name(), wrapper_id=wrapper_id, class_name=namespace_name + '.' + class_name) + ''').format(wrapper=self._wrapper_name(), + wrapper_id=wrapper_id, + class_name=namespace_name + '.' + class_name) - def wrap_collector_function_serialize(self, class_name, full_name='', namespace=''): - return textwrap.indent(textwrap.dedent('''\ + def wrap_collector_function_serialize(self, + class_name, + full_name='', + namespace=''): + """ + Wrap the serizalize collector function. + """ + return textwrap.indent(textwrap.dedent("""\ typedef boost::shared_ptr<{full_name}> Shared; checkArguments("string_serialize",nargout,nargin-1,0); Shared obj = unwrap_shared_ptr<{full_name}>(in[0], "ptr_{namespace}{class_name}"); @@ -1669,11 +1846,19 @@ class MatlabWrapper(object): boost::archive::text_oarchive out_archive(out_archive_stream); out_archive << *obj; out[0] = wrap< string >(out_archive_stream.str()); - ''').format(class_name=class_name, full_name=full_name, namespace=namespace), + """).format(class_name=class_name, + full_name=full_name, + namespace=namespace), prefix=' ') - def wrap_collector_function_deserialize(self, class_name, full_name='', namespace=''): - return textwrap.indent(textwrap.dedent('''\ + def wrap_collector_function_deserialize(self, + class_name, + full_name='', + namespace=''): + """ + Wrap the deserizalize collector function. + """ + return textwrap.indent(textwrap.dedent("""\ typedef boost::shared_ptr<{full_name}> Shared; checkArguments("{namespace}{class_name}.string_deserialize",nargout,nargin,1); string serialized = unwrap< string >(in[0]); @@ -1682,10 +1867,13 @@ class MatlabWrapper(object): Shared output(new {full_name}()); in_archive >> *output; out[0] = wrap_shared_ptr(output,"{namespace}.{class_name}", false); - ''').format(class_name=class_name, full_name=full_name, namespace=namespace), + """).format(class_name=class_name, + full_name=full_name, + namespace=namespace), prefix=' ') def wrap(self): + """High level function to wrap the project.""" self.wrap_namespace(self.module) self.generate_wrapper(self.module) @@ -1693,27 +1881,26 @@ class MatlabWrapper(object): def generate_content(cc_content, path, verbose=False): - """Generate files and folders from matlab wrapper content. - - Keyword arguments: - cc_content -- the content to generate formatted as - (file_name, file_content) or - (folder_name, [(file_name, file_content)]) - path -- the path to the files parent folder within the main folder """ + Generate files and folders from matlab wrapper content. + Args: + cc_content: The content to generate formatted as + (file_name, file_content) or + (folder_name, [(file_name, file_content)]) + path: The path to the files parent folder within the main folder + """ def _debug(message): if not verbose: return - import sys print(message, file=sys.stderr) for c in cc_content: - if type(c) == list: + if isinstance(c, list): if len(c) == 0: continue _debug("c object: {}".format(c[0][0])) - path_to_folder = path + '/' + c[0][0] + path_to_folder = osp.join(path, c[0][0]) if not os.path.isdir(path_to_folder): try: @@ -1722,11 +1909,11 @@ def generate_content(cc_content, path, verbose=False): pass for sub_content in c: - import sys _debug("sub object: {}".format(sub_content[1][0][0])) generate_content(sub_content[1], path_to_folder) - elif type(c[1]) == list: - path_to_folder = path + '/' + c[0] + + elif isinstance(c[1], list): + path_to_folder = osp.join(path, c[0]) _debug("[generate_content_global]: {}".format(path_to_folder)) if not os.path.isdir(path_to_folder): @@ -1735,13 +1922,12 @@ def generate_content(cc_content, path, verbose=False): except OSError: pass for sub_content in c[1]: - import sys - path_to_file = path_to_folder + '/' + sub_content[0] + path_to_file = osp.join(path_to_folder, sub_content[0]) _debug("[generate_global_method]: {}".format(path_to_file)) with open(path_to_file, 'w') as f: f.write(sub_content[1]) else: - path_to_file = path + '/' + c[0] + path_to_file = osp.join(path, c[0]) _debug("[generate_content]: {}".format(path_to_file)) if not os.path.isdir(path_to_file): diff --git a/gtwrap/pybind_wrapper.py b/gtwrap/pybind_wrapper.py index 986cdd8b1..3d82298da 100755 --- a/gtwrap/pybind_wrapper.py +++ b/gtwrap/pybind_wrapper.py @@ -10,7 +10,7 @@ Code generator for wrapping a C++ module with Pybind11 Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellaert """ -# pylint: disable=too-many-arguments, too-many-instance-attributes, no-self-use, no-else-return, too-many-arguments, unused-format-string-argument +# pylint: disable=too-many-arguments, too-many-instance-attributes, no-self-use, no-else-return, too-many-arguments, unused-format-string-argument, line-too-long import re import textwrap @@ -39,6 +39,9 @@ class PybindWrapper: self.module_template = module_template self.python_keywords = ['print', 'lambda'] + # amount of indentation to add before each function/method declaration. + self.method_indent = '\n' + (' ' * 8) + def _py_args_names(self, args_list): """Set the argument names in Pybind11 format.""" names = args_list.args_names() @@ -54,13 +57,13 @@ class PybindWrapper: names = args_list.args_names() types_names = ["{} {}".format(ctype, name) for ctype, name in zip(cpp_types, names)] - return ','.join(types_names) + return ', '.join(types_names) def wrap_ctors(self, my_class): """Wrap the constructors.""" res = "" for ctor in my_class.ctors: - res += ('\n' + ' ' * 8 + '.def(py::init<{args_cpp_types}>()' + res += (self.method_indent + '.def(py::init<{args_cpp_types}>()' '{py_args_names})'.format( args_cpp_types=", ".join(ctor.args.to_cpp(self.use_boost)), py_args_names=self._py_args_names(ctor.args), @@ -74,32 +77,19 @@ class PybindWrapper: if cpp_method in ["serialize", "serializable"]: if not cpp_class in self._serializing_classes: self._serializing_classes.append(cpp_class) - return textwrap.dedent(''' - .def("serialize", - []({class_inst} self){{ - return gtsam::serialize(*self); - }} - ) - .def("deserialize", - []({class_inst} self, string serialized){{ - gtsam::deserialize(serialized, *self); - }}, py::arg("serialized")) - '''.format(class_inst=cpp_class + '*')) + serialize_method = self.method_indent + \ + ".def(\"serialize\", []({class_inst} self){{ return gtsam::serialize(*self); }})".format(class_inst=cpp_class + '*') + deserialize_method = self.method_indent + \ + ".def(\"deserialize\", []({class_inst} self, string serialized){{ gtsam::deserialize(serialized, *self); }}, py::arg(\"serialized\"))" \ + .format(class_inst=cpp_class + '*') + return serialize_method + deserialize_method + if cpp_method == "pickle": if not cpp_class in self._serializing_classes: raise ValueError("Cannot pickle a class which is not serializable") - return textwrap.dedent(''' - .def(py::pickle( - [](const {cpp_class} &a){{ // __getstate__ - /* Returns a string that encodes the state of the object */ - return py::make_tuple(gtsam::serialize(a)); - }}, - [](py::tuple t){{ // __setstate__ - {cpp_class} obj; - gtsam::deserialize(t[0].cast(), obj); - return obj; - }})) - '''.format(cpp_class=cpp_class)) + pickle_method = self.method_indent + \ + ".def(py::pickle({indent} [](const {cpp_class} &a){{ /* __getstate__: Returns a string that encodes the state of the object */ return py::make_tuple(gtsam::serialize(a)); }},{indent} [](py::tuple t){{ /* __setstate__ */ {cpp_class} obj; gtsam::deserialize(t[0].cast(), obj); return obj; }}))" + return pickle_method.format(cpp_class=cpp_class, indent=self.method_indent) is_method = isinstance(method, instantiator.InstantiatedMethod) is_static = isinstance(method, parser.StaticMethod) @@ -128,14 +118,13 @@ class PybindWrapper: else py_method + "_", opt_self="{cpp_class}* self".format( cpp_class=cpp_class) if is_method else "", - cpp_class=cpp_class, - cpp_method=cpp_method, - opt_comma=',' if is_method and args_names else '', + opt_comma=', ' if is_method and args_names else '', args_signature_with_names=args_signature_with_names, function_call=function_call, py_args_names=py_args_names, suffix=suffix, )) + if method.name == 'print': type_list = method.args.to_cpp(self.use_boost) if len(type_list) > 0 and type_list[0].strip() == 'string': @@ -163,7 +152,11 @@ class PybindWrapper: return ret def wrap_methods(self, methods, cpp_class, prefix='\n' + ' ' * 8, suffix=''): - """Wrap all the methods in the `cpp_class`.""" + """ + Wrap all the methods in the `cpp_class`. + + This function is also used to wrap global functions. + """ res = "" for method in methods: @@ -185,6 +178,7 @@ class PybindWrapper: prefix=prefix, suffix=suffix, ) + return res def wrap_properties(self, properties, cpp_class, prefix='\n' + ' ' * 8): @@ -325,7 +319,8 @@ class PybindWrapper: # Global functions. all_funcs = [ func for func in namespace.content - if isinstance(func, parser.GlobalFunction) + if isinstance(func, (parser.GlobalFunction, + instantiator.InstantiatedGlobalFunction)) ] wrapped += self.wrap_methods( all_funcs, diff --git a/gtwrap/template_instantiator.py b/gtwrap/template_instantiator.py index fe2caf025..8e918e297 100644 --- a/gtwrap/template_instantiator.py +++ b/gtwrap/template_instantiator.py @@ -45,6 +45,7 @@ def instantiate_type(ctype: parser.Type, return parser.Type( typename=instantiations[idx], is_const=ctype.is_const, + is_shared_ptr=ctype.is_shared_ptr, is_ptr=ctype.is_ptr, is_ref=ctype.is_ref, is_basis=ctype.is_basis, @@ -63,6 +64,7 @@ def instantiate_type(ctype: parser.Type, return parser.Type( typename=cpp_typename, is_const=ctype.is_const, + is_shared_ptr=ctype.is_shared_ptr, is_ptr=ctype.is_ptr, is_ref=ctype.is_ref, is_basis=ctype.is_basis, @@ -128,11 +130,69 @@ def instantiate_name(original_name, instantiations): for inst in instantiations: # Ensure the first character of the type is capitalized name = inst.instantiated_name() - # Using `capitalize` on the complete causes other caps to be lower case + # Using `capitalize` on the complete name causes other caps to be lower case instantiated_names.append(name.replace(name[0], name[0].capitalize())) return "{}{}".format(original_name, "".join(instantiated_names)) +class InstantiatedGlobalFunction(parser.GlobalFunction): + """ + Instantiate global functions. + + E.g. + template + T add(const T& x, const T& y); + """ + def __init__(self, original, instantiations=(), new_name=''): + self.original = original + self.instantiations = instantiations + self.template = '' + self.parent = original.parent + + if not original.template: + self.name = original.name + self.return_type = original.return_type + self.args = original.args + else: + self.name = instantiate_name( + original.name, instantiations) if not new_name else new_name + self.return_type = instantiate_return_type( + original.return_type, + self.original.template.typenames, + self.instantiations, + # Keyword type name `This` should already be replaced in the + # previous class template instantiation round. + cpp_typename='', + ) + instantiated_args = instantiate_args_list( + original.args.args_list, + self.original.template.typenames, + self.instantiations, + # Keyword type name `This` should already be replaced in the + # previous class template instantiation round. + cpp_typename='', + ) + self.args = parser.ArgumentList(instantiated_args) + + super().__init__(self.name, + self.return_type, + self.args, + self.template, + parent=self.parent) + + def to_cpp(self): + """Generate the C++ code for wrapping.""" + if self.original.template: + instantiated_names = [inst.instantiated_name() for inst in self.instantiations] + ret = "{}<{}>".format(self.original.name, ",".join(instantiated_names)) + else: + ret = self.original.name + return ret + + def __repr__(self): + return "Instantiated {}".format( + super(InstantiatedGlobalFunction, self).__repr__() + ) class InstantiatedMethod(parser.Method): """ @@ -396,17 +456,38 @@ def instantiate_namespace_inplace(namespace): InstantiatedClass(original_class, list(instantiations))) + elif isinstance(element, parser.GlobalFunction): + original_func = element + if not original_func.template: + instantiated_content.append( + InstantiatedGlobalFunction(original_func, [])) + else: + # Use itertools to get all possible combinations of instantiations + # Works even if one template does not have an instantiation list + for instantiations in itertools.product( + *original_func.template.instantiations): + instantiated_content.append( + InstantiatedGlobalFunction(original_func, + list(instantiations))) + elif isinstance(element, parser.TypedefTemplateInstantiation): typedef_inst = element - original_class = namespace.top_level().find_class( + top_level = namespace.top_level() + original_element = top_level.find_class_or_function( typedef_inst.typename) - typedef_content.append( - InstantiatedClass( - original_class, - typedef_inst.typename.instantiations, - typedef_inst.new_name - ) - ) + + # Check if element is a typedef'd class or function. + if isinstance(original_element, parser.Class): + typedef_content.append( + InstantiatedClass(original_element, + typedef_inst.typename.instantiations, + typedef_inst.new_name)) + elif isinstance(original_element, parser.GlobalFunction): + typedef_content.append( + InstantiatedGlobalFunction( + original_element, typedef_inst.typename.instantiations, + typedef_inst.new_name)) + elif isinstance(element, parser.Namespace): instantiate_namespace_inplace(element) instantiated_content.append(element) diff --git a/requirements.txt b/requirements.txt index 210dfec50..dd24ea4ed 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1 +1,3 @@ pyparsing +pytest +loguru \ No newline at end of file diff --git a/tests/expected-matlab/+gtsam/Point2.m b/tests/expected-matlab/+gtsam/Point2.m index ca021439a..3c00ce3f9 100644 --- a/tests/expected-matlab/+gtsam/Point2.m +++ b/tests/expected-matlab/+gtsam/Point2.m @@ -7,6 +7,12 @@ % %-------Methods------- %argChar(char a) : returns void +%argChar(char a) : returns void +%argChar(char a) : returns void +%argChar(char a) : returns void +%argChar(char a) : returns void +%argChar(char a) : returns void +%argChar(char a) : returns void %argUChar(unsigned char a) : returns void %dim() : returns int %eigenArguments(Vector v, Matrix m) : returns void @@ -49,6 +55,42 @@ classdef Point2 < handle geometry_wrapper(4, this, varargin{:}); return end + % ARGCHAR usage: argChar(char a) : returns void + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 1 && isa(varargin{1},'char') + geometry_wrapper(5, this, varargin{:}); + return + end + % ARGCHAR usage: argChar(char a) : returns void + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 1 && isa(varargin{1},'char') + geometry_wrapper(6, this, varargin{:}); + return + end + % ARGCHAR usage: argChar(char a) : returns void + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 1 && isa(varargin{1},'char') + geometry_wrapper(7, this, varargin{:}); + return + end + % ARGCHAR usage: argChar(char a) : returns void + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 1 && isa(varargin{1},'char') + geometry_wrapper(8, this, varargin{:}); + return + end + % ARGCHAR usage: argChar(char a) : returns void + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 1 && isa(varargin{1},'char') + geometry_wrapper(9, this, varargin{:}); + return + end + % ARGCHAR usage: argChar(char a) : returns void + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 1 && isa(varargin{1},'char') + geometry_wrapper(10, this, varargin{:}); + return + end error('Arguments do not match any overload of function gtsam.Point2.argChar'); end @@ -56,7 +98,7 @@ classdef Point2 < handle % ARGUCHAR usage: argUChar(unsigned char a) : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'unsigned char') - geometry_wrapper(5, this, varargin{:}); + geometry_wrapper(11, this, varargin{:}); return end error('Arguments do not match any overload of function gtsam.Point2.argUChar'); @@ -66,7 +108,7 @@ classdef Point2 < handle % DIM usage: dim() : returns int % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - varargout{1} = geometry_wrapper(6, this, varargin{:}); + varargout{1} = geometry_wrapper(12, this, varargin{:}); return end error('Arguments do not match any overload of function gtsam.Point2.dim'); @@ -76,7 +118,7 @@ classdef Point2 < handle % EIGENARGUMENTS usage: eigenArguments(Vector v, Matrix m) : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 2 && isa(varargin{1},'double') && size(varargin{1},2)==1 && isa(varargin{2},'double') - geometry_wrapper(7, this, varargin{:}); + geometry_wrapper(13, this, varargin{:}); return end error('Arguments do not match any overload of function gtsam.Point2.eigenArguments'); @@ -86,7 +128,7 @@ classdef Point2 < handle % RETURNCHAR usage: returnChar() : returns char % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - varargout{1} = geometry_wrapper(8, this, varargin{:}); + varargout{1} = geometry_wrapper(14, this, varargin{:}); return end error('Arguments do not match any overload of function gtsam.Point2.returnChar'); @@ -96,7 +138,7 @@ classdef Point2 < handle % VECTORCONFUSION usage: vectorConfusion() : returns VectorNotEigen % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - varargout{1} = geometry_wrapper(9, this, varargin{:}); + varargout{1} = geometry_wrapper(15, this, varargin{:}); return end error('Arguments do not match any overload of function gtsam.Point2.vectorConfusion'); @@ -106,7 +148,7 @@ classdef Point2 < handle % X usage: x() : returns double % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - varargout{1} = geometry_wrapper(10, this, varargin{:}); + varargout{1} = geometry_wrapper(16, this, varargin{:}); return end error('Arguments do not match any overload of function gtsam.Point2.x'); @@ -116,7 +158,7 @@ classdef Point2 < handle % Y usage: y() : returns double % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - varargout{1} = geometry_wrapper(11, this, varargin{:}); + varargout{1} = geometry_wrapper(17, this, varargin{:}); return end error('Arguments do not match any overload of function gtsam.Point2.y'); diff --git a/tests/expected-matlab/+gtsam/Point3.m b/tests/expected-matlab/+gtsam/Point3.m index 526d9d3d1..06d378ac2 100644 --- a/tests/expected-matlab/+gtsam/Point3.m +++ b/tests/expected-matlab/+gtsam/Point3.m @@ -23,9 +23,9 @@ classdef Point3 < handle function obj = Point3(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - geometry_wrapper(12, my_ptr); + geometry_wrapper(18, my_ptr); elseif nargin == 3 && isa(varargin{1},'double') && isa(varargin{2},'double') && isa(varargin{3},'double') - my_ptr = geometry_wrapper(13, varargin{1}, varargin{2}, varargin{3}); + my_ptr = geometry_wrapper(19, varargin{1}, varargin{2}, varargin{3}); else error('Arguments do not match any overload of gtsam.Point3 constructor'); end @@ -33,7 +33,7 @@ classdef Point3 < handle end function delete(obj) - geometry_wrapper(14, obj.ptr_gtsamPoint3); + geometry_wrapper(20, obj.ptr_gtsamPoint3); end function display(obj), obj.print(''); end @@ -44,7 +44,7 @@ classdef Point3 < handle % NORM usage: norm() : returns double % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - varargout{1} = geometry_wrapper(15, this, varargin{:}); + varargout{1} = geometry_wrapper(21, this, varargin{:}); return end error('Arguments do not match any overload of function gtsam.Point3.norm'); @@ -54,7 +54,7 @@ classdef Point3 < handle % STRING_SERIALIZE usage: string_serialize() : returns string % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - varargout{1} = geometry_wrapper(16, this, varargin{:}); + varargout{1} = geometry_wrapper(22, this, varargin{:}); else error('Arguments do not match any overload of function gtsam.Point3.string_serialize'); end @@ -71,7 +71,7 @@ classdef Point3 < handle % STATICFUNCTIONRET usage: StaticFunctionRet(double z) : returns Point3 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(17, varargin{:}); + varargout{1} = geometry_wrapper(23, varargin{:}); return end @@ -82,7 +82,7 @@ classdef Point3 < handle % STATICFUNCTION usage: staticFunction() : returns double % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - varargout{1} = geometry_wrapper(18, varargin{:}); + varargout{1} = geometry_wrapper(24, varargin{:}); return end @@ -93,7 +93,7 @@ classdef Point3 < handle % STRING_DESERIALIZE usage: string_deserialize() : returns gtsam.Point3 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 - varargout{1} = geometry_wrapper(19, varargin{:}); + varargout{1} = geometry_wrapper(25, varargin{:}); else error('Arguments do not match any overload of function gtsam.Point3.string_deserialize'); end diff --git a/tests/expected-matlab/MyBase.m b/tests/expected-matlab/MyBase.m index 4d4d35ee5..57654626f 100644 --- a/tests/expected-matlab/MyBase.m +++ b/tests/expected-matlab/MyBase.m @@ -11,9 +11,9 @@ classdef MyBase < handle if nargin == 2 my_ptr = varargin{2}; else - my_ptr = geometry_wrapper(45, varargin{2}); + my_ptr = geometry_wrapper(51, varargin{2}); end - geometry_wrapper(44, my_ptr); + geometry_wrapper(50, my_ptr); else error('Arguments do not match any overload of MyBase constructor'); end @@ -21,7 +21,7 @@ classdef MyBase < handle end function delete(obj) - geometry_wrapper(46, obj.ptr_MyBase); + geometry_wrapper(52, obj.ptr_MyBase); end function display(obj), obj.print(''); end diff --git a/tests/expected-matlab/MyFactorPosePoint2.m b/tests/expected-matlab/MyFactorPosePoint2.m index d711c5325..3466e9291 100644 --- a/tests/expected-matlab/MyFactorPosePoint2.m +++ b/tests/expected-matlab/MyFactorPosePoint2.m @@ -12,9 +12,9 @@ classdef MyFactorPosePoint2 < handle function obj = MyFactorPosePoint2(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - geometry_wrapper(93, my_ptr); + geometry_wrapper(99, my_ptr); elseif nargin == 4 && isa(varargin{1},'numeric') && isa(varargin{2},'numeric') && isa(varargin{3},'double') && isa(varargin{4},'gtsam.noiseModel.Base') - my_ptr = geometry_wrapper(94, varargin{1}, varargin{2}, varargin{3}, varargin{4}); + my_ptr = geometry_wrapper(100, varargin{1}, varargin{2}, varargin{3}, varargin{4}); else error('Arguments do not match any overload of MyFactorPosePoint2 constructor'); end @@ -22,7 +22,7 @@ classdef MyFactorPosePoint2 < handle end function delete(obj) - geometry_wrapper(95, obj.ptr_MyFactorPosePoint2); + geometry_wrapper(101, obj.ptr_MyFactorPosePoint2); end function display(obj), obj.print(''); end diff --git a/tests/expected-matlab/MyTemplateMatrix.m b/tests/expected-matlab/MyTemplateMatrix.m index 54245921d..839b3809e 100644 --- a/tests/expected-matlab/MyTemplateMatrix.m +++ b/tests/expected-matlab/MyTemplateMatrix.m @@ -34,11 +34,11 @@ classdef MyTemplateMatrix < MyBase if nargin == 2 my_ptr = varargin{2}; else - my_ptr = geometry_wrapper(64, varargin{2}); + my_ptr = geometry_wrapper(70, varargin{2}); end - base_ptr = geometry_wrapper(63, my_ptr); + base_ptr = geometry_wrapper(69, my_ptr); elseif nargin == 0 - [ my_ptr, base_ptr ] = geometry_wrapper(65); + [ my_ptr, base_ptr ] = geometry_wrapper(71); else error('Arguments do not match any overload of MyTemplateMatrix constructor'); end @@ -47,7 +47,7 @@ classdef MyTemplateMatrix < MyBase end function delete(obj) - geometry_wrapper(66, obj.ptr_MyTemplateMatrix); + geometry_wrapper(72, obj.ptr_MyTemplateMatrix); end function display(obj), obj.print(''); end @@ -58,7 +58,7 @@ classdef MyTemplateMatrix < MyBase % ACCEPT_T usage: accept_T(Matrix value) : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - geometry_wrapper(67, this, varargin{:}); + geometry_wrapper(73, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.accept_T'); @@ -68,7 +68,7 @@ classdef MyTemplateMatrix < MyBase % ACCEPT_TPTR usage: accept_Tptr(Matrix value) : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - geometry_wrapper(68, this, varargin{:}); + geometry_wrapper(74, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.accept_Tptr'); @@ -78,7 +78,7 @@ classdef MyTemplateMatrix < MyBase % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Matrix, Matrix > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(69, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(75, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.create_MixedPtrs'); @@ -88,7 +88,7 @@ classdef MyTemplateMatrix < MyBase % CREATE_PTRS usage: create_ptrs() : returns pair< Matrix, Matrix > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(70, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(76, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.create_ptrs'); @@ -98,7 +98,7 @@ classdef MyTemplateMatrix < MyBase % RETURN_T usage: return_T(Matrix value) : returns Matrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(71, this, varargin{:}); + varargout{1} = geometry_wrapper(77, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.return_T'); @@ -108,7 +108,7 @@ classdef MyTemplateMatrix < MyBase % RETURN_TPTR usage: return_Tptr(Matrix value) : returns Matrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(72, this, varargin{:}); + varargout{1} = geometry_wrapper(78, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.return_Tptr'); @@ -118,7 +118,7 @@ classdef MyTemplateMatrix < MyBase % RETURN_PTRS usage: return_ptrs(Matrix p1, Matrix p2) : returns pair< Matrix, Matrix > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') - [ varargout{1} varargout{2} ] = geometry_wrapper(73, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(79, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.return_ptrs'); @@ -128,7 +128,7 @@ classdef MyTemplateMatrix < MyBase % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns Matrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(74, this, varargin{:}); + varargout{1} = geometry_wrapper(80, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethodMatrix'); @@ -138,7 +138,7 @@ classdef MyTemplateMatrix < MyBase % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns Point2 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(75, this, varargin{:}); + varargout{1} = geometry_wrapper(81, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethodPoint2'); @@ -148,7 +148,7 @@ classdef MyTemplateMatrix < MyBase % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns Point3 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==3 && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(76, this, varargin{:}); + varargout{1} = geometry_wrapper(82, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethodPoint3'); @@ -158,7 +158,7 @@ classdef MyTemplateMatrix < MyBase % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns Vector % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(77, this, varargin{:}); + varargout{1} = geometry_wrapper(83, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethodVector'); @@ -171,7 +171,7 @@ classdef MyTemplateMatrix < MyBase % LEVEL usage: Level(Matrix K) : returns MyTemplateMatrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(78, varargin{:}); + varargout{1} = geometry_wrapper(84, varargin{:}); return end diff --git a/tests/expected-matlab/MyTemplatePoint2.m b/tests/expected-matlab/MyTemplatePoint2.m index 89fb3c452..2a73f98da 100644 --- a/tests/expected-matlab/MyTemplatePoint2.m +++ b/tests/expected-matlab/MyTemplatePoint2.m @@ -34,11 +34,11 @@ classdef MyTemplatePoint2 < MyBase if nargin == 2 my_ptr = varargin{2}; else - my_ptr = geometry_wrapper(48, varargin{2}); + my_ptr = geometry_wrapper(54, varargin{2}); end - base_ptr = geometry_wrapper(47, my_ptr); + base_ptr = geometry_wrapper(53, my_ptr); elseif nargin == 0 - [ my_ptr, base_ptr ] = geometry_wrapper(49); + [ my_ptr, base_ptr ] = geometry_wrapper(55); else error('Arguments do not match any overload of MyTemplatePoint2 constructor'); end @@ -47,7 +47,7 @@ classdef MyTemplatePoint2 < MyBase end function delete(obj) - geometry_wrapper(50, obj.ptr_MyTemplatePoint2); + geometry_wrapper(56, obj.ptr_MyTemplatePoint2); end function display(obj), obj.print(''); end @@ -58,7 +58,7 @@ classdef MyTemplatePoint2 < MyBase % ACCEPT_T usage: accept_T(Point2 value) : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 - geometry_wrapper(51, this, varargin{:}); + geometry_wrapper(57, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.accept_T'); @@ -68,7 +68,7 @@ classdef MyTemplatePoint2 < MyBase % ACCEPT_TPTR usage: accept_Tptr(Point2 value) : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 - geometry_wrapper(52, this, varargin{:}); + geometry_wrapper(58, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.accept_Tptr'); @@ -78,7 +78,7 @@ classdef MyTemplatePoint2 < MyBase % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Point2, Point2 > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(53, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(59, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.create_MixedPtrs'); @@ -88,7 +88,7 @@ classdef MyTemplatePoint2 < MyBase % CREATE_PTRS usage: create_ptrs() : returns pair< Point2, Point2 > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(54, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(60, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.create_ptrs'); @@ -98,7 +98,7 @@ classdef MyTemplatePoint2 < MyBase % RETURN_T usage: return_T(Point2 value) : returns Point2 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(55, this, varargin{:}); + varargout{1} = geometry_wrapper(61, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.return_T'); @@ -108,7 +108,7 @@ classdef MyTemplatePoint2 < MyBase % RETURN_TPTR usage: return_Tptr(Point2 value) : returns Point2 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(56, this, varargin{:}); + varargout{1} = geometry_wrapper(62, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.return_Tptr'); @@ -118,7 +118,7 @@ classdef MyTemplatePoint2 < MyBase % RETURN_PTRS usage: return_ptrs(Point2 p1, Point2 p2) : returns pair< Point2, Point2 > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 2 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 && isa(varargin{2},'double') && size(varargin{2},1)==2 && size(varargin{2},2)==1 - [ varargout{1} varargout{2} ] = geometry_wrapper(57, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(63, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.return_ptrs'); @@ -128,7 +128,7 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns Matrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(58, this, varargin{:}); + varargout{1} = geometry_wrapper(64, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethodMatrix'); @@ -138,7 +138,7 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns Point2 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(59, this, varargin{:}); + varargout{1} = geometry_wrapper(65, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethodPoint2'); @@ -148,7 +148,7 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns Point3 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==3 && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(60, this, varargin{:}); + varargout{1} = geometry_wrapper(66, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethodPoint3'); @@ -158,7 +158,7 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns Vector % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(61, this, varargin{:}); + varargout{1} = geometry_wrapper(67, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethodVector'); @@ -171,7 +171,7 @@ classdef MyTemplatePoint2 < MyBase % LEVEL usage: Level(Point2 K) : returns MyTemplatePoint2 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(62, varargin{:}); + varargout{1} = geometry_wrapper(68, varargin{:}); return end diff --git a/tests/expected-matlab/MyVector12.m b/tests/expected-matlab/MyVector12.m index 8e13cc993..0cba5c7c1 100644 --- a/tests/expected-matlab/MyVector12.m +++ b/tests/expected-matlab/MyVector12.m @@ -12,9 +12,9 @@ classdef MyVector12 < handle function obj = MyVector12(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - geometry_wrapper(86, my_ptr); + geometry_wrapper(92, my_ptr); elseif nargin == 0 - my_ptr = geometry_wrapper(87); + my_ptr = geometry_wrapper(93); else error('Arguments do not match any overload of MyVector12 constructor'); end @@ -22,7 +22,7 @@ classdef MyVector12 < handle end function delete(obj) - geometry_wrapper(88, obj.ptr_MyVector12); + geometry_wrapper(94, obj.ptr_MyVector12); end function display(obj), obj.print(''); end diff --git a/tests/expected-matlab/MyVector3.m b/tests/expected-matlab/MyVector3.m index 1f8140f4f..a619c5133 100644 --- a/tests/expected-matlab/MyVector3.m +++ b/tests/expected-matlab/MyVector3.m @@ -12,9 +12,9 @@ classdef MyVector3 < handle function obj = MyVector3(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - geometry_wrapper(83, my_ptr); + geometry_wrapper(89, my_ptr); elseif nargin == 0 - my_ptr = geometry_wrapper(84); + my_ptr = geometry_wrapper(90); else error('Arguments do not match any overload of MyVector3 constructor'); end @@ -22,7 +22,7 @@ classdef MyVector3 < handle end function delete(obj) - geometry_wrapper(85, obj.ptr_MyVector3); + geometry_wrapper(91, obj.ptr_MyVector3); end function display(obj), obj.print(''); end diff --git a/tests/expected-matlab/Test.m b/tests/expected-matlab/Test.m index 16b5289c4..d6d375fdf 100644 --- a/tests/expected-matlab/Test.m +++ b/tests/expected-matlab/Test.m @@ -35,11 +35,11 @@ classdef Test < handle function obj = Test(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - geometry_wrapper(20, my_ptr); + geometry_wrapper(26, my_ptr); elseif nargin == 0 - my_ptr = geometry_wrapper(21); + my_ptr = geometry_wrapper(27); elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') - my_ptr = geometry_wrapper(22, varargin{1}, varargin{2}); + my_ptr = geometry_wrapper(28, varargin{1}, varargin{2}); else error('Arguments do not match any overload of Test constructor'); end @@ -47,7 +47,7 @@ classdef Test < handle end function delete(obj) - geometry_wrapper(23, obj.ptr_Test); + geometry_wrapper(29, obj.ptr_Test); end function display(obj), obj.print(''); end @@ -58,7 +58,7 @@ classdef Test < handle % ARG_EIGENCONSTREF usage: arg_EigenConstRef(Matrix value) : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - geometry_wrapper(24, this, varargin{:}); + geometry_wrapper(30, this, varargin{:}); return end error('Arguments do not match any overload of function Test.arg_EigenConstRef'); @@ -68,7 +68,7 @@ classdef Test < handle % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Test, Test > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(25, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(31, this, varargin{:}); return end error('Arguments do not match any overload of function Test.create_MixedPtrs'); @@ -78,7 +78,7 @@ classdef Test < handle % CREATE_PTRS usage: create_ptrs() : returns pair< Test, Test > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(26, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(32, this, varargin{:}); return end error('Arguments do not match any overload of function Test.create_ptrs'); @@ -88,7 +88,7 @@ classdef Test < handle % PRINT usage: print() : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - geometry_wrapper(27, this, varargin{:}); + geometry_wrapper(33, this, varargin{:}); return end error('Arguments do not match any overload of function Test.print'); @@ -98,7 +98,7 @@ classdef Test < handle % RETURN_POINT2PTR usage: return_Point2Ptr(bool value) : returns Point2 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'logical') - varargout{1} = geometry_wrapper(28, this, varargin{:}); + varargout{1} = geometry_wrapper(34, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_Point2Ptr'); @@ -108,7 +108,7 @@ classdef Test < handle % RETURN_TEST usage: return_Test(Test value) : returns Test % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(29, this, varargin{:}); + varargout{1} = geometry_wrapper(35, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_Test'); @@ -118,7 +118,7 @@ classdef Test < handle % RETURN_TESTPTR usage: return_TestPtr(Test value) : returns Test % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(30, this, varargin{:}); + varargout{1} = geometry_wrapper(36, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_TestPtr'); @@ -128,7 +128,7 @@ classdef Test < handle % RETURN_BOOL usage: return_bool(bool value) : returns bool % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'logical') - varargout{1} = geometry_wrapper(31, this, varargin{:}); + varargout{1} = geometry_wrapper(37, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_bool'); @@ -138,7 +138,7 @@ classdef Test < handle % RETURN_DOUBLE usage: return_double(double value) : returns double % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(32, this, varargin{:}); + varargout{1} = geometry_wrapper(38, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_double'); @@ -148,7 +148,7 @@ classdef Test < handle % RETURN_FIELD usage: return_field(Test t) : returns bool % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(33, this, varargin{:}); + varargout{1} = geometry_wrapper(39, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_field'); @@ -158,7 +158,7 @@ classdef Test < handle % RETURN_INT usage: return_int(int value) : returns int % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = geometry_wrapper(34, this, varargin{:}); + varargout{1} = geometry_wrapper(40, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_int'); @@ -168,7 +168,7 @@ classdef Test < handle % RETURN_MATRIX1 usage: return_matrix1(Matrix value) : returns Matrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(35, this, varargin{:}); + varargout{1} = geometry_wrapper(41, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_matrix1'); @@ -178,7 +178,7 @@ classdef Test < handle % RETURN_MATRIX2 usage: return_matrix2(Matrix value) : returns Matrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(36, this, varargin{:}); + varargout{1} = geometry_wrapper(42, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_matrix2'); @@ -188,13 +188,13 @@ classdef Test < handle % RETURN_PAIR usage: return_pair(Vector v, Matrix A) : returns pair< Vector, Matrix > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 2 && isa(varargin{1},'double') && size(varargin{1},2)==1 && isa(varargin{2},'double') - [ varargout{1} varargout{2} ] = geometry_wrapper(37, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(43, this, varargin{:}); return end % RETURN_PAIR usage: return_pair(Vector v) : returns pair< Vector, Matrix > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 - [ varargout{1} varargout{2} ] = geometry_wrapper(38, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(44, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_pair'); @@ -204,7 +204,7 @@ classdef Test < handle % RETURN_PTRS usage: return_ptrs(Test p1, Test p2) : returns pair< Test, Test > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 2 && isa(varargin{1},'Test') && isa(varargin{2},'Test') - [ varargout{1} varargout{2} ] = geometry_wrapper(39, this, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(45, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_ptrs'); @@ -214,7 +214,7 @@ classdef Test < handle % RETURN_SIZE_T usage: return_size_t(size_t value) : returns size_t % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = geometry_wrapper(40, this, varargin{:}); + varargout{1} = geometry_wrapper(46, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_size_t'); @@ -224,7 +224,7 @@ classdef Test < handle % RETURN_STRING usage: return_string(string value) : returns string % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'char') - varargout{1} = geometry_wrapper(41, this, varargin{:}); + varargout{1} = geometry_wrapper(47, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_string'); @@ -234,7 +234,7 @@ classdef Test < handle % RETURN_VECTOR1 usage: return_vector1(Vector value) : returns Vector % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(42, this, varargin{:}); + varargout{1} = geometry_wrapper(48, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_vector1'); @@ -244,7 +244,7 @@ classdef Test < handle % RETURN_VECTOR2 usage: return_vector2(Vector value) : returns Vector % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(43, this, varargin{:}); + varargout{1} = geometry_wrapper(49, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_vector2'); diff --git a/tests/expected-matlab/aGlobalFunction.m b/tests/expected-matlab/aGlobalFunction.m index 8f1c65821..d262d9ed0 100644 --- a/tests/expected-matlab/aGlobalFunction.m +++ b/tests/expected-matlab/aGlobalFunction.m @@ -1,6 +1,6 @@ function varargout = aGlobalFunction(varargin) if length(varargin) == 0 - varargout{1} = geometry_wrapper(99, varargin{:}); + varargout{1} = geometry_wrapper(105, varargin{:}); else error('Arguments do not match any overload of function aGlobalFunction'); end diff --git a/tests/expected-matlab/geometry_wrapper.cpp b/tests/expected-matlab/geometry_wrapper.cpp index 98d723fab..703ca76ae 100644 --- a/tests/expected-matlab/geometry_wrapper.cpp +++ b/tests/expected-matlab/geometry_wrapper.cpp @@ -216,7 +216,55 @@ void gtsamPoint2_argChar_4(int nargout, mxArray *out[], int nargin, const mxArra obj->argChar(a); } -void gtsamPoint2_argUChar_5(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_argChar_5(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("argChar",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + boost::shared_ptr a = unwrap_shared_ptr< char >(in[1], "ptr_char"); + obj->argChar(a); +} + +void gtsamPoint2_argChar_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("argChar",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + char a = unwrap< char >(in[1]); + obj->argChar(a); +} + +void gtsamPoint2_argChar_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("argChar",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + boost::shared_ptr a = unwrap_shared_ptr< char >(in[1], "ptr_char"); + obj->argChar(a); +} + +void gtsamPoint2_argChar_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("argChar",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + boost::shared_ptr a = unwrap_shared_ptr< char >(in[1], "ptr_char"); + obj->argChar(a); +} + +void gtsamPoint2_argChar_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("argChar",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + char a = unwrap< char >(in[1]); + obj->argChar(a); +} + +void gtsamPoint2_argChar_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("argChar",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + boost::shared_ptr a = unwrap_shared_ptr< char >(in[1], "ptr_char"); + obj->argChar(a); +} + +void gtsamPoint2_argUChar_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("argUChar",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); @@ -224,14 +272,14 @@ void gtsamPoint2_argUChar_5(int nargout, mxArray *out[], int nargin, const mxArr obj->argUChar(a); } -void gtsamPoint2_dim_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_dim_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("dim",nargout,nargin-1,0); auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); out[0] = wrap< int >(obj->dim()); } -void gtsamPoint2_eigenArguments_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_eigenArguments_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("eigenArguments",nargout,nargin-1,2); auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); @@ -240,35 +288,35 @@ void gtsamPoint2_eigenArguments_7(int nargout, mxArray *out[], int nargin, const obj->eigenArguments(v,m); } -void gtsamPoint2_returnChar_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_returnChar_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("returnChar",nargout,nargin-1,0); auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); out[0] = wrap< char >(obj->returnChar()); } -void gtsamPoint2_vectorConfusion_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_vectorConfusion_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("vectorConfusion",nargout,nargin-1,0); auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); out[0] = wrap_shared_ptr(boost::make_shared(obj->vectorConfusion()),"VectorNotEigen", false); } -void gtsamPoint2_x_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_x_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("x",nargout,nargin-1,0); auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); out[0] = wrap< double >(obj->x()); } -void gtsamPoint2_y_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint2_y_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("y",nargout,nargin-1,0); auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); out[0] = wrap< double >(obj->y()); } -void gtsamPoint3_collectorInsertAndMakeBase_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_collectorInsertAndMakeBase_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -277,7 +325,7 @@ void gtsamPoint3_collectorInsertAndMakeBase_12(int nargout, mxArray *out[], int collector_gtsamPoint3.insert(self); } -void gtsamPoint3_constructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -291,7 +339,7 @@ void gtsamPoint3_constructor_13(int nargout, mxArray *out[], int nargin, const m *reinterpret_cast (mxGetData(out[0])) = self; } -void gtsamPoint3_deconstructor_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_deconstructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_gtsamPoint3",nargout,nargin,1); @@ -304,14 +352,14 @@ void gtsamPoint3_deconstructor_14(int nargout, mxArray *out[], int nargin, const } } -void gtsamPoint3_norm_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_norm_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("norm",nargout,nargin-1,0); auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint3"); out[0] = wrap< double >(obj->norm()); } -void gtsamPoint3_string_serialize_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_string_serialize_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("string_serialize",nargout,nargin-1,0); @@ -321,20 +369,20 @@ void gtsamPoint3_string_serialize_16(int nargout, mxArray *out[], int nargin, co out_archive << *obj; out[0] = wrap< string >(out_archive_stream.str()); } -void gtsamPoint3_StaticFunctionRet_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_StaticFunctionRet_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("gtsamPoint3.StaticFunctionRet",nargout,nargin,1); double z = unwrap< double >(in[0]); out[0] = wrap< Point3 >(gtsam::Point3::StaticFunctionRet(z)); } -void gtsamPoint3_staticFunction_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_staticFunction_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("gtsamPoint3.staticFunction",nargout,nargin,0); out[0] = wrap< double >(gtsam::Point3::staticFunction()); } -void gtsamPoint3_string_deserialize_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void gtsamPoint3_string_deserialize_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("gtsamPoint3.string_deserialize",nargout,nargin,1); @@ -345,7 +393,7 @@ void gtsamPoint3_string_deserialize_19(int nargout, mxArray *out[], int nargin, in_archive >> *output; out[0] = wrap_shared_ptr(output,"gtsam.Point3", false); } -void Test_collectorInsertAndMakeBase_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_collectorInsertAndMakeBase_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -354,7 +402,7 @@ void Test_collectorInsertAndMakeBase_20(int nargout, mxArray *out[], int nargin, collector_Test.insert(self); } -void Test_constructor_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_constructor_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -365,7 +413,7 @@ void Test_constructor_21(int nargout, mxArray *out[], int nargin, const mxArray *reinterpret_cast (mxGetData(out[0])) = self; } -void Test_constructor_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_constructor_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -378,7 +426,7 @@ void Test_constructor_22(int nargout, mxArray *out[], int nargin, const mxArray *reinterpret_cast (mxGetData(out[0])) = self; } -void Test_deconstructor_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_deconstructor_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_Test",nargout,nargin,1); @@ -391,7 +439,7 @@ void Test_deconstructor_23(int nargout, mxArray *out[], int nargin, const mxArra } } -void Test_arg_EigenConstRef_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_arg_EigenConstRef_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("arg_EigenConstRef",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -399,7 +447,7 @@ void Test_arg_EigenConstRef_24(int nargout, mxArray *out[], int nargin, const mx obj->arg_EigenConstRef(value); } -void Test_create_MixedPtrs_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_create_MixedPtrs_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("create_MixedPtrs",nargout,nargin-1,0); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -408,7 +456,7 @@ void Test_create_MixedPtrs_25(int nargout, mxArray *out[], int nargin, const mxA out[1] = wrap_shared_ptr(pairResult.second,"Test", false); } -void Test_create_ptrs_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_create_ptrs_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("create_ptrs",nargout,nargin-1,0); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -417,14 +465,14 @@ void Test_create_ptrs_26(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap_shared_ptr(pairResult.second,"Test", false); } -void Test_print_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_print_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("print",nargout,nargin-1,0); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); obj->print(); } -void Test_return_Point2Ptr_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_Point2Ptr_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_Point2Ptr",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -435,7 +483,7 @@ void Test_return_Point2Ptr_28(int nargout, mxArray *out[], int nargin, const mxA } } -void Test_return_Test_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_Test_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_Test",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -443,7 +491,7 @@ void Test_return_Test_29(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap_shared_ptr(boost::make_shared(obj->return_Test(value)),"Test", false); } -void Test_return_TestPtr_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_TestPtr_36(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_TestPtr",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -451,7 +499,7 @@ void Test_return_TestPtr_30(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap_shared_ptr(obj->return_TestPtr(value),"Test", false); } -void Test_return_bool_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_bool_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_bool",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -459,7 +507,7 @@ void Test_return_bool_31(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap< bool >(obj->return_bool(value)); } -void Test_return_double_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_double_38(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_double",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -467,7 +515,7 @@ void Test_return_double_32(int nargout, mxArray *out[], int nargin, const mxArra out[0] = wrap< double >(obj->return_double(value)); } -void Test_return_field_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_field_39(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_field",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -475,7 +523,7 @@ void Test_return_field_33(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap< bool >(obj->return_field(t)); } -void Test_return_int_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_int_40(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_int",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -483,7 +531,7 @@ void Test_return_int_34(int nargout, mxArray *out[], int nargin, const mxArray * out[0] = wrap< int >(obj->return_int(value)); } -void Test_return_matrix1_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_matrix1_41(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_matrix1",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -491,7 +539,7 @@ void Test_return_matrix1_35(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Matrix >(obj->return_matrix1(value)); } -void Test_return_matrix2_36(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_matrix2_42(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_matrix2",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -499,7 +547,7 @@ void Test_return_matrix2_36(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Matrix >(obj->return_matrix2(value)); } -void Test_return_pair_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_pair_43(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_pair",nargout,nargin-1,2); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -510,7 +558,7 @@ void Test_return_pair_37(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap< Matrix >(pairResult.second); } -void Test_return_pair_38(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_pair_44(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_pair",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -520,7 +568,7 @@ void Test_return_pair_38(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap< Matrix >(pairResult.second); } -void Test_return_ptrs_39(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_ptrs_45(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_ptrs",nargout,nargin-1,2); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -531,7 +579,7 @@ void Test_return_ptrs_39(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap_shared_ptr(pairResult.second,"Test", false); } -void Test_return_size_t_40(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_size_t_46(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_size_t",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -539,7 +587,7 @@ void Test_return_size_t_40(int nargout, mxArray *out[], int nargin, const mxArra out[0] = wrap< size_t >(obj->return_size_t(value)); } -void Test_return_string_41(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_string_47(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_string",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -547,7 +595,7 @@ void Test_return_string_41(int nargout, mxArray *out[], int nargin, const mxArra out[0] = wrap< string >(obj->return_string(value)); } -void Test_return_vector1_42(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_vector1_48(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_vector1",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -555,7 +603,7 @@ void Test_return_vector1_42(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Vector >(obj->return_vector1(value)); } -void Test_return_vector2_43(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_vector2_49(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_vector2",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -563,7 +611,7 @@ void Test_return_vector2_43(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Vector >(obj->return_vector2(value)); } -void MyBase_collectorInsertAndMakeBase_44(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyBase_collectorInsertAndMakeBase_50(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -572,7 +620,7 @@ void MyBase_collectorInsertAndMakeBase_44(int nargout, mxArray *out[], int nargi collector_MyBase.insert(self); } -void MyBase_upcastFromVoid_45(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { +void MyBase_upcastFromVoid_51(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; boost::shared_ptr *asVoid = *reinterpret_cast**> (mxGetData(in[0])); @@ -581,7 +629,7 @@ void MyBase_upcastFromVoid_45(int nargout, mxArray *out[], int nargin, const mxA *reinterpret_cast(mxGetData(out[0])) = self; } -void MyBase_deconstructor_46(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyBase_deconstructor_52(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_MyBase",nargout,nargin,1); @@ -594,7 +642,7 @@ void MyBase_deconstructor_46(int nargout, mxArray *out[], int nargin, const mxAr } } -void MyTemplatePoint2_collectorInsertAndMakeBase_47(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_collectorInsertAndMakeBase_53(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -607,7 +655,7 @@ void MyTemplatePoint2_collectorInsertAndMakeBase_47(int nargout, mxArray *out[], *reinterpret_cast(mxGetData(out[0])) = new SharedBase(*self); } -void MyTemplatePoint2_upcastFromVoid_48(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { +void MyTemplatePoint2_upcastFromVoid_54(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; boost::shared_ptr *asVoid = *reinterpret_cast**> (mxGetData(in[0])); @@ -616,7 +664,7 @@ void MyTemplatePoint2_upcastFromVoid_48(int nargout, mxArray *out[], int nargin, *reinterpret_cast(mxGetData(out[0])) = self; } -void MyTemplatePoint2_constructor_49(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_constructor_55(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -631,7 +679,7 @@ void MyTemplatePoint2_constructor_49(int nargout, mxArray *out[], int nargin, co *reinterpret_cast(mxGetData(out[1])) = new SharedBase(*self); } -void MyTemplatePoint2_deconstructor_50(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_deconstructor_56(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr> Shared; checkArguments("delete_MyTemplatePoint2",nargout,nargin,1); @@ -644,7 +692,7 @@ void MyTemplatePoint2_deconstructor_50(int nargout, mxArray *out[], int nargin, } } -void MyTemplatePoint2_accept_T_51(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_accept_T_57(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("accept_T",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); @@ -652,7 +700,7 @@ void MyTemplatePoint2_accept_T_51(int nargout, mxArray *out[], int nargin, const obj->accept_T(value); } -void MyTemplatePoint2_accept_Tptr_52(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_accept_Tptr_58(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("accept_Tptr",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); @@ -660,7 +708,7 @@ void MyTemplatePoint2_accept_Tptr_52(int nargout, mxArray *out[], int nargin, co obj->accept_Tptr(value); } -void MyTemplatePoint2_create_MixedPtrs_53(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_create_MixedPtrs_59(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("create_MixedPtrs",nargout,nargin-1,0); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); @@ -672,7 +720,7 @@ void MyTemplatePoint2_create_MixedPtrs_53(int nargout, mxArray *out[], int nargi } } -void MyTemplatePoint2_create_ptrs_54(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_create_ptrs_60(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("create_ptrs",nargout,nargin-1,0); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); @@ -687,7 +735,7 @@ void MyTemplatePoint2_create_ptrs_54(int nargout, mxArray *out[], int nargin, co } } -void MyTemplatePoint2_return_T_55(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_return_T_61(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_T",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); @@ -695,7 +743,7 @@ void MyTemplatePoint2_return_T_55(int nargout, mxArray *out[], int nargin, const out[0] = wrap< Point2 >(obj->return_T(value)); } -void MyTemplatePoint2_return_Tptr_56(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_return_Tptr_62(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_Tptr",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); @@ -706,7 +754,7 @@ void MyTemplatePoint2_return_Tptr_56(int nargout, mxArray *out[], int nargin, co } } -void MyTemplatePoint2_return_ptrs_57(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_return_ptrs_63(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_ptrs",nargout,nargin-1,2); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); @@ -723,7 +771,7 @@ void MyTemplatePoint2_return_ptrs_57(int nargout, mxArray *out[], int nargin, co } } -void MyTemplatePoint2_templatedMethod_58(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_templatedMethod_64(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("templatedMethodMatrix",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); @@ -731,7 +779,7 @@ void MyTemplatePoint2_templatedMethod_58(int nargout, mxArray *out[], int nargin out[0] = wrap< Matrix >(obj->templatedMethod(t)); } -void MyTemplatePoint2_templatedMethod_59(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_templatedMethod_65(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("templatedMethodPoint2",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); @@ -739,7 +787,7 @@ void MyTemplatePoint2_templatedMethod_59(int nargout, mxArray *out[], int nargin out[0] = wrap< Point2 >(obj->templatedMethod(t)); } -void MyTemplatePoint2_templatedMethod_60(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_templatedMethod_66(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("templatedMethodPoint3",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); @@ -747,7 +795,7 @@ void MyTemplatePoint2_templatedMethod_60(int nargout, mxArray *out[], int nargin out[0] = wrap< Point3 >(obj->templatedMethod(t)); } -void MyTemplatePoint2_templatedMethod_61(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_templatedMethod_67(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("templatedMethodVector",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); @@ -755,14 +803,14 @@ void MyTemplatePoint2_templatedMethod_61(int nargout, mxArray *out[], int nargin out[0] = wrap< Vector >(obj->templatedMethod(t)); } -void MyTemplatePoint2_Level_62(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplatePoint2_Level_68(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("MyTemplatePoint2.Level",nargout,nargin,1); Point2 K = unwrap< Point2 >(in[0]); out[0] = wrap_shared_ptr(boost::make_shared>(MyTemplate::Level(K)),"MyTemplatePoint2", false); } -void MyTemplateMatrix_collectorInsertAndMakeBase_63(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_collectorInsertAndMakeBase_69(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -775,7 +823,7 @@ void MyTemplateMatrix_collectorInsertAndMakeBase_63(int nargout, mxArray *out[], *reinterpret_cast(mxGetData(out[0])) = new SharedBase(*self); } -void MyTemplateMatrix_upcastFromVoid_64(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { +void MyTemplateMatrix_upcastFromVoid_70(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; boost::shared_ptr *asVoid = *reinterpret_cast**> (mxGetData(in[0])); @@ -784,7 +832,7 @@ void MyTemplateMatrix_upcastFromVoid_64(int nargout, mxArray *out[], int nargin, *reinterpret_cast(mxGetData(out[0])) = self; } -void MyTemplateMatrix_constructor_65(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_constructor_71(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -799,7 +847,7 @@ void MyTemplateMatrix_constructor_65(int nargout, mxArray *out[], int nargin, co *reinterpret_cast(mxGetData(out[1])) = new SharedBase(*self); } -void MyTemplateMatrix_deconstructor_66(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_deconstructor_72(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr> Shared; checkArguments("delete_MyTemplateMatrix",nargout,nargin,1); @@ -812,7 +860,7 @@ void MyTemplateMatrix_deconstructor_66(int nargout, mxArray *out[], int nargin, } } -void MyTemplateMatrix_accept_T_67(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_accept_T_73(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("accept_T",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); @@ -820,7 +868,7 @@ void MyTemplateMatrix_accept_T_67(int nargout, mxArray *out[], int nargin, const obj->accept_T(value); } -void MyTemplateMatrix_accept_Tptr_68(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_accept_Tptr_74(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("accept_Tptr",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); @@ -828,7 +876,7 @@ void MyTemplateMatrix_accept_Tptr_68(int nargout, mxArray *out[], int nargin, co obj->accept_Tptr(value); } -void MyTemplateMatrix_create_MixedPtrs_69(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_create_MixedPtrs_75(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("create_MixedPtrs",nargout,nargin-1,0); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); @@ -840,7 +888,7 @@ void MyTemplateMatrix_create_MixedPtrs_69(int nargout, mxArray *out[], int nargi } } -void MyTemplateMatrix_create_ptrs_70(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_create_ptrs_76(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("create_ptrs",nargout,nargin-1,0); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); @@ -855,7 +903,7 @@ void MyTemplateMatrix_create_ptrs_70(int nargout, mxArray *out[], int nargin, co } } -void MyTemplateMatrix_return_T_71(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_return_T_77(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_T",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); @@ -863,7 +911,7 @@ void MyTemplateMatrix_return_T_71(int nargout, mxArray *out[], int nargin, const out[0] = wrap< Matrix >(obj->return_T(value)); } -void MyTemplateMatrix_return_Tptr_72(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_return_Tptr_78(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_Tptr",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); @@ -874,7 +922,7 @@ void MyTemplateMatrix_return_Tptr_72(int nargout, mxArray *out[], int nargin, co } } -void MyTemplateMatrix_return_ptrs_73(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_return_ptrs_79(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_ptrs",nargout,nargin-1,2); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); @@ -891,7 +939,7 @@ void MyTemplateMatrix_return_ptrs_73(int nargout, mxArray *out[], int nargin, co } } -void MyTemplateMatrix_templatedMethod_74(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_templatedMethod_80(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("templatedMethodMatrix",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); @@ -899,7 +947,7 @@ void MyTemplateMatrix_templatedMethod_74(int nargout, mxArray *out[], int nargin out[0] = wrap< Matrix >(obj->templatedMethod(t)); } -void MyTemplateMatrix_templatedMethod_75(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_templatedMethod_81(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("templatedMethodPoint2",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); @@ -907,7 +955,7 @@ void MyTemplateMatrix_templatedMethod_75(int nargout, mxArray *out[], int nargin out[0] = wrap< Point2 >(obj->templatedMethod(t)); } -void MyTemplateMatrix_templatedMethod_76(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_templatedMethod_82(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("templatedMethodPoint3",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); @@ -915,7 +963,7 @@ void MyTemplateMatrix_templatedMethod_76(int nargout, mxArray *out[], int nargin out[0] = wrap< Point3 >(obj->templatedMethod(t)); } -void MyTemplateMatrix_templatedMethod_77(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_templatedMethod_83(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("templatedMethodVector",nargout,nargin-1,1); auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); @@ -923,14 +971,14 @@ void MyTemplateMatrix_templatedMethod_77(int nargout, mxArray *out[], int nargin out[0] = wrap< Vector >(obj->templatedMethod(t)); } -void MyTemplateMatrix_Level_78(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyTemplateMatrix_Level_84(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("MyTemplateMatrix.Level",nargout,nargin,1); Matrix K = unwrap< Matrix >(in[0]); out[0] = wrap_shared_ptr(boost::make_shared>(MyTemplate::Level(K)),"MyTemplateMatrix", false); } -void PrimitiveRefDouble_collectorInsertAndMakeBase_79(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void PrimitiveRefDouble_collectorInsertAndMakeBase_85(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -939,7 +987,7 @@ void PrimitiveRefDouble_collectorInsertAndMakeBase_79(int nargout, mxArray *out[ collector_PrimitiveRefDouble.insert(self); } -void PrimitiveRefDouble_constructor_80(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void PrimitiveRefDouble_constructor_86(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -950,7 +998,7 @@ void PrimitiveRefDouble_constructor_80(int nargout, mxArray *out[], int nargin, *reinterpret_cast (mxGetData(out[0])) = self; } -void PrimitiveRefDouble_deconstructor_81(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void PrimitiveRefDouble_deconstructor_87(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr> Shared; checkArguments("delete_PrimitiveRefDouble",nargout,nargin,1); @@ -963,14 +1011,14 @@ void PrimitiveRefDouble_deconstructor_81(int nargout, mxArray *out[], int nargin } } -void PrimitiveRefDouble_Brutal_82(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void PrimitiveRefDouble_Brutal_88(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("PrimitiveRefDouble.Brutal",nargout,nargin,1); double t = unwrap< double >(in[0]); out[0] = wrap_shared_ptr(boost::make_shared>(PrimitiveRef::Brutal(t)),"PrimitiveRefdouble", false); } -void MyVector3_collectorInsertAndMakeBase_83(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyVector3_collectorInsertAndMakeBase_89(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -979,7 +1027,7 @@ void MyVector3_collectorInsertAndMakeBase_83(int nargout, mxArray *out[], int na collector_MyVector3.insert(self); } -void MyVector3_constructor_84(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyVector3_constructor_90(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -990,7 +1038,7 @@ void MyVector3_constructor_84(int nargout, mxArray *out[], int nargin, const mxA *reinterpret_cast (mxGetData(out[0])) = self; } -void MyVector3_deconstructor_85(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyVector3_deconstructor_91(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr> Shared; checkArguments("delete_MyVector3",nargout,nargin,1); @@ -1003,7 +1051,7 @@ void MyVector3_deconstructor_85(int nargout, mxArray *out[], int nargin, const m } } -void MyVector12_collectorInsertAndMakeBase_86(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyVector12_collectorInsertAndMakeBase_92(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -1012,7 +1060,7 @@ void MyVector12_collectorInsertAndMakeBase_86(int nargout, mxArray *out[], int n collector_MyVector12.insert(self); } -void MyVector12_constructor_87(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyVector12_constructor_93(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -1023,7 +1071,7 @@ void MyVector12_constructor_87(int nargout, mxArray *out[], int nargin, const mx *reinterpret_cast (mxGetData(out[0])) = self; } -void MyVector12_deconstructor_88(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyVector12_deconstructor_94(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr> Shared; checkArguments("delete_MyVector12",nargout,nargin,1); @@ -1036,7 +1084,7 @@ void MyVector12_deconstructor_88(int nargout, mxArray *out[], int nargin, const } } -void MultipleTemplatesIntDouble_collectorInsertAndMakeBase_89(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MultipleTemplatesIntDouble_collectorInsertAndMakeBase_95(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -1045,7 +1093,7 @@ void MultipleTemplatesIntDouble_collectorInsertAndMakeBase_89(int nargout, mxArr collector_MultipleTemplatesIntDouble.insert(self); } -void MultipleTemplatesIntDouble_deconstructor_90(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MultipleTemplatesIntDouble_deconstructor_96(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr> Shared; checkArguments("delete_MultipleTemplatesIntDouble",nargout,nargin,1); @@ -1058,7 +1106,7 @@ void MultipleTemplatesIntDouble_deconstructor_90(int nargout, mxArray *out[], in } } -void MultipleTemplatesIntFloat_collectorInsertAndMakeBase_91(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MultipleTemplatesIntFloat_collectorInsertAndMakeBase_97(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -1067,7 +1115,7 @@ void MultipleTemplatesIntFloat_collectorInsertAndMakeBase_91(int nargout, mxArra collector_MultipleTemplatesIntFloat.insert(self); } -void MultipleTemplatesIntFloat_deconstructor_92(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MultipleTemplatesIntFloat_deconstructor_98(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr> Shared; checkArguments("delete_MultipleTemplatesIntFloat",nargout,nargin,1); @@ -1080,7 +1128,7 @@ void MultipleTemplatesIntFloat_deconstructor_92(int nargout, mxArray *out[], int } } -void MyFactorPosePoint2_collectorInsertAndMakeBase_93(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_collectorInsertAndMakeBase_99(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -1089,7 +1137,7 @@ void MyFactorPosePoint2_collectorInsertAndMakeBase_93(int nargout, mxArray *out[ collector_MyFactorPosePoint2.insert(self); } -void MyFactorPosePoint2_constructor_94(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_constructor_100(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -1104,7 +1152,7 @@ void MyFactorPosePoint2_constructor_94(int nargout, mxArray *out[], int nargin, *reinterpret_cast (mxGetData(out[0])) = self; } -void MyFactorPosePoint2_deconstructor_95(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_deconstructor_101(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr> Shared; checkArguments("delete_MyFactorPosePoint2",nargout,nargin,1); @@ -1117,7 +1165,7 @@ void MyFactorPosePoint2_deconstructor_95(int nargout, mxArray *out[], int nargin } } -void load2D_96(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void load2D_102(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("load2D",nargout,nargin,5); string filename = unwrap< string >(in[0]); @@ -1129,7 +1177,7 @@ void load2D_96(int nargout, mxArray *out[], int nargin, const mxArray *in[]) out[0] = wrap_shared_ptr(pairResult.first,"gtsam.NonlinearFactorGraph", false); out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Values", false); } -void load2D_97(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void load2D_103(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("load2D",nargout,nargin,5); string filename = unwrap< string >(in[0]); @@ -1141,7 +1189,7 @@ void load2D_97(int nargout, mxArray *out[], int nargin, const mxArray *in[]) out[0] = wrap_shared_ptr(pairResult.first,"gtsam.NonlinearFactorGraph", false); out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Values", false); } -void load2D_98(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void load2D_104(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("load2D",nargout,nargin,2); string filename = unwrap< string >(in[0]); @@ -1150,24 +1198,44 @@ void load2D_98(int nargout, mxArray *out[], int nargin, const mxArray *in[]) out[0] = wrap_shared_ptr(pairResult.first,"gtsam.NonlinearFactorGraph", false); out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Values", false); } -void aGlobalFunction_99(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void aGlobalFunction_105(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("aGlobalFunction",nargout,nargin,0); out[0] = wrap< Vector >(aGlobalFunction()); } -void overloadedGlobalFunction_100(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void overloadedGlobalFunction_106(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("overloadedGlobalFunction",nargout,nargin,1); int a = unwrap< int >(in[0]); out[0] = wrap< Vector >(overloadedGlobalFunction(a)); } -void overloadedGlobalFunction_101(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void overloadedGlobalFunction_107(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("overloadedGlobalFunction",nargout,nargin,2); int a = unwrap< int >(in[0]); double b = unwrap< double >(in[1]); out[0] = wrap< Vector >(overloadedGlobalFunction(a,b)); } +void MultiTemplatedFunctionStringSize_tDouble_108(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("MultiTemplatedFunctionStringSize_tDouble",nargout,nargin,2); + T& x = *unwrap_shared_ptr< T >(in[0], "ptr_T"); + size_t y = unwrap< size_t >(in[1]); + out[0] = wrap< double >(MultiTemplatedFunctionStringSize_tDouble(x,y)); +} +void MultiTemplatedFunctionDoubleSize_tDouble_109(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("MultiTemplatedFunctionDoubleSize_tDouble",nargout,nargin,2); + T& x = *unwrap_shared_ptr< T >(in[0], "ptr_T"); + size_t y = unwrap< size_t >(in[1]); + out[0] = wrap< double >(MultiTemplatedFunctionDoubleSize_tDouble(x,y)); +} +void TemplatedFunctionRot3_110(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("TemplatedFunctionRot3",nargout,nargin,1); + gtsam::Rot3& t = *unwrap_shared_ptr< gtsam::Rot3 >(in[0], "ptr_gtsamRot3"); + TemplatedFunctionRot3(t); +} void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { @@ -1196,295 +1264,322 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) gtsamPoint2_argChar_4(nargout, out, nargin-1, in+1); break; case 5: - gtsamPoint2_argUChar_5(nargout, out, nargin-1, in+1); + gtsamPoint2_argChar_5(nargout, out, nargin-1, in+1); break; case 6: - gtsamPoint2_dim_6(nargout, out, nargin-1, in+1); + gtsamPoint2_argChar_6(nargout, out, nargin-1, in+1); break; case 7: - gtsamPoint2_eigenArguments_7(nargout, out, nargin-1, in+1); + gtsamPoint2_argChar_7(nargout, out, nargin-1, in+1); break; case 8: - gtsamPoint2_returnChar_8(nargout, out, nargin-1, in+1); + gtsamPoint2_argChar_8(nargout, out, nargin-1, in+1); break; case 9: - gtsamPoint2_vectorConfusion_9(nargout, out, nargin-1, in+1); + gtsamPoint2_argChar_9(nargout, out, nargin-1, in+1); break; case 10: - gtsamPoint2_x_10(nargout, out, nargin-1, in+1); + gtsamPoint2_argChar_10(nargout, out, nargin-1, in+1); break; case 11: - gtsamPoint2_y_11(nargout, out, nargin-1, in+1); + gtsamPoint2_argUChar_11(nargout, out, nargin-1, in+1); break; case 12: - gtsamPoint3_collectorInsertAndMakeBase_12(nargout, out, nargin-1, in+1); + gtsamPoint2_dim_12(nargout, out, nargin-1, in+1); break; case 13: - gtsamPoint3_constructor_13(nargout, out, nargin-1, in+1); + gtsamPoint2_eigenArguments_13(nargout, out, nargin-1, in+1); break; case 14: - gtsamPoint3_deconstructor_14(nargout, out, nargin-1, in+1); + gtsamPoint2_returnChar_14(nargout, out, nargin-1, in+1); break; case 15: - gtsamPoint3_norm_15(nargout, out, nargin-1, in+1); + gtsamPoint2_vectorConfusion_15(nargout, out, nargin-1, in+1); break; case 16: - gtsamPoint3_string_serialize_16(nargout, out, nargin-1, in+1); + gtsamPoint2_x_16(nargout, out, nargin-1, in+1); break; case 17: - gtsamPoint3_StaticFunctionRet_17(nargout, out, nargin-1, in+1); + gtsamPoint2_y_17(nargout, out, nargin-1, in+1); break; case 18: - gtsamPoint3_staticFunction_18(nargout, out, nargin-1, in+1); + gtsamPoint3_collectorInsertAndMakeBase_18(nargout, out, nargin-1, in+1); break; case 19: - gtsamPoint3_string_deserialize_19(nargout, out, nargin-1, in+1); + gtsamPoint3_constructor_19(nargout, out, nargin-1, in+1); break; case 20: - Test_collectorInsertAndMakeBase_20(nargout, out, nargin-1, in+1); + gtsamPoint3_deconstructor_20(nargout, out, nargin-1, in+1); break; case 21: - Test_constructor_21(nargout, out, nargin-1, in+1); + gtsamPoint3_norm_21(nargout, out, nargin-1, in+1); break; case 22: - Test_constructor_22(nargout, out, nargin-1, in+1); + gtsamPoint3_string_serialize_22(nargout, out, nargin-1, in+1); break; case 23: - Test_deconstructor_23(nargout, out, nargin-1, in+1); + gtsamPoint3_StaticFunctionRet_23(nargout, out, nargin-1, in+1); break; case 24: - Test_arg_EigenConstRef_24(nargout, out, nargin-1, in+1); + gtsamPoint3_staticFunction_24(nargout, out, nargin-1, in+1); break; case 25: - Test_create_MixedPtrs_25(nargout, out, nargin-1, in+1); + gtsamPoint3_string_deserialize_25(nargout, out, nargin-1, in+1); break; case 26: - Test_create_ptrs_26(nargout, out, nargin-1, in+1); + Test_collectorInsertAndMakeBase_26(nargout, out, nargin-1, in+1); break; case 27: - Test_print_27(nargout, out, nargin-1, in+1); + Test_constructor_27(nargout, out, nargin-1, in+1); break; case 28: - Test_return_Point2Ptr_28(nargout, out, nargin-1, in+1); + Test_constructor_28(nargout, out, nargin-1, in+1); break; case 29: - Test_return_Test_29(nargout, out, nargin-1, in+1); + Test_deconstructor_29(nargout, out, nargin-1, in+1); break; case 30: - Test_return_TestPtr_30(nargout, out, nargin-1, in+1); + Test_arg_EigenConstRef_30(nargout, out, nargin-1, in+1); break; case 31: - Test_return_bool_31(nargout, out, nargin-1, in+1); + Test_create_MixedPtrs_31(nargout, out, nargin-1, in+1); break; case 32: - Test_return_double_32(nargout, out, nargin-1, in+1); + Test_create_ptrs_32(nargout, out, nargin-1, in+1); break; case 33: - Test_return_field_33(nargout, out, nargin-1, in+1); + Test_print_33(nargout, out, nargin-1, in+1); break; case 34: - Test_return_int_34(nargout, out, nargin-1, in+1); + Test_return_Point2Ptr_34(nargout, out, nargin-1, in+1); break; case 35: - Test_return_matrix1_35(nargout, out, nargin-1, in+1); + Test_return_Test_35(nargout, out, nargin-1, in+1); break; case 36: - Test_return_matrix2_36(nargout, out, nargin-1, in+1); + Test_return_TestPtr_36(nargout, out, nargin-1, in+1); break; case 37: - Test_return_pair_37(nargout, out, nargin-1, in+1); + Test_return_bool_37(nargout, out, nargin-1, in+1); break; case 38: - Test_return_pair_38(nargout, out, nargin-1, in+1); + Test_return_double_38(nargout, out, nargin-1, in+1); break; case 39: - Test_return_ptrs_39(nargout, out, nargin-1, in+1); + Test_return_field_39(nargout, out, nargin-1, in+1); break; case 40: - Test_return_size_t_40(nargout, out, nargin-1, in+1); + Test_return_int_40(nargout, out, nargin-1, in+1); break; case 41: - Test_return_string_41(nargout, out, nargin-1, in+1); + Test_return_matrix1_41(nargout, out, nargin-1, in+1); break; case 42: - Test_return_vector1_42(nargout, out, nargin-1, in+1); + Test_return_matrix2_42(nargout, out, nargin-1, in+1); break; case 43: - Test_return_vector2_43(nargout, out, nargin-1, in+1); + Test_return_pair_43(nargout, out, nargin-1, in+1); break; case 44: - MyBase_collectorInsertAndMakeBase_44(nargout, out, nargin-1, in+1); + Test_return_pair_44(nargout, out, nargin-1, in+1); break; case 45: - MyBase_upcastFromVoid_45(nargout, out, nargin-1, in+1); + Test_return_ptrs_45(nargout, out, nargin-1, in+1); break; case 46: - MyBase_deconstructor_46(nargout, out, nargin-1, in+1); + Test_return_size_t_46(nargout, out, nargin-1, in+1); break; case 47: - MyTemplatePoint2_collectorInsertAndMakeBase_47(nargout, out, nargin-1, in+1); + Test_return_string_47(nargout, out, nargin-1, in+1); break; case 48: - MyTemplatePoint2_upcastFromVoid_48(nargout, out, nargin-1, in+1); + Test_return_vector1_48(nargout, out, nargin-1, in+1); break; case 49: - MyTemplatePoint2_constructor_49(nargout, out, nargin-1, in+1); + Test_return_vector2_49(nargout, out, nargin-1, in+1); break; case 50: - MyTemplatePoint2_deconstructor_50(nargout, out, nargin-1, in+1); + MyBase_collectorInsertAndMakeBase_50(nargout, out, nargin-1, in+1); break; case 51: - MyTemplatePoint2_accept_T_51(nargout, out, nargin-1, in+1); + MyBase_upcastFromVoid_51(nargout, out, nargin-1, in+1); break; case 52: - MyTemplatePoint2_accept_Tptr_52(nargout, out, nargin-1, in+1); + MyBase_deconstructor_52(nargout, out, nargin-1, in+1); break; case 53: - MyTemplatePoint2_create_MixedPtrs_53(nargout, out, nargin-1, in+1); + MyTemplatePoint2_collectorInsertAndMakeBase_53(nargout, out, nargin-1, in+1); break; case 54: - MyTemplatePoint2_create_ptrs_54(nargout, out, nargin-1, in+1); + MyTemplatePoint2_upcastFromVoid_54(nargout, out, nargin-1, in+1); break; case 55: - MyTemplatePoint2_return_T_55(nargout, out, nargin-1, in+1); + MyTemplatePoint2_constructor_55(nargout, out, nargin-1, in+1); break; case 56: - MyTemplatePoint2_return_Tptr_56(nargout, out, nargin-1, in+1); + MyTemplatePoint2_deconstructor_56(nargout, out, nargin-1, in+1); break; case 57: - MyTemplatePoint2_return_ptrs_57(nargout, out, nargin-1, in+1); + MyTemplatePoint2_accept_T_57(nargout, out, nargin-1, in+1); break; case 58: - MyTemplatePoint2_templatedMethod_58(nargout, out, nargin-1, in+1); + MyTemplatePoint2_accept_Tptr_58(nargout, out, nargin-1, in+1); break; case 59: - MyTemplatePoint2_templatedMethod_59(nargout, out, nargin-1, in+1); + MyTemplatePoint2_create_MixedPtrs_59(nargout, out, nargin-1, in+1); break; case 60: - MyTemplatePoint2_templatedMethod_60(nargout, out, nargin-1, in+1); + MyTemplatePoint2_create_ptrs_60(nargout, out, nargin-1, in+1); break; case 61: - MyTemplatePoint2_templatedMethod_61(nargout, out, nargin-1, in+1); + MyTemplatePoint2_return_T_61(nargout, out, nargin-1, in+1); break; case 62: - MyTemplatePoint2_Level_62(nargout, out, nargin-1, in+1); + MyTemplatePoint2_return_Tptr_62(nargout, out, nargin-1, in+1); break; case 63: - MyTemplateMatrix_collectorInsertAndMakeBase_63(nargout, out, nargin-1, in+1); + MyTemplatePoint2_return_ptrs_63(nargout, out, nargin-1, in+1); break; case 64: - MyTemplateMatrix_upcastFromVoid_64(nargout, out, nargin-1, in+1); + MyTemplatePoint2_templatedMethod_64(nargout, out, nargin-1, in+1); break; case 65: - MyTemplateMatrix_constructor_65(nargout, out, nargin-1, in+1); + MyTemplatePoint2_templatedMethod_65(nargout, out, nargin-1, in+1); break; case 66: - MyTemplateMatrix_deconstructor_66(nargout, out, nargin-1, in+1); + MyTemplatePoint2_templatedMethod_66(nargout, out, nargin-1, in+1); break; case 67: - MyTemplateMatrix_accept_T_67(nargout, out, nargin-1, in+1); + MyTemplatePoint2_templatedMethod_67(nargout, out, nargin-1, in+1); break; case 68: - MyTemplateMatrix_accept_Tptr_68(nargout, out, nargin-1, in+1); + MyTemplatePoint2_Level_68(nargout, out, nargin-1, in+1); break; case 69: - MyTemplateMatrix_create_MixedPtrs_69(nargout, out, nargin-1, in+1); + MyTemplateMatrix_collectorInsertAndMakeBase_69(nargout, out, nargin-1, in+1); break; case 70: - MyTemplateMatrix_create_ptrs_70(nargout, out, nargin-1, in+1); + MyTemplateMatrix_upcastFromVoid_70(nargout, out, nargin-1, in+1); break; case 71: - MyTemplateMatrix_return_T_71(nargout, out, nargin-1, in+1); + MyTemplateMatrix_constructor_71(nargout, out, nargin-1, in+1); break; case 72: - MyTemplateMatrix_return_Tptr_72(nargout, out, nargin-1, in+1); + MyTemplateMatrix_deconstructor_72(nargout, out, nargin-1, in+1); break; case 73: - MyTemplateMatrix_return_ptrs_73(nargout, out, nargin-1, in+1); + MyTemplateMatrix_accept_T_73(nargout, out, nargin-1, in+1); break; case 74: - MyTemplateMatrix_templatedMethod_74(nargout, out, nargin-1, in+1); + MyTemplateMatrix_accept_Tptr_74(nargout, out, nargin-1, in+1); break; case 75: - MyTemplateMatrix_templatedMethod_75(nargout, out, nargin-1, in+1); + MyTemplateMatrix_create_MixedPtrs_75(nargout, out, nargin-1, in+1); break; case 76: - MyTemplateMatrix_templatedMethod_76(nargout, out, nargin-1, in+1); + MyTemplateMatrix_create_ptrs_76(nargout, out, nargin-1, in+1); break; case 77: - MyTemplateMatrix_templatedMethod_77(nargout, out, nargin-1, in+1); + MyTemplateMatrix_return_T_77(nargout, out, nargin-1, in+1); break; case 78: - MyTemplateMatrix_Level_78(nargout, out, nargin-1, in+1); + MyTemplateMatrix_return_Tptr_78(nargout, out, nargin-1, in+1); break; case 79: - PrimitiveRefDouble_collectorInsertAndMakeBase_79(nargout, out, nargin-1, in+1); + MyTemplateMatrix_return_ptrs_79(nargout, out, nargin-1, in+1); break; case 80: - PrimitiveRefDouble_constructor_80(nargout, out, nargin-1, in+1); + MyTemplateMatrix_templatedMethod_80(nargout, out, nargin-1, in+1); break; case 81: - PrimitiveRefDouble_deconstructor_81(nargout, out, nargin-1, in+1); + MyTemplateMatrix_templatedMethod_81(nargout, out, nargin-1, in+1); break; case 82: - PrimitiveRefDouble_Brutal_82(nargout, out, nargin-1, in+1); + MyTemplateMatrix_templatedMethod_82(nargout, out, nargin-1, in+1); break; case 83: - MyVector3_collectorInsertAndMakeBase_83(nargout, out, nargin-1, in+1); + MyTemplateMatrix_templatedMethod_83(nargout, out, nargin-1, in+1); break; case 84: - MyVector3_constructor_84(nargout, out, nargin-1, in+1); + MyTemplateMatrix_Level_84(nargout, out, nargin-1, in+1); break; case 85: - MyVector3_deconstructor_85(nargout, out, nargin-1, in+1); + PrimitiveRefDouble_collectorInsertAndMakeBase_85(nargout, out, nargin-1, in+1); break; case 86: - MyVector12_collectorInsertAndMakeBase_86(nargout, out, nargin-1, in+1); + PrimitiveRefDouble_constructor_86(nargout, out, nargin-1, in+1); break; case 87: - MyVector12_constructor_87(nargout, out, nargin-1, in+1); + PrimitiveRefDouble_deconstructor_87(nargout, out, nargin-1, in+1); break; case 88: - MyVector12_deconstructor_88(nargout, out, nargin-1, in+1); + PrimitiveRefDouble_Brutal_88(nargout, out, nargin-1, in+1); break; case 89: - MultipleTemplatesIntDouble_collectorInsertAndMakeBase_89(nargout, out, nargin-1, in+1); + MyVector3_collectorInsertAndMakeBase_89(nargout, out, nargin-1, in+1); break; case 90: - MultipleTemplatesIntDouble_deconstructor_90(nargout, out, nargin-1, in+1); + MyVector3_constructor_90(nargout, out, nargin-1, in+1); break; case 91: - MultipleTemplatesIntFloat_collectorInsertAndMakeBase_91(nargout, out, nargin-1, in+1); + MyVector3_deconstructor_91(nargout, out, nargin-1, in+1); break; case 92: - MultipleTemplatesIntFloat_deconstructor_92(nargout, out, nargin-1, in+1); + MyVector12_collectorInsertAndMakeBase_92(nargout, out, nargin-1, in+1); break; case 93: - MyFactorPosePoint2_collectorInsertAndMakeBase_93(nargout, out, nargin-1, in+1); + MyVector12_constructor_93(nargout, out, nargin-1, in+1); break; case 94: - MyFactorPosePoint2_constructor_94(nargout, out, nargin-1, in+1); + MyVector12_deconstructor_94(nargout, out, nargin-1, in+1); break; case 95: - MyFactorPosePoint2_deconstructor_95(nargout, out, nargin-1, in+1); + MultipleTemplatesIntDouble_collectorInsertAndMakeBase_95(nargout, out, nargin-1, in+1); break; case 96: - load2D_96(nargout, out, nargin-1, in+1); + MultipleTemplatesIntDouble_deconstructor_96(nargout, out, nargin-1, in+1); break; case 97: - load2D_97(nargout, out, nargin-1, in+1); + MultipleTemplatesIntFloat_collectorInsertAndMakeBase_97(nargout, out, nargin-1, in+1); break; case 98: - load2D_98(nargout, out, nargin-1, in+1); + MultipleTemplatesIntFloat_deconstructor_98(nargout, out, nargin-1, in+1); break; case 99: - aGlobalFunction_99(nargout, out, nargin-1, in+1); + MyFactorPosePoint2_collectorInsertAndMakeBase_99(nargout, out, nargin-1, in+1); break; case 100: - overloadedGlobalFunction_100(nargout, out, nargin-1, in+1); + MyFactorPosePoint2_constructor_100(nargout, out, nargin-1, in+1); break; case 101: - overloadedGlobalFunction_101(nargout, out, nargin-1, in+1); + MyFactorPosePoint2_deconstructor_101(nargout, out, nargin-1, in+1); + break; + case 102: + load2D_102(nargout, out, nargin-1, in+1); + break; + case 103: + load2D_103(nargout, out, nargin-1, in+1); + break; + case 104: + load2D_104(nargout, out, nargin-1, in+1); + break; + case 105: + aGlobalFunction_105(nargout, out, nargin-1, in+1); + break; + case 106: + overloadedGlobalFunction_106(nargout, out, nargin-1, in+1); + break; + case 107: + overloadedGlobalFunction_107(nargout, out, nargin-1, in+1); + break; + case 108: + MultiTemplatedFunctionStringSize_tDouble_108(nargout, out, nargin-1, in+1); + break; + case 109: + MultiTemplatedFunctionDoubleSize_tDouble_109(nargout, out, nargin-1, in+1); + break; + case 110: + TemplatedFunctionRot3_110(nargout, out, nargin-1, in+1); break; } } catch(const std::exception& e) { diff --git a/tests/expected-matlab/load2D.m b/tests/expected-matlab/load2D.m index bcea4ed76..323054d3e 100644 --- a/tests/expected-matlab/load2D.m +++ b/tests/expected-matlab/load2D.m @@ -1,10 +1,10 @@ function varargout = load2D(varargin) if length(varargin) == 5 && isa(varargin{1},'char') && isa(varargin{2},'Test') && isa(varargin{3},'numeric') && isa(varargin{4},'logical') && isa(varargin{5},'logical') - [ varargout{1} varargout{2} ] = geometry_wrapper(96, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(102, varargin{:}); elseif length(varargin) == 5 && isa(varargin{1},'char') && isa(varargin{2},'gtsam.noiseModel.Diagonal') && isa(varargin{3},'numeric') && isa(varargin{4},'logical') && isa(varargin{5},'logical') - [ varargout{1} varargout{2} ] = geometry_wrapper(97, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(103, varargin{:}); elseif length(varargin) == 2 && isa(varargin{1},'char') && isa(varargin{2},'gtsam.noiseModel.Diagonal') - [ varargout{1} varargout{2} ] = geometry_wrapper(98, varargin{:}); + [ varargout{1} varargout{2} ] = geometry_wrapper(104, varargin{:}); else error('Arguments do not match any overload of function load2D'); end diff --git a/tests/expected-matlab/overloadedGlobalFunction.m b/tests/expected-matlab/overloadedGlobalFunction.m index 2fbaa88dc..5992abed1 100644 --- a/tests/expected-matlab/overloadedGlobalFunction.m +++ b/tests/expected-matlab/overloadedGlobalFunction.m @@ -1,8 +1,8 @@ function varargout = overloadedGlobalFunction(varargin) if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = geometry_wrapper(100, varargin{:}); + varargout{1} = geometry_wrapper(106, varargin{:}); elseif length(varargin) == 2 && isa(varargin{1},'numeric') && isa(varargin{2},'double') - varargout{1} = geometry_wrapper(101, varargin{:}); + varargout{1} = geometry_wrapper(107, varargin{:}); else error('Arguments do not match any overload of function overloadedGlobalFunction'); end diff --git a/tests/expected-python/geometry_pybind.cpp b/tests/expected-python/geometry_pybind.cpp index 348888f25..7aa150d30 100644 --- a/tests/expected-python/geometry_pybind.cpp +++ b/tests/expected-python/geometry_pybind.cpp @@ -29,86 +29,60 @@ PYBIND11_MODULE(geometry_py, m_) { py::class_>(m_gtsam, "Point2") .def(py::init<>()) - .def(py::init< double, double>(), py::arg("x"), py::arg("y")) + .def(py::init(), py::arg("x"), py::arg("y")) .def("x",[](gtsam::Point2* self){return self->x();}) .def("y",[](gtsam::Point2* self){return self->y();}) .def("dim",[](gtsam::Point2* self){return self->dim();}) .def("returnChar",[](gtsam::Point2* self){return self->returnChar();}) .def("argChar",[](gtsam::Point2* self, char a){ self->argChar(a);}, py::arg("a")) + .def("argChar",[](gtsam::Point2* self, std::shared_ptr& a){ self->argChar(a);}, py::arg("a")) + .def("argChar",[](gtsam::Point2* self, char& a){ self->argChar(a);}, py::arg("a")) + .def("argChar",[](gtsam::Point2* self, char* a){ self->argChar(a);}, py::arg("a")) + .def("argChar",[](gtsam::Point2* self, const std::shared_ptr& a){ self->argChar(a);}, py::arg("a")) + .def("argChar",[](gtsam::Point2* self, const char& a){ self->argChar(a);}, py::arg("a")) + .def("argChar",[](gtsam::Point2* self, const char* a){ self->argChar(a);}, py::arg("a")) .def("argUChar",[](gtsam::Point2* self, unsigned char a){ self->argUChar(a);}, py::arg("a")) - .def("eigenArguments",[](gtsam::Point2* self,const gtsam::Vector& v,const gtsam::Matrix& m){ self->eigenArguments(v, m);}, py::arg("v"), py::arg("m")) + .def("eigenArguments",[](gtsam::Point2* self, const gtsam::Vector& v, const gtsam::Matrix& m){ self->eigenArguments(v, m);}, py::arg("v"), py::arg("m")) .def("vectorConfusion",[](gtsam::Point2* self){return self->vectorConfusion();}) -.def("serialize", - [](gtsam::Point2* self){ - return gtsam::serialize(*self); - } -) -.def("deserialize", - [](gtsam::Point2* self, string serialized){ - gtsam::deserialize(serialized, *self); - }, py::arg("serialized")) - -.def(py::pickle( - [](const gtsam::Point2 &a){ // __getstate__ - /* Returns a string that encodes the state of the object */ - return py::make_tuple(gtsam::serialize(a)); - }, - [](py::tuple t){ // __setstate__ - gtsam::Point2 obj; - gtsam::deserialize(t[0].cast(), obj); - return obj; - })) -; + .def("serialize", [](gtsam::Point2* self){ return gtsam::serialize(*self); }) + .def("deserialize", [](gtsam::Point2* self, string serialized){ gtsam::deserialize(serialized, *self); }, py::arg("serialized")) + .def(py::pickle( + [](const gtsam::Point2 &a){ /* __getstate__: Returns a string that encodes the state of the object */ return py::make_tuple(gtsam::serialize(a)); }, + [](py::tuple t){ /* __setstate__ */ gtsam::Point2 obj; gtsam::deserialize(t[0].cast(), obj); return obj; })); py::class_>(m_gtsam, "Point3") - .def(py::init< double, double, double>(), py::arg("x"), py::arg("y"), py::arg("z")) + .def(py::init(), py::arg("x"), py::arg("y"), py::arg("z")) .def("norm",[](gtsam::Point3* self){return self->norm();}) -.def("serialize", - [](gtsam::Point3* self){ - return gtsam::serialize(*self); - } -) -.def("deserialize", - [](gtsam::Point3* self, string serialized){ - gtsam::deserialize(serialized, *self); - }, py::arg("serialized")) - -.def(py::pickle( - [](const gtsam::Point3 &a){ // __getstate__ - /* Returns a string that encodes the state of the object */ - return py::make_tuple(gtsam::serialize(a)); - }, - [](py::tuple t){ // __setstate__ - gtsam::Point3 obj; - gtsam::deserialize(t[0].cast(), obj); - return obj; - })) - + .def("serialize", [](gtsam::Point3* self){ return gtsam::serialize(*self); }) + .def("deserialize", [](gtsam::Point3* self, string serialized){ gtsam::deserialize(serialized, *self); }, py::arg("serialized")) + .def(py::pickle( + [](const gtsam::Point3 &a){ /* __getstate__: Returns a string that encodes the state of the object */ return py::make_tuple(gtsam::serialize(a)); }, + [](py::tuple t){ /* __setstate__ */ gtsam::Point3 obj; gtsam::deserialize(t[0].cast(), obj); return obj; })) .def_static("staticFunction",[](){return gtsam::Point3::staticFunction();}) - .def_static("StaticFunctionRet",[]( double z){return gtsam::Point3::StaticFunctionRet(z);}, py::arg("z")); + .def_static("StaticFunctionRet",[](double z){return gtsam::Point3::StaticFunctionRet(z);}, py::arg("z")); py::class_>(m_, "Test") .def(py::init<>()) - .def(py::init< double, const gtsam::Matrix&>(), py::arg("a"), py::arg("b")) - .def("return_pair",[](Test* self,const gtsam::Vector& v,const gtsam::Matrix& A){return self->return_pair(v, A);}, py::arg("v"), py::arg("A")) - .def("return_pair",[](Test* self,const gtsam::Vector& v){return self->return_pair(v);}, py::arg("v")) + .def(py::init(), py::arg("a"), py::arg("b")) + .def("return_pair",[](Test* self, const gtsam::Vector& v, const gtsam::Matrix& A){return self->return_pair(v, A);}, py::arg("v"), py::arg("A")) + .def("return_pair",[](Test* self, const gtsam::Vector& v){return self->return_pair(v);}, py::arg("v")) .def("return_bool",[](Test* self, bool value){return self->return_bool(value);}, py::arg("value")) .def("return_size_t",[](Test* self, size_t value){return self->return_size_t(value);}, py::arg("value")) .def("return_int",[](Test* self, int value){return self->return_int(value);}, py::arg("value")) .def("return_double",[](Test* self, double value){return self->return_double(value);}, py::arg("value")) .def("return_string",[](Test* self, string value){return self->return_string(value);}, py::arg("value")) - .def("return_vector1",[](Test* self,const gtsam::Vector& value){return self->return_vector1(value);}, py::arg("value")) - .def("return_matrix1",[](Test* self,const gtsam::Matrix& value){return self->return_matrix1(value);}, py::arg("value")) - .def("return_vector2",[](Test* self,const gtsam::Vector& value){return self->return_vector2(value);}, py::arg("value")) - .def("return_matrix2",[](Test* self,const gtsam::Matrix& value){return self->return_matrix2(value);}, py::arg("value")) - .def("arg_EigenConstRef",[](Test* self,const gtsam::Matrix& value){ self->arg_EigenConstRef(value);}, py::arg("value")) - .def("return_field",[](Test* self,const Test& t){return self->return_field(t);}, py::arg("t")) - .def("return_TestPtr",[](Test* self,const std::shared_ptr& value){return self->return_TestPtr(value);}, py::arg("value")) - .def("return_Test",[](Test* self,const std::shared_ptr& value){return self->return_Test(value);}, py::arg("value")) + .def("return_vector1",[](Test* self, const gtsam::Vector& value){return self->return_vector1(value);}, py::arg("value")) + .def("return_matrix1",[](Test* self, const gtsam::Matrix& value){return self->return_matrix1(value);}, py::arg("value")) + .def("return_vector2",[](Test* self, const gtsam::Vector& value){return self->return_vector2(value);}, py::arg("value")) + .def("return_matrix2",[](Test* self, const gtsam::Matrix& value){return self->return_matrix2(value);}, py::arg("value")) + .def("arg_EigenConstRef",[](Test* self, const gtsam::Matrix& value){ self->arg_EigenConstRef(value);}, py::arg("value")) + .def("return_field",[](Test* self, const Test& t){return self->return_field(t);}, py::arg("t")) + .def("return_TestPtr",[](Test* self, const std::shared_ptr& value){return self->return_TestPtr(value);}, py::arg("value")) + .def("return_Test",[](Test* self, std::shared_ptr& value){return self->return_Test(value);}, py::arg("value")) .def("return_Point2Ptr",[](Test* self, bool value){return self->return_Point2Ptr(value);}, py::arg("value")) .def("create_ptrs",[](Test* self){return self->create_ptrs();}) .def("create_MixedPtrs",[](Test* self){return self->create_MixedPtrs();}) - .def("return_ptrs",[](Test* self,const std::shared_ptr& p1,const std::shared_ptr& p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2")) + .def("return_ptrs",[](Test* self, std::shared_ptr& p1, std::shared_ptr& p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2")) .def("print_",[](Test* self){ self->print();}) .def("__repr__", [](const Test &a) { @@ -122,32 +96,32 @@ PYBIND11_MODULE(geometry_py, m_) { py::class_, MyBase, std::shared_ptr>>(m_, "MyTemplatePoint2") .def(py::init<>()) - .def("templatedMethodPoint2",[](MyTemplate* self,const gtsam::Point2& t){return self->templatedMethod(t);}, py::arg("t")) - .def("templatedMethodPoint3",[](MyTemplate* self,const gtsam::Point3& t){return self->templatedMethod(t);}, py::arg("t")) - .def("templatedMethodVector",[](MyTemplate* self,const gtsam::Vector& t){return self->templatedMethod(t);}, py::arg("t")) - .def("templatedMethodMatrix",[](MyTemplate* self,const gtsam::Matrix& t){return self->templatedMethod(t);}, py::arg("t")) - .def("accept_T",[](MyTemplate* self,const gtsam::Point2& value){ self->accept_T(value);}, py::arg("value")) - .def("accept_Tptr",[](MyTemplate* self,const std::shared_ptr& value){ self->accept_Tptr(value);}, py::arg("value")) - .def("return_Tptr",[](MyTemplate* self,const std::shared_ptr& value){return self->return_Tptr(value);}, py::arg("value")) - .def("return_T",[](MyTemplate* self,const std::shared_ptr& value){return self->return_T(value);}, py::arg("value")) + .def("templatedMethodPoint2",[](MyTemplate* self, const gtsam::Point2& t){return self->templatedMethod(t);}, py::arg("t")) + .def("templatedMethodPoint3",[](MyTemplate* self, const gtsam::Point3& t){return self->templatedMethod(t);}, py::arg("t")) + .def("templatedMethodVector",[](MyTemplate* self, const gtsam::Vector& t){return self->templatedMethod(t);}, py::arg("t")) + .def("templatedMethodMatrix",[](MyTemplate* self, const gtsam::Matrix& t){return self->templatedMethod(t);}, py::arg("t")) + .def("accept_T",[](MyTemplate* self, const gtsam::Point2& value){ self->accept_T(value);}, py::arg("value")) + .def("accept_Tptr",[](MyTemplate* self, std::shared_ptr& value){ self->accept_Tptr(value);}, py::arg("value")) + .def("return_Tptr",[](MyTemplate* self, std::shared_ptr& value){return self->return_Tptr(value);}, py::arg("value")) + .def("return_T",[](MyTemplate* self, gtsam::Point2* value){return self->return_T(value);}, py::arg("value")) .def("create_ptrs",[](MyTemplate* self){return self->create_ptrs();}) .def("create_MixedPtrs",[](MyTemplate* self){return self->create_MixedPtrs();}) - .def("return_ptrs",[](MyTemplate* self,const std::shared_ptr& p1,const std::shared_ptr& p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2")) + .def("return_ptrs",[](MyTemplate* self, std::shared_ptr& p1, std::shared_ptr& p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2")) .def_static("Level",[](const gtsam::Point2& K){return MyTemplate::Level(K);}, py::arg("K")); py::class_, MyBase, std::shared_ptr>>(m_, "MyTemplateMatrix") .def(py::init<>()) - .def("templatedMethodPoint2",[](MyTemplate* self,const gtsam::Point2& t){return self->templatedMethod(t);}, py::arg("t")) - .def("templatedMethodPoint3",[](MyTemplate* self,const gtsam::Point3& t){return self->templatedMethod(t);}, py::arg("t")) - .def("templatedMethodVector",[](MyTemplate* self,const gtsam::Vector& t){return self->templatedMethod(t);}, py::arg("t")) - .def("templatedMethodMatrix",[](MyTemplate* self,const gtsam::Matrix& t){return self->templatedMethod(t);}, py::arg("t")) - .def("accept_T",[](MyTemplate* self,const gtsam::Matrix& value){ self->accept_T(value);}, py::arg("value")) - .def("accept_Tptr",[](MyTemplate* self,const std::shared_ptr& value){ self->accept_Tptr(value);}, py::arg("value")) - .def("return_Tptr",[](MyTemplate* self,const std::shared_ptr& value){return self->return_Tptr(value);}, py::arg("value")) - .def("return_T",[](MyTemplate* self,const std::shared_ptr& value){return self->return_T(value);}, py::arg("value")) + .def("templatedMethodPoint2",[](MyTemplate* self, const gtsam::Point2& t){return self->templatedMethod(t);}, py::arg("t")) + .def("templatedMethodPoint3",[](MyTemplate* self, const gtsam::Point3& t){return self->templatedMethod(t);}, py::arg("t")) + .def("templatedMethodVector",[](MyTemplate* self, const gtsam::Vector& t){return self->templatedMethod(t);}, py::arg("t")) + .def("templatedMethodMatrix",[](MyTemplate* self, const gtsam::Matrix& t){return self->templatedMethod(t);}, py::arg("t")) + .def("accept_T",[](MyTemplate* self, const gtsam::Matrix& value){ self->accept_T(value);}, py::arg("value")) + .def("accept_Tptr",[](MyTemplate* self, const std::shared_ptr& value){ self->accept_Tptr(value);}, py::arg("value")) + .def("return_Tptr",[](MyTemplate* self, const std::shared_ptr& value){return self->return_Tptr(value);}, py::arg("value")) + .def("return_T",[](MyTemplate* self, const gtsam::Matrix* value){return self->return_T(value);}, py::arg("value")) .def("create_ptrs",[](MyTemplate* self){return self->create_ptrs();}) .def("create_MixedPtrs",[](MyTemplate* self){return self->create_MixedPtrs();}) - .def("return_ptrs",[](MyTemplate* self,const std::shared_ptr& p1,const std::shared_ptr& p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2")) + .def("return_ptrs",[](MyTemplate* self, const std::shared_ptr& p1, const std::shared_ptr& p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2")) .def_static("Level",[](const gtsam::Matrix& K){return MyTemplate::Level(K);}, py::arg("K")); py::class_, std::shared_ptr>>(m_, "PrimitiveRefDouble") @@ -165,14 +139,17 @@ PYBIND11_MODULE(geometry_py, m_) { py::class_, std::shared_ptr>>(m_, "MultipleTemplatesIntFloat"); py::class_, std::shared_ptr>>(m_, "MyFactorPosePoint2") - .def(py::init< size_t, size_t, double, const std::shared_ptr&>(), py::arg("key1"), py::arg("key2"), py::arg("measured"), py::arg("noiseModel")); + .def(py::init&>(), py::arg("key1"), py::arg("key2"), py::arg("measured"), py::arg("noiseModel")); - m_.def("load2D",[]( string filename,const std::shared_ptr& model, int maxID, bool addNoise, bool smart){return ::load2D(filename, model, maxID, addNoise, smart);}, py::arg("filename"), py::arg("model"), py::arg("maxID"), py::arg("addNoise"), py::arg("smart")); - m_.def("load2D",[]( string filename,const std::shared_ptr& model, int maxID, bool addNoise, bool smart){return ::load2D(filename, model, maxID, addNoise, smart);}, py::arg("filename"), py::arg("model"), py::arg("maxID"), py::arg("addNoise"), py::arg("smart")); - m_.def("load2D",[]( string filename,const std::shared_ptr& model){return ::load2D(filename, model);}, py::arg("filename"), py::arg("model")); + m_.def("load2D",[](string filename, std::shared_ptr& model, int maxID, bool addNoise, bool smart){return ::load2D(filename, model, maxID, addNoise, smart);}, py::arg("filename"), py::arg("model"), py::arg("maxID"), py::arg("addNoise"), py::arg("smart")); + m_.def("load2D",[](string filename, const std::shared_ptr& model, int maxID, bool addNoise, bool smart){return ::load2D(filename, model, maxID, addNoise, smart);}, py::arg("filename"), py::arg("model"), py::arg("maxID"), py::arg("addNoise"), py::arg("smart")); + m_.def("load2D",[](string filename, gtsam::noiseModel::Diagonal* model){return ::load2D(filename, model);}, py::arg("filename"), py::arg("model")); m_.def("aGlobalFunction",[](){return ::aGlobalFunction();}); - m_.def("overloadedGlobalFunction",[]( int a){return ::overloadedGlobalFunction(a);}, py::arg("a")); - m_.def("overloadedGlobalFunction",[]( int a, double b){return ::overloadedGlobalFunction(a, b);}, py::arg("a"), py::arg("b")); + m_.def("overloadedGlobalFunction",[](int a){return ::overloadedGlobalFunction(a);}, py::arg("a")); + m_.def("overloadedGlobalFunction",[](int a, double b){return ::overloadedGlobalFunction(a, b);}, py::arg("a"), py::arg("b")); + m_.def("MultiTemplatedFunctionStringSize_tDouble",[](const T& x, size_t y){return ::MultiTemplatedFunction(x, y);}, py::arg("x"), py::arg("y")); + m_.def("MultiTemplatedFunctionDoubleSize_tDouble",[](const T& x, size_t y){return ::MultiTemplatedFunction(x, y);}, py::arg("x"), py::arg("y")); + m_.def("TemplatedFunctionRot3",[](const gtsam::Rot3& t){ ::TemplatedFunction(t);}, py::arg("t")); #include "python/specializations.h" diff --git a/tests/expected-python/testNamespaces_py.cpp b/tests/expected-python/testNamespaces_py.cpp new file mode 100644 index 000000000..b115eea66 --- /dev/null +++ b/tests/expected-python/testNamespaces_py.cpp @@ -0,0 +1,62 @@ + + +#include +#include +#include +#include "gtsam/nonlinear/utilities.h" // for RedirectCout. + +#include "path/to/ns1.h" +#include "path/to/ns1/ClassB.h" +#include "path/to/ns2.h" +#include "path/to/ns2/ClassA.h" +#include "path/to/ns3.h" + +#include "wrap/serialization.h" +#include + + + + + +using namespace std; + +namespace py = pybind11; + +PYBIND11_MODULE(testNamespaces_py, m_) { + m_.doc() = "pybind11 wrapper of testNamespaces_py"; + + pybind11::module m_ns1 = m_.def_submodule("ns1", "ns1 submodule"); + + py::class_>(m_ns1, "ClassA") + .def(py::init<>()); + + py::class_>(m_ns1, "ClassB") + .def(py::init<>()); + + m_ns1.def("aGlobalFunction",[](){return ns1::aGlobalFunction();}); pybind11::module m_ns2 = m_.def_submodule("ns2", "ns2 submodule"); + + py::class_>(m_ns2, "ClassA") + .def(py::init<>()) + .def("memberFunction",[](ns2::ClassA* self){return self->memberFunction();}) + .def("nsArg",[](ns2::ClassA* self, const ns1::ClassB& arg){return self->nsArg(arg);}, py::arg("arg")) + .def("nsReturn",[](ns2::ClassA* self, double q){return self->nsReturn(q);}, py::arg("q")) + .def_static("afunction",[](){return ns2::ClassA::afunction();}); + pybind11::module m_ns2_ns3 = m_ns2.def_submodule("ns3", "ns3 submodule"); + + py::class_>(m_ns2_ns3, "ClassB") + .def(py::init<>()); + + py::class_>(m_ns2, "ClassC") + .def(py::init<>()); + + m_ns2.def("aGlobalFunction",[](){return ns2::aGlobalFunction();}); + m_ns2.def("overloadedGlobalFunction",[](const ns1::ClassA& a){return ns2::overloadedGlobalFunction(a);}, py::arg("a")); + m_ns2.def("overloadedGlobalFunction",[](const ns1::ClassA& a, double b){return ns2::overloadedGlobalFunction(a, b);}, py::arg("a"), py::arg("b")); + py::class_>(m_, "ClassD") + .def(py::init<>()); + + +#include "python/specializations.h" + +} + diff --git a/tests/geometry.h b/tests/geometry.h index 716b4307d..23ec5ff23 100644 --- a/tests/geometry.h +++ b/tests/geometry.h @@ -17,6 +17,12 @@ class Point2 { int dim() const; char returnChar() const; void argChar(char a) const; + void argChar(char* a) const; + void argChar(char& a) const; + void argChar(char@ a) const; + void argChar(const char* a) const; + void argChar(const char& a) const; + void argChar(const char@ a) const; void argUChar(unsigned char a) const; void eigenArguments(Vector v, Matrix m) const; VectorNotEigen vectorConfusion(); @@ -87,7 +93,7 @@ class Test { bool return_field(const Test& t) const; - Test* return_TestPtr(Test* value) const; + Test* return_TestPtr(const Test* value) const; Test return_Test(Test* value) const; gtsam::Point2* return_Point2Ptr(bool value) const; @@ -104,8 +110,8 @@ class Test { }; pair load2D(string filename, Test* model, int maxID, bool addNoise, bool smart); -pair load2D(string filename, gtsam::noiseModel::Diagonal* model, int maxID, bool addNoise, bool smart); -pair load2D(string filename, gtsam::noiseModel::Diagonal* model); +pair load2D(string filename, const gtsam::noiseModel::Diagonal* model, int maxID, bool addNoise, bool smart); +pair load2D(string filename, gtsam::noiseModel::Diagonal@ model); Vector aGlobalFunction(); @@ -130,7 +136,7 @@ virtual class MyTemplate : MyBase { void accept_T(const T& value) const; void accept_Tptr(T* value) const; T* return_Tptr(T* value) const; - T return_T(T* value) const; + T return_T(T@ value) const; pair create_ptrs () const; pair create_MixedPtrs () const; pair return_ptrs (T* p1, T* p2) const; @@ -167,3 +173,13 @@ class MyVector { // Class with multiple instantiated templates template class MultipleTemplates {}; + +// A templated free/global function. Multiple templates supported. +template +R MultiTemplatedFunction(const T& x, T2 y); + +// Check if we can typedef the templated function +template +void TemplatedFunction(const T& t); + +typedef TemplatedFunction TemplatedFunctionRot3; diff --git a/tests/interface_parser_test.py b/tests/interface_parser_test.py deleted file mode 100644 index 3197b4214..000000000 --- a/tests/interface_parser_test.py +++ /dev/null @@ -1,258 +0,0 @@ -# TODO(duy): make them proper tests!!! -import unittest - -import sys, os -sys.path.append(os.path.dirname(os.path.dirname(os.path.abspath(__file__)))) - -from gtwrap.interface_parser import * - - -class TestPyparsing(unittest.TestCase): - def test_argument_list(self): - arg_string = "int a, C1 c1, C2& c2, C3* c3, "\ - "const C4 c4, const C5& c5,"\ - "const C6* c6" - args = ArgumentList.rule.parseString(arg_string) - print(ArgumentList(args)) - - -empty_args = ArgumentList.rule.parseString("")[0] -print(empty_args) - -arg_string = "int a, C1 c1, C2& c2, C3* c3, "\ - "const C4 c4, const C5& c5,"\ - "const C6* c6" -args = ArgumentList.rule.parseString(arg_string)[0] -print(args) - -# Test ReturnType -ReturnType.rule.parseString("pair")[0] -ReturnType.rule.parseString("cdwdc")[0] - -# expect throw -# ReturnType.parseString("int&") -# ReturnType.parseString("const int") - -ret = Class.rule.parseString(""" -virtual class SymbolicFactorGraph { - SymbolicFactorGraph(); - SymbolicFactorGraph(const gtsam::SymbolicBayesNet& bayesNet); - SymbolicFactorGraph(const gtsam::SymbolicBayesTree& bayesTree); - - // From FactorGraph. - void push_back(gtsam::SymbolicFactor* factor); - void print(string s) const; - bool equals(const gtsam::SymbolicFactorGraph& rhs, double tol) const; - size_t size() const; - bool exists(size_t idx) const; - - // Standard interface - gtsam::KeySet keys() const; - void push_back(const gtsam::SymbolicFactorGraph& graph); - void push_back(const gtsam::SymbolicBayesNet& bayesNet); - void push_back(const gtsam::SymbolicBayesTree& bayesTree); - - /* Advanced interface */ - void push_factor(size_t key); - void push_factor(size_t key1, size_t key2); - void push_factor(size_t key1, size_t key2, size_t key3); - void push_factor(size_t key1, size_t key2, size_t key3, size_t key4); - - gtsam::SymbolicBayesNet* eliminateSequential(); - gtsam::SymbolicBayesNet* eliminateSequential( - const gtsam::Ordering& ordering); - gtsam::SymbolicBayesTree* eliminateMultifrontal(); - gtsam::SymbolicBayesTree* eliminateMultifrontal( - const gtsam::Ordering& ordering); - pair - eliminatePartialSequential(const gtsam::Ordering& ordering); - pair - eliminatePartialSequential(const gtsam::KeyVector& keys); - pair - eliminatePartialMultifrontal(const gtsam::Ordering& ordering); - gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet( - const gtsam::Ordering& ordering); - gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet( - const gtsam::KeyVector& key_vector, - const gtsam::Ordering& marginalizedVariableOrdering); - gtsam::SymbolicFactorGraph* marginal(const gtsam::KeyVector& key_vector); -}; -""")[0] - -ret = Class.rule.parseString(""" -virtual class Base { -}; -""")[0] - -ret = Class.rule.parseString(""" -virtual class Null: gtsam::noiseModel::mEstimator::Base { - Null(); - void print(string s) const; - static gtsam::noiseModel::mEstimator::Null* Create(); - - // enabling serialization functionality - void serializable() const; -}; -""")[0] - -retFactorIndices = Class.rule.parseString(""" -class FactorIndices {}; -""")[0] - -retIsam2 = Class.rule.parseString(""" -class ISAM2 { - ISAM2(); - ISAM2(const gtsam::ISAM2Params& params); - ISAM2(const gtsam::ISAM2& other); - - bool equals(const gtsam::ISAM2& other, double tol) const; - void print(string s) const; - void printStats() const; - void saveGraph(string s) const; - - gtsam::ISAM2Result update(); - gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, - const gtsam::Values& newTheta); - gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, - const gtsam::Values& newTheta, const gtsam::FactorIndices& - removeFactorIndices); - gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, - const gtsam::Values& newTheta, - const gtsam::FactorIndices& removeFactorIndices, - const gtsam::KeyGroupMap& constrainedKeys); - - gtsam::Values getLinearizationPoint() const; - gtsam::Values calculateEstimate() const; - template - VALUE calculateEstimate(size_t key) const; - gtsam::Values calculateBestEstimate() const; - Matrix marginalCovariance(size_t key) const; - gtsam::VectorValues getDelta() const; - gtsam::NonlinearFactorGraph getFactorsUnsafe() const; - gtsam::VariableIndex getVariableIndex() const; - gtsam::ISAM2Params params() const; -}; -""")[0] -# if __name__ == '__main__': -# unittest.main() - -typename = Typename.rule.parseString("rew")[0] -ret = ReturnType.rule.parseString("pair")[0] -ret1 = Method.rule.parseString( - "int f(const int x, const Class& c, Class* t) const;")[0] -ret = Method.rule.parseString("int f() const;")[0] - -ret1 = StaticMethod.rule.parseString( - "static int f(const int x, const Class& c, Class* t);")[0] -ret = StaticMethod.rule.parseString("static int f();")[0] -ret1 = Constructor.rule.parseString( - "f(const int x, const Class& c, Class* t);")[0] -ret = Constructor.rule.parseString("f();")[0] - -typedef = TypedefTemplateInstantiation.rule.parseString(""" -typedef gtsam::BearingFactor - BearingFactor2D; -""")[0] - -include = Include.rule.parseString("#include ")[0] -print(include) - -fwd = ForwardDeclaration.rule.parseString( - "virtual class Test:gtsam::Point3;")[0] - -func = GlobalFunction.rule.parseString(""" -gtsam::Values localToWorld(const gtsam::Values& local, - const gtsam::Pose2& base, const gtsam::KeyVector& keys); -""")[0] -print(func) - -try: - namespace = Namespace.rule.parseString(""" -namespace gtsam { -#include -class Point2 { -Point2(); -Point2(double x, double y); -double x() const; -double y() const; -int dim() const; -char returnChar() const; -void argChar(char a) const; -void argUChar(unsigned char a) const; -void eigenArguments(Vector v, Matrix m) const; -VectorNotEigen vectorConfusion(); -}; - -#include -class Point3 { -Point3(double x, double y, double z); -double norm() const; - -// static functions - use static keyword and uppercase -static double staticFunction(); -static gtsam::Point3 StaticFunctionRet(double z); - -// enabling serialization functionality -void serialize() const; // Just triggers a flag internally -}; - -} - """) -except ParseException as pe: - print(pe.markInputline()) - -# filename = "tools/workspace/pybind_wrapper/gtsam.h" -# with open(filename, "r") as f: -# content = f.read() -# module = Module.parseString(content) - -module = Module.parseString(""" -namespace one { - namespace two { - namespace three { - class Class123 { - }; - } - class Class12a { - }; - } - namespace two_dummy { - namespace three_dummy{ - - } - namespace fourth_dummy{ - - } - } - namespace two { - class Class12b { - - }; - } -} - -class Global{ -}; -""") - -print("module: ", module) - -sub_namespace = find_sub_namespace(module, ['one', 'two', 'three']) -print("Found namespace:", sub_namespace[0].name) -print(find_sub_namespace(module, ['one', 'two_test', 'three'])) -print(find_sub_namespace(module, ['one', 'two'])) - -found_class = module.find_class( - Typename(namespaces_name=['one', 'two', 'three', 'Class123'])) -print(found_class) - -found_class = module.find_class( - Typename(namespaces_name=['one', 'two', 'Class12b'])) -print(found_class.name) - -found_class = module.find_class( - Typename(namespaces_name=['one', 'two', 'Class12a'])) -print(found_class.name) diff --git a/tests/test_docs.py b/tests/test_docs.py index 2fe4f2086..f6bec8293 100644 --- a/tests/test_docs.py +++ b/tests/test_docs.py @@ -1,6 +1,6 @@ """ Unit test for documentation generation -Author: Matthew Sklar +Author: Matthew Sklar, Varun Agrawal Date: May 2019 """ import filecmp @@ -16,7 +16,6 @@ sys.path.append(os.path.dirname(os.path.dirname(os.path.abspath(__file__)))) import docs.parser.parse_doxygen_xml as parser from docs.docs import ClassDoc, Doc, Docs, FreeDoc - tree_root = ET.Element('a') tree_left = ET.SubElement(tree_root, 'b') tree_right = ET.SubElement(tree_root, 1) @@ -31,6 +30,7 @@ d2 = ET.SubElement(d, 'd') class TestDocument(unittest.TestCase): + """Test class for document generation utilities.""" DIR_NAME = path.dirname(__file__) DOC_DIR = 'doc-test-files' @@ -42,33 +42,39 @@ class TestDocument(unittest.TestCase): EXPECTED_XML_DIR_PATH = path.abspath(path.join(DIR_NAME, EXPECTED_XML_DIR)) def test_generate_xml(self): - '''Test parse_xml.generate_xml''' - shutil.rmtree(self.OUTPUT_XML_DIR_PATH, ignore_errors=True) - parser.generate_xml( - self.DOC_DIR_PATH, self.OUTPUT_XML_DIR_PATH, quiet=True) + """Test parse_xml.generate_xml""" + if path.exists(self.OUTPUT_XML_DIR_PATH): + shutil.rmtree(self.OUTPUT_XML_DIR_PATH, ignore_errors=True) + parser.generate_xml(self.DOC_DIR_PATH, + self.OUTPUT_XML_DIR_PATH, + quiet=True) self.assertTrue(os.path.isdir(self.OUTPUT_XML_DIR_PATH)) - shutil.rmtree(path.join(self.OUTPUT_XML_DIR_PATH, 'xml')) - parser.generate_xml( - self.DOC_DIR_PATH, self.OUTPUT_XML_DIR_PATH, quiet=True) + xml_path = path.join(self.OUTPUT_XML_DIR_PATH, 'xml') + if path.exists(xml_path): + shutil.rmtree(xml_path) + parser.generate_xml(self.DOC_DIR_PATH, + self.OUTPUT_XML_DIR_PATH, + quiet=True) - dircmp = filecmp.dircmp( - self.OUTPUT_XML_DIR_PATH, self.EXPECTED_XML_DIR_PATH) + dircmp = filecmp.dircmp(self.OUTPUT_XML_DIR_PATH, + self.EXPECTED_XML_DIR_PATH) self.assertTrue(not dircmp.diff_files and not dircmp.funny_files) def test_parse(self): - docs = parser.ParseDoxygenXML( - self.DOC_DIR_PATH, self.OUTPUT_XML_DIR_PATH).run() + """Test the parsing of the XML generated by Doxygen.""" + docs = parser.ParseDoxygenXML(self.DOC_DIR_PATH, + self.OUTPUT_XML_DIR_PATH).run() for class_name in docs.get_class_docs_keys_list(): actual_tree_root = docs.get_class_docs( class_name).get_tree().getroot() expected_tree_root = ET.parse(class_name).getroot() - self.assertEqual( - ET.tostring(actual_tree_root), ET.tostring(expected_tree_root)) + self.assertEqual(ET.tostring(actual_tree_root), + ET.tostring(expected_tree_root)) class TestDocTemplate(unittest.TestCase): @@ -102,7 +108,7 @@ class TestDocTemplate(unittest.TestCase): # ClassDoc def test_class_doc(self): - '''Test the constructor in ClassDoc''' + """Test the constructor in ClassDoc""" self.assertIs(self.class_doc_root.tree, tree_root) self.assertIs(self.class_doc_left.tree, tree_left) self.assertIs(self.class_doc_right.tree, tree_right) @@ -110,7 +116,7 @@ class TestDocTemplate(unittest.TestCase): self.assertIs(self.class_doc_recursive.tree, tree_recursive) def test_class_doc_get_tree(self): - '''Test the get_tree() method is ClassDoc''' + """Test the get_tree() method is ClassDoc""" self.assertIs(self.class_doc_root.get_tree(), tree_root) self.assertIs(self.class_doc_left.get_tree(), tree_left) self.assertIs(self.class_doc_right.get_tree(), tree_right) @@ -118,7 +124,7 @@ class TestDocTemplate(unittest.TestCase): self.assertIs(self.class_doc_recursive.get_tree(), tree_recursive) def test_class_doc_eq(self): - '''Test ClassDoc.__eq__''' + """Test ClassDoc.__eq__""" doc1 = ClassDoc(ET.ElementTree(a)) doc2 = ClassDoc(ET.ElementTree(d)) doc3 = ClassDoc(ET.ElementTree(d2)) @@ -132,7 +138,7 @@ class TestDocTemplate(unittest.TestCase): # FreeDoc def test_free_doc(self): - '''Test the constructor in FreeDoc''' + """Test the constructor in FreeDoc""" self.assertIs(self.free_doc_root.tree, tree_root) self.assertIs(self.free_doc_left.tree, tree_left) self.assertIs(self.free_doc_right.tree, tree_right) @@ -140,7 +146,7 @@ class TestDocTemplate(unittest.TestCase): self.assertIs(self.free_doc_recursive.tree, tree_recursive) def test_free_doc_get_tree(self): - '''Test the get_tree() method is FreeDoc''' + """Test the get_tree() method is FreeDoc""" self.assertIs(self.free_doc_root.get_tree(), tree_root) self.assertIs(self.free_doc_left.get_tree(), tree_left) self.assertIs(self.free_doc_right.get_tree(), tree_right) @@ -148,7 +154,7 @@ class TestDocTemplate(unittest.TestCase): self.assertIs(self.free_doc_recursive.get_tree(), tree_recursive) def test_free_doc_eq(self): - '''Test FreeDoc.__eq__''' + """Test FreeDoc.__eq__""" doc1 = FreeDoc(ET.ElementTree(a)) doc2 = FreeDoc(ET.ElementTree(d)) doc3 = FreeDoc(ET.ElementTree(d2)) @@ -162,7 +168,7 @@ class TestDocTemplate(unittest.TestCase): # Docs def test_docs(self): - '''Test Docs template constructor''' + """Test Docs template constructor""" docs = Docs(self.CLASS_DOCS, self.FREE_DOCS) self.assertIs(docs.class_docs, self.CLASS_DOCS) @@ -172,15 +178,15 @@ class TestDocTemplate(unittest.TestCase): docs = Docs(self.CLASS_DOCS, self.FREE_DOCS) for doc_name in self.CLASS_DOCS.keys(): - self.assertIs( - self.CLASS_DOCS.get(doc_name), docs.get_class_docs(doc_name)) + self.assertIs(self.CLASS_DOCS.get(doc_name), + docs.get_class_docs(doc_name)) def test_get_free_docs(self): docs = Docs(self.CLASS_DOCS, self.FREE_DOCS) for doc_name in self.FREE_DOCS.keys(): - self.assertIs( - self.FREE_DOCS.get(doc_name), docs.get_free_docs(doc_name)) + self.assertIs(self.FREE_DOCS.get(doc_name), + docs.get_free_docs(doc_name)) def test_get_class_docs_keys_list(self): docs = Docs(self.CLASS_DOCS, self.FREE_DOCS) diff --git a/tests/test_interface_parser.py b/tests/test_interface_parser.py new file mode 100644 index 000000000..c43802b2a --- /dev/null +++ b/tests/test_interface_parser.py @@ -0,0 +1,372 @@ +""" +GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Tests for interface_parser. + +Author: Varun Agrawal +""" + +# pylint: disable=import-error,wrong-import-position + +import os +import sys +import unittest + +from pyparsing import ParseException + +sys.path.append(os.path.dirname(os.path.dirname(os.path.abspath(__file__)))) + +from gtwrap.interface_parser import (ArgumentList, Class, Constructor, + ForwardDeclaration, GlobalFunction, + Include, Method, Module, Namespace, + ReturnType, StaticMethod, Type, + TypedefTemplateInstantiation, Typename, + find_sub_namespace) + + +class TestInterfaceParser(unittest.TestCase): + """Test driver for all classes in interface_parser.py.""" + def test_typename(self): + """Test parsing of Typename.""" + typename = Typename.rule.parseString("size_t")[0] + self.assertEqual("size_t", typename.name) + + typename = Typename.rule.parseString("gtsam::PinholeCamera")[0] + self.assertEqual("PinholeCamera", typename.name) + self.assertEqual(["gtsam"], typename.namespaces) + self.assertEqual("Cal3S2", typename.instantiations[0].name) + self.assertEqual(["gtsam"], typename.instantiations[0].namespaces) + + def test_type(self): + """Test for Type.""" + t = Type.rule.parseString("int x")[0] + self.assertEqual("int", t.typename.name) + self.assertTrue(t.is_basis) + + t = Type.rule.parseString("T x")[0] + self.assertEqual("T", t.typename.name) + self.assertTrue(not t.is_basis) + + t = Type.rule.parseString("const int x")[0] + self.assertEqual("int", t.typename.name) + self.assertTrue(t.is_basis) + self.assertTrue(t.is_const) + + def test_empty_arguments(self): + """Test no arguments.""" + empty_args = ArgumentList.rule.parseString("")[0] + self.assertEqual(0, len(empty_args)) + + def test_argument_list(self): + """Test arguments list for a method/function.""" + arg_string = "int a, C1 c1, C2& c2, C3* c3, "\ + "const C4 c4, const C5& c5,"\ + "const C6* c6" + args = ArgumentList.rule.parseString(arg_string)[0] + + self.assertEqual(7, len(args.args_list)) + self.assertEqual(['a', 'c1', 'c2', 'c3', 'c4', 'c5', 'c6'], + args.args_names()) + + def test_argument_list_qualifiers(self): + """ + Test arguments list where the arguments are qualified with `const` + and can be either raw pointers, shared pointers or references. + """ + arg_string = "double x1, double* x2, double& x3, double@ x4, " \ + "const double x5, const double* x6, const double& x7, const double@ x8" + args = ArgumentList.rule.parseString(arg_string)[0].args_list + self.assertEqual(8, len(args)) + self.assertFalse(args[1].ctype.is_ptr and args[1].ctype.is_shared_ptr + and args[1].ctype.is_ref) + self.assertTrue(args[1].ctype.is_shared_ptr) + self.assertTrue(args[2].ctype.is_ref) + self.assertTrue(args[3].ctype.is_ptr) + self.assertTrue(args[4].ctype.is_const) + self.assertTrue(args[5].ctype.is_shared_ptr and args[5].ctype.is_const) + self.assertTrue(args[6].ctype.is_ref and args[6].ctype.is_const) + self.assertTrue(args[7].ctype.is_ptr and args[7].ctype.is_const) + + def test_return_type(self): + """Test ReturnType""" + # Test void + return_type = ReturnType.rule.parseString("void")[0] + self.assertEqual("void", return_type.type1.typename.name) + self.assertTrue(return_type.type1.is_basis) + + # Test basis type + return_type = ReturnType.rule.parseString("size_t")[0] + self.assertEqual("size_t", return_type.type1.typename.name) + self.assertTrue(not return_type.type2) + self.assertTrue(return_type.type1.is_basis) + + # Test with qualifiers + return_type = ReturnType.rule.parseString("int&")[0] + self.assertEqual("int", return_type.type1.typename.name) + self.assertTrue(return_type.type1.is_basis + and return_type.type1.is_ref) + + return_type = ReturnType.rule.parseString("const int")[0] + self.assertEqual("int", return_type.type1.typename.name) + self.assertTrue(return_type.type1.is_basis + and return_type.type1.is_const) + + # Test pair return + return_type = ReturnType.rule.parseString("pair")[0] + self.assertEqual("char", return_type.type1.typename.name) + self.assertEqual("int", return_type.type2.typename.name) + + def test_method(self): + """Test for a class method.""" + ret = Method.rule.parseString("int f();")[0] + self.assertEqual("f", ret.name) + self.assertEqual(0, len(ret.args)) + self.assertTrue(not ret.is_const) + + ret = Method.rule.parseString("int f() const;")[0] + self.assertEqual("f", ret.name) + self.assertEqual(0, len(ret.args)) + self.assertTrue(ret.is_const) + + ret = Method.rule.parseString( + "int f(const int x, const Class& c, Class* t) const;")[0] + self.assertEqual("f", ret.name) + self.assertEqual(3, len(ret.args)) + + def test_static_method(self): + """Test for static methods.""" + ret = StaticMethod.rule.parseString("static int f();")[0] + self.assertEqual("f", ret.name) + self.assertEqual(0, len(ret.args)) + + ret = StaticMethod.rule.parseString( + "static int f(const int x, const Class& c, Class* t);")[0] + self.assertEqual("f", ret.name) + self.assertEqual(3, len(ret.args)) + + def test_constructor(self): + """Test for class constructor.""" + ret = Constructor.rule.parseString("f();")[0] + self.assertEqual("f", ret.name) + self.assertEqual(0, len(ret.args)) + + ret = Constructor.rule.parseString( + "f(const int x, const Class& c, Class* t);")[0] + self.assertEqual("f", ret.name) + self.assertEqual(3, len(ret.args)) + + def test_typedef_template_instantiation(self): + """Test for typedef'd instantiation of a template.""" + typedef = TypedefTemplateInstantiation.rule.parseString(""" + typedef gtsam::BearingFactor + BearingFactor2D; + """)[0] + self.assertEqual("BearingFactor2D", typedef.new_name) + self.assertEqual("BearingFactor", typedef.typename.name) + self.assertEqual(["gtsam"], typedef.typename.namespaces) + self.assertEqual(3, len(typedef.typename.instantiations)) + + def test_base_class(self): + """Test a base class.""" + ret = Class.rule.parseString(""" + virtual class Base { + }; + """)[0] + self.assertEqual("Base", ret.name) + self.assertEqual(0, len(ret.ctors)) + self.assertEqual(0, len(ret.methods)) + self.assertEqual(0, len(ret.static_methods)) + self.assertEqual(0, len(ret.properties)) + self.assertTrue(ret.is_virtual) + + def test_empty_class(self): + """Test an empty class declaration.""" + ret = Class.rule.parseString(""" + class FactorIndices {}; + """)[0] + self.assertEqual("FactorIndices", ret.name) + self.assertEqual(0, len(ret.ctors)) + self.assertEqual(0, len(ret.methods)) + self.assertEqual(0, len(ret.static_methods)) + self.assertEqual(0, len(ret.properties)) + self.assertTrue(not ret.is_virtual) + + def test_class(self): + """Test a non-trivial class.""" + ret = Class.rule.parseString(""" + class SymbolicFactorGraph { + SymbolicFactorGraph(); + SymbolicFactorGraph(const gtsam::SymbolicBayesNet& bayesNet); + SymbolicFactorGraph(const gtsam::SymbolicBayesTree& bayesTree); + + // Dummy static method + static gtsam::SymbolidFactorGraph CreateGraph(); + + void push_back(gtsam::SymbolicFactor* factor); + void print(string s) const; + bool equals(const gtsam::SymbolicFactorGraph& rhs, double tol) const; + size_t size() const; + bool exists(size_t idx) const; + + // Standard interface + gtsam::KeySet keys() const; + void push_back(const gtsam::SymbolicFactorGraph& graph); + void push_back(const gtsam::SymbolicBayesNet& bayesNet); + void push_back(const gtsam::SymbolicBayesTree& bayesTree); + + /* Advanced interface */ + void push_factor(size_t key); + void push_factor(size_t key1, size_t key2); + void push_factor(size_t key1, size_t key2, size_t key3); + void push_factor(size_t key1, size_t key2, size_t key3, size_t key4); + + gtsam::SymbolicBayesNet* eliminateSequential(); + gtsam::SymbolicBayesNet* eliminateSequential( + const gtsam::Ordering& ordering); + gtsam::SymbolicBayesTree* eliminateMultifrontal(); + gtsam::SymbolicBayesTree* eliminateMultifrontal( + const gtsam::Ordering& ordering); + pair + eliminatePartialSequential(const gtsam::Ordering& ordering); + pair + eliminatePartialSequential(const gtsam::KeyVector& keys); + pair + eliminatePartialMultifrontal(const gtsam::Ordering& ordering); + gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet( + const gtsam::Ordering& ordering); + gtsam::SymbolicBayesNet* marginalMultifrontalBayesNet( + const gtsam::KeyVector& key_vector, + const gtsam::Ordering& marginalizedVariableOrdering); + gtsam::SymbolicFactorGraph* marginal(const gtsam::KeyVector& key_vector); + }; + """)[0] + + self.assertEqual("SymbolicFactorGraph", ret.name) + self.assertEqual(3, len(ret.ctors)) + self.assertEqual(23, len(ret.methods)) + self.assertEqual(1, len(ret.static_methods)) + self.assertEqual(0, len(ret.properties)) + self.assertTrue(not ret.is_virtual) + + def test_class_inheritance(self): + """Test for class inheritance.""" + ret = Class.rule.parseString(""" + virtual class Null: gtsam::noiseModel::mEstimator::Base { + Null(); + void print(string s) const; + static gtsam::noiseModel::mEstimator::Null* Create(); + + // enabling serialization functionality + void serializable() const; + }; + """)[0] + self.assertEqual("Null", ret.name) + self.assertEqual(1, len(ret.ctors)) + self.assertEqual(2, len(ret.methods)) + self.assertEqual(1, len(ret.static_methods)) + self.assertEqual(0, len(ret.properties)) + self.assertEqual("Base", ret.parent_class.name) + self.assertEqual(["gtsam", "noiseModel", "mEstimator"], + ret.parent_class.namespaces) + self.assertTrue(ret.is_virtual) + + def test_include(self): + """Test for include statements.""" + include = Include.rule.parseString( + "#include ")[0] + self.assertEqual("gtsam/slam/PriorFactor.h", include.header) + + def test_forward_declaration(self): + """Test for forward declarations.""" + fwd = ForwardDeclaration.rule.parseString( + "virtual class Test:gtsam::Point3;")[0] + + fwd_name = fwd.name.asList()[0] + self.assertEqual("Test", fwd_name.name) + self.assertTrue(fwd.is_virtual) + + def test_function(self): + """Test for global/free function.""" + func = GlobalFunction.rule.parseString(""" + gtsam::Values localToWorld(const gtsam::Values& local, + const gtsam::Pose2& base, const gtsam::KeyVector& keys); + """)[0] + self.assertEqual("localToWorld", func.name) + self.assertEqual("Values", func.return_type.type1.typename.name) + self.assertEqual(3, len(func.args)) + + def test_namespace(self): + """Test for namespace parsing.""" + namespace = Namespace.rule.parseString(""" + namespace gtsam { + #include + class Point2 { + Point2(); + Point2(double x, double y); + double x() const; + double y() const; + int dim() const; + char returnChar() const; + void argChar(char a) const; + void argUChar(unsigned char a) const; + }; + + #include + class Point3 { + Point3(double x, double y, double z); + double norm() const; + + // static functions - use static keyword and uppercase + static double staticFunction(); + static gtsam::Point3 StaticFunctionRet(double z); + + // enabling serialization functionality + void serialize() const; // Just triggers a flag internally + }; + }""")[0] + self.assertEqual("gtsam", namespace.name) + + def test_module(self): + """Test module parsing.""" + module = Module.parseString(""" + namespace one { + namespace two { + namespace three { + class Class123 { + }; + } + class Class12a { + }; + } + namespace two_dummy { + namespace three_dummy{ + + } + namespace fourth_dummy{ + + } + } + namespace two { + class Class12b { + + }; + } + } + + class Global{ + }; + """) + + # print("module: ", module) + # print(dir(module.content[0].name)) + self.assertEqual(["one", "Global"], [x.name for x in module.content]) + self.assertEqual(["two", "two_dummy", "two"], + [x.name for x in module.content[0].content]) + + +if __name__ == '__main__': + unittest.main() diff --git a/tests/test_matlab_wrapper.py b/tests/test_matlab_wrapper.py index 6e7699c86..ade85cb69 100644 --- a/tests/test_matlab_wrapper.py +++ b/tests/test_matlab_wrapper.py @@ -10,6 +10,8 @@ import os import sys import unittest +from loguru import logger + sys.path.append(os.path.dirname(os.path.dirname(os.path.abspath(__file__)))) import gtwrap.interface_parser as parser @@ -25,6 +27,10 @@ class TestWrap(unittest.TestCase): MATLAB_TEST_DIR = TEST_DIR + "expected-matlab/" MATLAB_ACTUAL_DIR = TEST_DIR + "actual-matlab/" + # set the log level to INFO by default + logger.remove() # remove the default sink + logger.add(sys.stderr, format="{time} {level} {message}", level="INFO") + def generate_content(self, cc_content, path=''): """Generate files and folders from matlab wrapper content. @@ -41,7 +47,7 @@ class TestWrap(unittest.TestCase): if isinstance(c, list): if len(c) == 0: continue - print("c object: {}".format(c[0][0]), file=sys.stderr) + logger.debug("c object: {}".format(c[0][0])) path_to_folder = path + '/' + c[0][0] if not os.path.isdir(path_to_folder): @@ -51,13 +57,13 @@ class TestWrap(unittest.TestCase): pass for sub_content in c: - print("sub object: {}".format(sub_content[1][0][0]), file=sys.stderr) + logger.debug("sub object: {}".format(sub_content[1][0][0])) self.generate_content(sub_content[1], path_to_folder) elif isinstance(c[1], list): path_to_folder = path + '/' + c[0] - print("[generate_content_global]: {}".format(path_to_folder), file=sys.stderr) + logger.debug("[generate_content_global]: {}".format(path_to_folder)) if not os.path.isdir(path_to_folder): try: os.makedirs(path_to_folder, exist_ok=True) @@ -65,14 +71,15 @@ class TestWrap(unittest.TestCase): pass for sub_content in c[1]: path_to_file = path_to_folder + '/' + sub_content[0] - print("[generate_global_method]: {}".format(path_to_file), file=sys.stderr) + logger.debug( + "[generate_global_method]: {}".format(path_to_file)) with open(path_to_file, 'w') as f: f.write(sub_content[1]) else: path_to_file = path + '/' + c[0] - print("[generate_content]: {}".format(path_to_file), file=sys.stderr) + logger.debug("[generate_content]: {}".format(path_to_file)) if not os.path.isdir(path_to_file): try: os.mkdir(path) @@ -122,23 +129,16 @@ class TestWrap(unittest.TestCase): self.assertTrue(os.path.isdir(self.MATLAB_ACTUAL_DIR + '+gtsam')) files = [ - '+gtsam/Point2.m', - '+gtsam/Point3.m', - 'Test.m', - 'MyBase.m', - 'load2D.m', - 'MyTemplatePoint2.m', - 'MyTemplateMatrix.m', - 'MyVector3.m', - 'MyVector12.m', - 'MyFactorPosePoint2.m', - 'aGlobalFunction.m', - 'overloadedGlobalFunction.m', + '+gtsam/Point2.m', '+gtsam/Point3.m', 'Test.m', 'MyBase.m', + 'load2D.m', 'MyTemplatePoint2.m', 'MyTemplateMatrix.m', + 'MyVector3.m', 'MyVector12.m', 'MyFactorPosePoint2.m', + 'aGlobalFunction.m', 'overloadedGlobalFunction.m', 'geometry_wrapper.cpp' ] for file in files: compare_and_diff(file) + if __name__ == '__main__': unittest.main() diff --git a/tests/test_pybind_wrapper.py b/tests/test_pybind_wrapper.py index 61edc3e78..7896ab28b 100644 --- a/tests/test_pybind_wrapper.py +++ b/tests/test_pybind_wrapper.py @@ -26,15 +26,10 @@ class TestWrap(unittest.TestCase): """Tests for Python wrapper based on Pybind11.""" TEST_DIR = os.path.dirname(os.path.realpath(__file__)) + "/" - def test_geometry_python(self): + def wrap_content(self, content, module_name, output_dir): """ - Check generation of python geometry wrapper. - python3 ../pybind_wrapper.py --src geometry.h --module_name - geometry_py --out output/geometry_py.cc" + Common function to wrap content. """ - with open(os.path.join(self.TEST_DIR, 'geometry.h'), 'r') as f: - content = f.read() - module = parser.Module.parseString(content) instantiator.instantiate_namespace_inplace(module) @@ -45,7 +40,7 @@ class TestWrap(unittest.TestCase): # Create Pybind wrapper instance wrapper = PybindWrapper( module=module, - module_name='geometry_py', + module_name=module_name, use_boost=False, top_module_namespaces=[''], ignore_classes=[''], @@ -54,14 +49,27 @@ class TestWrap(unittest.TestCase): cc_content = wrapper.wrap() - output = path.join(self.TEST_DIR, 'actual-python/geometry_py.cpp') + output = path.join(self.TEST_DIR, output_dir, module_name + ".cpp") - if not path.exists(path.join(self.TEST_DIR, 'actual-python')): - os.mkdir(path.join(self.TEST_DIR, 'actual-python')) + if not path.exists(path.join(self.TEST_DIR, output_dir)): + os.mkdir(path.join(self.TEST_DIR, output_dir)) with open(output, 'w') as f: f.write(cc_content) + return output + + def test_geometry_python(self): + """ + Check generation of python geometry wrapper. + python3 ../pybind_wrapper.py --src geometry.h --module_name + geometry_py --out output/geometry_py.cc + """ + with open(os.path.join(self.TEST_DIR, 'geometry.h'), 'r') as f: + content = f.read() + + output = self.wrap_content(content, 'geometry_py', 'actual-python') + expected = path.join(self.TEST_DIR, 'expected-python/geometry_pybind.cpp') success = filecmp.cmp(output, expected) @@ -69,5 +77,23 @@ class TestWrap(unittest.TestCase): os.system("diff {} {}".format(output, expected)) self.assertTrue(success) + def test_namespaces(self): + """ + Check generation of python geometry wrapper. + python3 ../pybind_wrapper.py --src testNamespaces.h --module_name + testNamespaces_py --out output/testNamespaces_py.cc + """ + with open(os.path.join(self.TEST_DIR, 'testNamespaces.h'), 'r') as f: + content = f.read() + + output = self.wrap_content(content, 'testNamespaces_py', 'actual-python') + + expected = path.join(self.TEST_DIR, 'expected-python/testNamespaces_py.cpp') + success = filecmp.cmp(output, expected) + + if not success: + os.system("diff {} {}".format(output, expected)) + self.assertTrue(success) + if __name__ == '__main__': unittest.main() From 66d3b95a6db2c261b2d280c11d19768d16c8874c Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Mar 2021 16:14:55 -0400 Subject: [PATCH 09/21] Squashed 'wrap/' changes from 3eff76f60..548e61b1f 548e61b1f Merge pull request #57 from borglab/fix/configurable-matlab-include b58eabaf1 set correct template file path 483cdab9c fix 1f393516d fix CI syntax 8f0a3543f more concise cmake command because we don't care about the extra files generated 641ad1326 update CI to run cmake de6b9260f added CMake variable to configure the include directory for matlab.h cbe5f18bc Merge pull request #54 from borglab/feature/refactor2 cc78ee3bb test formatting 046a50b01 break down interface_parser into a submodule of smaller parts git-subtree-dir: wrap git-subtree-split: 548e61b1fbf02759d2e4a52435c2f1b3cbde98f0 --- .github/workflows/linux-ci.yml | 1 + .github/workflows/macos-ci.yml | 2 + .gitignore | 4 +- CMakeLists.txt | 7 + gtwrap/interface_parser.py | 951 ------------------------- gtwrap/interface_parser/__init__.py | 43 ++ gtwrap/interface_parser/classes.py | 282 ++++++++ gtwrap/interface_parser/declaration.py | 60 ++ gtwrap/interface_parser/function.py | 166 +++++ gtwrap/interface_parser/module.py | 55 ++ gtwrap/interface_parser/namespace.py | 128 ++++ gtwrap/interface_parser/template.py | 90 +++ gtwrap/interface_parser/tokens.py | 48 ++ gtwrap/interface_parser/type.py | 232 ++++++ gtwrap/matlab_wrapper.py | 10 +- gtwrap/pybind_wrapper.py | 1 - templates/matlab_wrapper.tpl.in | 2 + tests/test_interface_parser.py | 8 +- tests/test_pybind_wrapper.py | 28 +- 19 files changed, 1144 insertions(+), 974 deletions(-) delete mode 100644 gtwrap/interface_parser.py create mode 100644 gtwrap/interface_parser/__init__.py create mode 100644 gtwrap/interface_parser/classes.py create mode 100644 gtwrap/interface_parser/declaration.py create mode 100644 gtwrap/interface_parser/function.py create mode 100644 gtwrap/interface_parser/module.py create mode 100644 gtwrap/interface_parser/namespace.py create mode 100644 gtwrap/interface_parser/template.py create mode 100644 gtwrap/interface_parser/tokens.py create mode 100644 gtwrap/interface_parser/type.py create mode 100644 templates/matlab_wrapper.tpl.in diff --git a/.github/workflows/linux-ci.yml b/.github/workflows/linux-ci.yml index 3d7232acd..34623385e 100644 --- a/.github/workflows/linux-ci.yml +++ b/.github/workflows/linux-ci.yml @@ -33,6 +33,7 @@ jobs: - name: Build and Test run: | + cmake . cd tests # Use Pytest to run all the tests. pytest diff --git a/.github/workflows/macos-ci.yml b/.github/workflows/macos-ci.yml index cd0571b34..3910d28d8 100644 --- a/.github/workflows/macos-ci.yml +++ b/.github/workflows/macos-ci.yml @@ -31,6 +31,8 @@ jobs: - name: Build and Test run: | + cmake . cd tests # Use Pytest to run all the tests. pytest + diff --git a/.gitignore b/.gitignore index 4bc4f119e..ed9bd8621 100644 --- a/.gitignore +++ b/.gitignore @@ -5,4 +5,6 @@ __pycache__/ *.egg-info # Files related to code coverage stats -**/.coverage \ No newline at end of file +**/.coverage + +gtwrap/matlab_wrapper.tpl diff --git a/CMakeLists.txt b/CMakeLists.txt index 3b1bbc1fe..883f438e6 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -21,6 +21,13 @@ else() set(SCRIPT_INSTALL_DIR "${CMAKE_INSTALL_PREFIX}/lib/cmake") endif() +# Configure the include directory for matlab.h +# This allows the #include to be either gtwrap/matlab.h, wrap/matlab.h or something custom. +if(NOT DEFINED GTWRAP_INCLUDE_NAME) + set(GTWRAP_INCLUDE_NAME "gtwrap" CACHE INTERNAL "Directory name for Matlab includes") +endif() +configure_file(${PROJECT_SOURCE_DIR}/templates/matlab_wrapper.tpl.in ${PROJECT_SOURCE_DIR}/gtwrap/matlab_wrapper.tpl) + # Install CMake scripts to the standard CMake script directory. install(FILES cmake/gtwrapConfig.cmake cmake/MatlabWrap.cmake cmake/PybindWrap.cmake cmake/GtwrapUtils.cmake diff --git a/gtwrap/interface_parser.py b/gtwrap/interface_parser.py deleted file mode 100644 index 157de555a..000000000 --- a/gtwrap/interface_parser.py +++ /dev/null @@ -1,951 +0,0 @@ -""" -GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, -Atlanta, Georgia 30332-0415 -All Rights Reserved - -See LICENSE for the license information - -Parser to get the interface of a C++ source file -Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellaert -""" - -# pylint: disable=unnecessary-lambda, unused-import, expression-not-assigned, no-else-return, protected-access, too-few-public-methods, too-many-arguments - -import sys -from typing import Iterable, Union, Tuple, List - -import pyparsing # type: ignore -from pyparsing import (CharsNotIn, Forward, Group, Keyword, Literal, OneOrMore, - Optional, Or, ParseException, ParseResults, ParserElement, Suppress, - Word, ZeroOrMore, alphanums, alphas, cppStyleComment, - delimitedList, empty, nums, stringEnd) - -# Fix deepcopy issue with pyparsing -# Can remove once https://github.com/pyparsing/pyparsing/issues/208 is resolved. -if sys.version_info >= (3, 8): - def fixed_get_attr(self, item): - """ - Fix for monkey-patching issue with deepcopy in pyparsing.ParseResults - """ - if item == '__deepcopy__': - raise AttributeError(item) - try: - return self[item] - except KeyError: - return "" - - # apply the monkey-patch - pyparsing.ParseResults.__getattr__ = fixed_get_attr - - -ParserElement.enablePackrat() - -# rule for identifiers (e.g. variable names) -IDENT = Word(alphas + '_', alphanums + '_') ^ Word(nums) - -RAW_POINTER, SHARED_POINTER, REF = map(Literal, "@*&") - -LPAREN, RPAREN, LBRACE, RBRACE, COLON, SEMI_COLON = map(Suppress, "(){}:;") -LOPBRACK, ROPBRACK, COMMA, EQUAL = map(Suppress, "<>,=") -CONST, VIRTUAL, CLASS, STATIC, PAIR, TEMPLATE, TYPEDEF, INCLUDE = map( - Keyword, - [ - "const", - "virtual", - "class", - "static", - "pair", - "template", - "typedef", - "#include", - ], -) -NAMESPACE = Keyword("namespace") -BASIS_TYPES = map( - Keyword, - [ - "void", - "bool", - "unsigned char", - "char", - "int", - "size_t", - "double", - "float", - ], -) - - -class Typename: - """ - Generic type which can be either a basic type or a class type, - similar to C++'s `typename` aka a qualified dependent type. - Contains type name with full namespace and template arguments. - - E.g. - ``` - gtsam::PinholeCamera - ``` - - will give the name as `PinholeCamera`, namespace as `gtsam`, - and template instantiations as `[gtsam::Cal3S2]`. - - Args: - namespaces_and_name: A list representing the namespaces of the type - with the type being the last element. - instantiations: Template parameters to the type. - """ - - namespaces_name_rule = delimitedList(IDENT, "::") - instantiation_name_rule = delimitedList(IDENT, "::") - rule = Forward() - rule << ( - namespaces_name_rule("namespaces_and_name") # - + Optional( - (LOPBRACK + delimitedList(rule, ",")("instantiations") + ROPBRACK)) - ).setParseAction(lambda t: Typename(t.namespaces_and_name, t.instantiations)) - - def __init__(self, - namespaces_and_name: ParseResults, - instantiations: Union[tuple, list, str, ParseResults] = ()): - self.name = namespaces_and_name[-1] # the name is the last element in this list - self.namespaces = namespaces_and_name[:-1] - - if instantiations: - if isinstance(instantiations, Iterable): - self.instantiations = instantiations # type: ignore - else: - self.instantiations = instantiations.asList() - else: - self.instantiations = [] - - if self.name in ["Matrix", "Vector"] and not self.namespaces: - self.namespaces = ["gtsam"] - - @staticmethod - def from_parse_result(parse_result: Union[str, list]): - """Unpack the parsed result to get the Typename instance.""" - return parse_result[0] - - def __repr__(self) -> str: - return self.to_cpp() - - def instantiated_name(self) -> str: - """Get the instantiated name of the type.""" - res = self.name - for instantiation in self.instantiations: - res += instantiation.instantiated_name() - return res - - def to_cpp(self) -> str: - """Generate the C++ code for wrapping.""" - idx = 1 if self.namespaces and not self.namespaces[0] else 0 - if self.instantiations: - cpp_name = self.name + "<{}>".format( - ", ".join([inst.to_cpp() for inst in self.instantiations]) - ) - else: - cpp_name = self.name - return '{}{}{}'.format( - "::".join(self.namespaces[idx:]), - "::" if self.namespaces[idx:] else "", - cpp_name, - ) - - def __eq__(self, other) -> bool: - if isinstance(other, Typename): - return str(self) == str(other) - else: - return False - - def __ne__(self, other) -> bool: - res = self.__eq__(other) - return not res - - -class QualifiedType: - """Type with qualifiers, such as `const`.""" - - rule = ( - Typename.rule("typename") # - + Optional(SHARED_POINTER("is_shared_ptr") | RAW_POINTER("is_ptr") | REF("is_ref")) - ).setParseAction( - lambda t: QualifiedType(t) - ) - - def __init__(self, t: ParseResults): - self.typename = Typename.from_parse_result(t.typename) - self.is_shared_ptr = t.is_shared_ptr - self.is_ptr = t.is_ptr - self.is_ref = t.is_ref - -class BasisType: - """ - Basis types are the built-in types in C++ such as double, int, char, etc. - - When using templates, the basis type will take on the same form as the template. - - E.g. - ``` - template - void func(const T& x); - ``` - - will give - - ``` - m_.def("CoolFunctionDoubleDouble",[](const double& s) { - return wrap_example::CoolFunction(s); - }, py::arg("s")); - ``` - """ - - rule = ( - Or(BASIS_TYPES)("typename") # - + Optional(SHARED_POINTER("is_shared_ptr") | RAW_POINTER("is_ptr") | REF("is_ref")) # - ).setParseAction(lambda t: BasisType(t)) - - def __init__(self, t: ParseResults): - self.typename = Typename([t.typename]) - self.is_ptr = t.is_ptr - self.is_shared_ptr = t.is_shared_ptr - self.is_ref = t.is_ref - -class Type: - """The type value that is parsed, e.g. void, string, size_t.""" - rule = ( - Optional(CONST("is_const")) # - + (BasisType.rule("basis") | QualifiedType.rule("qualified")) # BR - ).setParseAction(lambda t: Type.from_parse_result(t)) - - def __init__(self, typename: Typename, is_const: str, is_shared_ptr: str, - is_ptr: str, is_ref: str, is_basis: bool): - self.typename = typename - self.is_const = is_const - self.is_shared_ptr = is_shared_ptr - self.is_ptr = is_ptr - self.is_ref = is_ref - self.is_basis = is_basis - - @staticmethod - def from_parse_result(t: ParseResults): - """Return the resulting Type from parsing the source.""" - if t.basis: - return Type( - typename=t.basis.typename, - is_const=t.is_const, - is_shared_ptr=t.basis.is_shared_ptr, - is_ptr=t.basis.is_ptr, - is_ref=t.basis.is_ref, - is_basis=True, - ) - elif t.qualified: - return Type( - typename=t.qualified.typename, - is_const=t.is_const, - is_shared_ptr=t.qualified.is_shared_ptr, - is_ptr=t.qualified.is_ptr, - is_ref=t.qualified.is_ref, - is_basis=False, - ) - else: - raise ValueError("Parse result is not a Type") - - def __repr__(self) -> str: - return "{self.typename} " \ - "{self.is_const}{self.is_shared_ptr}{self.is_ptr}{self.is_ref}".format( - self=self) - - def to_cpp(self, use_boost: bool) -> str: - """ - Generate the C++ code for wrapping. - - Treat all pointers as "const shared_ptr&" - Treat Matrix and Vector as "const Matrix&" and "const Vector&" resp. - """ - shared_ptr_ns = "boost" if use_boost else "std" - - if self.is_shared_ptr: - # always pass by reference: https://stackoverflow.com/a/8741626/1236990 - typename = "{ns}::shared_ptr<{typename}>&".format( - ns=shared_ptr_ns, typename=self.typename.to_cpp()) - elif self.is_ptr: - typename = "{typename}*".format(typename=self.typename.to_cpp()) - elif self.is_ref or self.typename.name in ["Matrix", "Vector"]: - typename = typename = "{typename}&".format( - typename=self.typename.to_cpp()) - else: - typename = self.typename.to_cpp() - - return ("{const}{typename}".format( - const="const " if - (self.is_const - or self.typename.name in ["Matrix", "Vector"]) else "", - typename=typename)) - - -class Argument: - """ - The type and name of a function/method argument. - - E.g. - ``` - void sayHello(/*`s` is the method argument with type `const string&`*/ const string& s); - ``` - """ - rule = (Type.rule("ctype") + - IDENT("name")).setParseAction(lambda t: Argument(t.ctype, t.name)) - - def __init__(self, ctype: Type, name: str): - self.ctype = ctype - self.name = name - self.parent: Union[ArgumentList, None] = None - - def __repr__(self) -> str: - return '{} {}'.format(self.ctype.__repr__(), self.name) - - -class ArgumentList: - """ - List of Argument objects for all arguments in a function. - """ - rule = Optional(delimitedList(Argument.rule)("args_list")).setParseAction( - lambda t: ArgumentList.from_parse_result(t.args_list) - ) - - def __init__(self, args_list: List[Argument]): - self.args_list = args_list - for arg in args_list: - arg.parent = self - self.parent: Union[Method, StaticMethod, Template, Constructor, - GlobalFunction, None] = None - - @staticmethod - def from_parse_result(parse_result: ParseResults): - """Return the result of parsing.""" - if parse_result: - return ArgumentList(parse_result.asList()) - else: - return ArgumentList([]) - - def __repr__(self) -> str: - return self.args_list.__repr__() - - def __len__(self) -> int: - return len(self.args_list) - - def args_names(self) -> List[str]: - """Return a list of the names of all the arguments.""" - return [arg.name for arg in self.args_list] - - def to_cpp(self, use_boost: bool) -> List[str]: - """Generate the C++ code for wrapping.""" - return [arg.ctype.to_cpp(use_boost) for arg in self.args_list] - - -class ReturnType: - """ - Rule to parse the return type. - - The return type can either be a single type or a pair such as . - """ - _pair = ( - PAIR.suppress() # - + LOPBRACK # - + Type.rule("type1") # - + COMMA # - + Type.rule("type2") # - + ROPBRACK # - ) - rule = (_pair ^ Type.rule("type1")).setParseAction( # BR - lambda t: ReturnType(t.type1, t.type2)) - - def __init__(self, type1: Type, type2: Type): - self.type1 = type1 - self.type2 = type2 - self.parent: Union[Method, StaticMethod, GlobalFunction, None] = None - - def is_void(self) -> bool: - """ - Check if the return type is void. - """ - return self.type1.typename.name == "void" and not self.type2 - - def __repr__(self) -> str: - return "{}{}".format( - self.type1, (', ' + self.type2.__repr__()) if self.type2 else '') - - def to_cpp(self, use_boost: bool) -> str: - """ - Generate the C++ code for wrapping. - - If there are two return types, we return a pair<>, - otherwise we return the regular return type. - """ - if self.type2: - return "std::pair<{type1},{type2}>".format( - type1=self.type1.to_cpp(use_boost), - type2=self.type2.to_cpp(use_boost)) - else: - return self.type1.to_cpp(use_boost) - - -class Template: - """ - Rule to parse templated values in the interface file. - - E.g. - template // this is the Template. - class Camera { ... }; - """ - class TypenameAndInstantiations: - """ - Rule to parse the template parameters. - - template // POSE is the Instantiation. - """ - rule = ( - IDENT("typename") # - + Optional( # - EQUAL # - + LBRACE # - + ((delimitedList(Typename.rule)("instantiations"))) # - + RBRACE # - )).setParseAction(lambda t: Template.TypenameAndInstantiations( - t.typename, t.instantiations)) - - def __init__(self, typename: str, instantiations: ParseResults): - self.typename = typename - - if instantiations: - self.instantiations = instantiations.asList() - else: - self.instantiations = [] - - rule = ( # BR - TEMPLATE # - + LOPBRACK # - + delimitedList(TypenameAndInstantiations.rule)( - "typename_and_instantiations_list") # - + ROPBRACK # BR - ).setParseAction( - lambda t: Template(t.typename_and_instantiations_list.asList())) - - def __init__(self, typename_and_instantiations_list: List[TypenameAndInstantiations]): - ti_list = typename_and_instantiations_list - self.typenames = [ti.typename for ti in ti_list] - self.instantiations = [ti.instantiations for ti in ti_list] - - def __repr__(self) -> str: - return "<{0}>".format(", ".join(self.typenames)) - - -class Method: - """ - Rule to parse a method in a class. - - E.g. - ``` - class Hello { - void sayHello() const; - }; - ``` - """ - rule = ( - Optional(Template.rule("template")) # - + ReturnType.rule("return_type") # - + IDENT("name") # - + LPAREN # - + ArgumentList.rule("args_list") # - + RPAREN # - + Optional(CONST("is_const")) # - + SEMI_COLON # BR - ).setParseAction(lambda t: Method(t.template, t.name, t.return_type, t. - args_list, t.is_const)) - - def __init__(self, - template: str, - name: str, - return_type: ReturnType, - args: ArgumentList, - is_const: str, - parent: Union[str, "Class"] = ''): - self.template = template - self.name = name - self.return_type = return_type - self.args = args - self.is_const = is_const - - self.parent = parent - - def __repr__(self) -> str: - return "Method: {} {} {}({}){}".format( - self.template, - self.return_type, - self.name, - self.args, - self.is_const, - ) - - -class StaticMethod: - """ - Rule to parse all the static methods in a class. - - E.g. - ``` - class Hello { - static void changeGreeting(); - }; - ``` - """ - rule = ( - STATIC # - + ReturnType.rule("return_type") # - + IDENT("name") # - + LPAREN # - + ArgumentList.rule("args_list") # - + RPAREN # - + SEMI_COLON # BR - ).setParseAction( - lambda t: StaticMethod(t.name, t.return_type, t.args_list)) - - def __init__(self, - name: str, - return_type: ReturnType, - args: ArgumentList, - parent: Union[str, "Class"] = ''): - self.name = name - self.return_type = return_type - self.args = args - - self.parent = parent - - def __repr__(self) -> str: - return "static {} {}{}".format(self.return_type, self.name, self.args) - - def to_cpp(self) -> str: - """Generate the C++ code for wrapping.""" - return self.name - - -class Constructor: - """ - Rule to parse the class constructor. - Can have 0 or more arguments. - """ - rule = ( - IDENT("name") # - + LPAREN # - + ArgumentList.rule("args_list") # - + RPAREN # - + SEMI_COLON # BR - ).setParseAction(lambda t: Constructor(t.name, t.args_list)) - - def __init__(self, name: str, args: ArgumentList, parent: Union["Class", str] =''): - self.name = name - self.args = args - - self.parent = parent - - def __repr__(self) -> str: - return "Constructor: {}".format(self.name) - - -class Property: - """ - Rule to parse the variable members of a class. - - E.g. - ``` - class Hello { - string name; // This is a property. - }; - ```` - """ - rule = ( - Type.rule("ctype") # - + IDENT("name") # - + SEMI_COLON # - ).setParseAction(lambda t: Property(t.ctype, t.name)) - - def __init__(self, ctype: Type, name: str, parent=''): - self.ctype = ctype - self.name = name - self.parent = parent - - def __repr__(self) -> str: - return '{} {}'.format(self.ctype.__repr__(), self.name) - - -def collect_namespaces(obj): - """ - Get the chain of namespaces from the lowest to highest for the given object. - - Args: - obj: Object of type Namespace, Class or InstantiatedClass. - """ - namespaces = [] - ancestor = obj.parent - while ancestor and ancestor.name: - namespaces = [ancestor.name] + namespaces - ancestor = ancestor.parent - return [''] + namespaces - - -class Class: - """ - Rule to parse a class defined in the interface file. - - E.g. - ``` - class Hello { - ... - }; - ``` - """ - class MethodsAndProperties: - """ - Rule for all the methods and properties within a class. - """ - rule = ZeroOrMore( - Constructor.rule ^ StaticMethod.rule ^ Method.rule ^ Property.rule - ).setParseAction(lambda t: Class.MethodsAndProperties(t.asList())) - - def __init__(self, methods_props: List[Union[Constructor, Method, - StaticMethod, Property]]): - self.ctors = [] - self.methods = [] - self.static_methods = [] - self.properties = [] - for m in methods_props: - if isinstance(m, Constructor): - self.ctors.append(m) - elif isinstance(m, Method): - self.methods.append(m) - elif isinstance(m, StaticMethod): - self.static_methods.append(m) - elif isinstance(m, Property): - self.properties.append(m) - - _parent = COLON + Typename.rule("parent_class") - rule = ( - Optional(Template.rule("template")) # - + Optional(VIRTUAL("is_virtual")) # - + CLASS # - + IDENT("name") # - + Optional(_parent) # - + LBRACE # - + MethodsAndProperties.rule("methods_props") # - + RBRACE # - + SEMI_COLON # BR - ).setParseAction(lambda t: Class( - t.template, - t.is_virtual, - t.name, - t.parent_class, - t.methods_props.ctors, - t.methods_props.methods, - t.methods_props.static_methods, - t.methods_props.properties, - )) - - def __init__( - self, - template: Template, - is_virtual: str, - name: str, - parent_class: list, - ctors: List[Constructor], - methods: List[Method], - static_methods: List[StaticMethod], - properties: List[Property], - parent: str = '', - ): - self.template = template - self.is_virtual = is_virtual - self.name = name - if parent_class: - self.parent_class = Typename.from_parse_result(parent_class) - else: - self.parent_class = '' - - self.ctors = ctors - self.methods = methods - self.static_methods = static_methods - self.properties = properties - self.parent = parent - # Make sure ctors' names and class name are the same. - for ctor in self.ctors: - if ctor.name != self.name: - raise ValueError( - "Error in constructor name! {} != {}".format( - ctor.name, self.name - ) - ) - - for ctor in self.ctors: - ctor.parent = self - for method in self.methods: - method.parent = self - for static_method in self.static_methods: - static_method.parent = self - for _property in self.properties: - _property.parent = self - - def namespaces(self) -> list: - """Get the namespaces which this class is nested under as a list.""" - return collect_namespaces(self) - - def __repr__(self): - return "Class: {self.name}".format(self=self) - - -class TypedefTemplateInstantiation: - """ - Rule for parsing typedefs (with templates) within the interface file. - - E.g. - ``` - typedef SuperComplexName EasierName; - ``` - """ - rule = ( - TYPEDEF + Typename.rule("typename") + IDENT("new_name") + SEMI_COLON - ).setParseAction( - lambda t: TypedefTemplateInstantiation( - Typename.from_parse_result(t.typename), t.new_name - ) - ) - - def __init__(self, typename: Typename, new_name: str, parent: str=''): - self.typename = typename - self.new_name = new_name - self.parent = parent - - -class Include: - """ - Rule to parse #include directives. - """ - rule = ( - INCLUDE + LOPBRACK + CharsNotIn('>')("header") + ROPBRACK - ).setParseAction(lambda t: Include(t.header)) - - def __init__(self, header: CharsNotIn, parent: str = ''): - self.header = header - self.parent = parent - - def __repr__(self) -> str: - return "#include <{}>".format(self.header) - - -class ForwardDeclaration: - """ - Rule to parse forward declarations in the interface file. - """ - rule = ( - Optional(VIRTUAL("is_virtual")) - + CLASS - + Typename.rule("name") - + Optional(COLON + Typename.rule("parent_type")) - + SEMI_COLON - ).setParseAction( - lambda t: ForwardDeclaration(t.name, t.parent_type, t.is_virtual) - ) - - def __init__(self, - name: Typename, - parent_type: str, - is_virtual: str, - parent: str = ''): - self.name = name - if parent_type: - self.parent_type = Typename.from_parse_result(parent_type) - else: - self.parent_type = '' - - self.is_virtual = is_virtual - self.parent = parent - - def __repr__(self) -> str: - return "ForwardDeclaration: {} {}({})".format(self.is_virtual, - self.name, self.parent) - - -class GlobalFunction: - """ - Rule to parse functions defined in the global scope. - """ - rule = ( - Optional(Template.rule("template")) - + ReturnType.rule("return_type") # - + IDENT("name") # - + LPAREN # - + ArgumentList.rule("args_list") # - + RPAREN # - + SEMI_COLON # - ).setParseAction(lambda t: GlobalFunction(t.name, t.return_type, t. - args_list, t.template)) - - def __init__(self, - name: str, - return_type: ReturnType, - args_list: ArgumentList, - template: Template, - parent: str = ''): - self.name = name - self.return_type = return_type - self.args = args_list - self.template = template - - self.parent = parent - self.return_type.parent = self - self.args.parent = self - - def __repr__(self) -> str: - return "GlobalFunction: {}{}({})".format( - self.return_type, self.name, self.args - ) - - def to_cpp(self) -> str: - """Generate the C++ code for wrapping.""" - return self.name - - -def find_sub_namespace(namespace: "Namespace", - str_namespaces: List["Namespace"]) -> list: - """ - Get the namespaces nested under `namespace`, filtered by a list of namespace strings. - - Args: - namespace: The top-level namespace under which to find sub-namespaces. - str_namespaces: The list of namespace strings to filter against. - """ - if not str_namespaces: - return [namespace] - - sub_namespaces = ( - ns for ns in namespace.content if isinstance(ns, Namespace) - ) - - found_namespaces = [ - ns for ns in sub_namespaces if ns.name == str_namespaces[0] - ] - if not found_namespaces: - return [] - - res = [] - for found_namespace in found_namespaces: - ns = find_sub_namespace(found_namespace, str_namespaces[1:]) - if ns: - res += ns - return res - - -class Namespace: - """Rule for parsing a namespace in the interface file.""" - - rule = Forward() - rule << ( - NAMESPACE # - + IDENT("name") # - + LBRACE # - + ZeroOrMore( # BR - ForwardDeclaration.rule # - ^ Include.rule # - ^ Class.rule # - ^ TypedefTemplateInstantiation.rule # - ^ GlobalFunction.rule # - ^ rule # - )("content") # BR - + RBRACE # - ).setParseAction(lambda t: Namespace.from_parse_result(t)) - - def __init__(self, name: str, content: ZeroOrMore, parent=''): - self.name = name - self.content = content - self.parent = parent - for child in self.content: - child.parent = self - - @staticmethod - def from_parse_result(t: ParseResults): - """Return the result of parsing.""" - if t.content: - content = t.content.asList() - else: - content = [] - return Namespace(t.name, content) - - def find_class_or_function( - self, typename: Typename) -> Union[Class, GlobalFunction]: - """ - Find the Class or GlobalFunction object given its typename. - We have to traverse the tree of namespaces. - """ - found_namespaces = find_sub_namespace(self, typename.namespaces) - res = [] - for namespace in found_namespaces: - classes_and_funcs = (c for c in namespace.content - if isinstance(c, (Class, GlobalFunction))) - res += [c for c in classes_and_funcs if c.name == typename.name] - if not res: - raise ValueError( - "Cannot find class {} in module!".format(typename.name) - ) - elif len(res) > 1: - raise ValueError( - "Found more than one classes {} in module!".format( - typename.name - ) - ) - else: - return res[0] - - def top_level(self) -> "Namespace": - """Return the top leve namespace.""" - if self.name == '' or self.parent == '': - return self - else: - return self.parent.top_level() - - def __repr__(self) -> str: - return "Namespace: {}\n\t{}".format(self.name, self.content) - - def full_namespaces(self) -> List["Namespace"]: - """Get the full namespace list.""" - ancestors = collect_namespaces(self) - if self.name: - ancestors.append(self.name) - return ancestors - - -class Module: - """ - Module is just a global namespace. - - E.g. - ``` - namespace gtsam { - ... - } - ``` - """ - - rule = ( - ZeroOrMore(ForwardDeclaration.rule # - ^ Include.rule # - ^ Class.rule # - ^ TypedefTemplateInstantiation.rule # - ^ GlobalFunction.rule # - ^ Namespace.rule # - ).setParseAction(lambda t: Namespace('', t.asList())) + - stringEnd) - - rule.ignore(cppStyleComment) - - @staticmethod - def parseString(s: str) -> ParseResults: - """Parse the source string and apply the rules.""" - return Module.rule.parseString(s)[0] diff --git a/gtwrap/interface_parser/__init__.py b/gtwrap/interface_parser/__init__.py new file mode 100644 index 000000000..8bb1fc7dd --- /dev/null +++ b/gtwrap/interface_parser/__init__.py @@ -0,0 +1,43 @@ +""" +GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Parser to get the interface of a C++ source file + +Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellaert +""" + +import sys +import pyparsing + +from .classes import * +from .declaration import * +from .function import * +from .module import * +from .namespace import * +from .template import * +from .tokens import * +from .type import * + +# Fix deepcopy issue with pyparsing +# Can remove once https://github.com/pyparsing/pyparsing/issues/208 is resolved. +if sys.version_info >= (3, 8): + + def fixed_get_attr(self, item): + """ + Fix for monkey-patching issue with deepcopy in pyparsing.ParseResults + """ + if item == '__deepcopy__': + raise AttributeError(item) + try: + return self[item] + except KeyError: + return "" + + # apply the monkey-patch + pyparsing.ParseResults.__getattr__ = fixed_get_attr + +pyparsing.ParserElement.enablePackrat() diff --git a/gtwrap/interface_parser/classes.py b/gtwrap/interface_parser/classes.py new file mode 100644 index 000000000..7332e0bfe --- /dev/null +++ b/gtwrap/interface_parser/classes.py @@ -0,0 +1,282 @@ +""" +GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Parser classes and rules for parsing C++ classes. + +Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellaert +""" + +from typing import List, Union + +from pyparsing import Optional, ZeroOrMore + +from .function import ArgumentList, ReturnType +from .template import Template +from .tokens import (CLASS, COLON, CONST, IDENT, LBRACE, LPAREN, RBRACE, + RPAREN, SEMI_COLON, STATIC, VIRTUAL) +from .type import Type, Typename + + +class Method: + """ + Rule to parse a method in a class. + + E.g. + ``` + class Hello { + void sayHello() const; + }; + ``` + """ + rule = ( + Optional(Template.rule("template")) # + + ReturnType.rule("return_type") # + + IDENT("name") # + + LPAREN # + + ArgumentList.rule("args_list") # + + RPAREN # + + Optional(CONST("is_const")) # + + SEMI_COLON # BR + ).setParseAction(lambda t: Method(t.template, t.name, t.return_type, t. + args_list, t.is_const)) + + def __init__(self, + template: str, + name: str, + return_type: ReturnType, + args: ArgumentList, + is_const: str, + parent: Union[str, "Class"] = ''): + self.template = template + self.name = name + self.return_type = return_type + self.args = args + self.is_const = is_const + + self.parent = parent + + def __repr__(self) -> str: + return "Method: {} {} {}({}){}".format( + self.template, + self.return_type, + self.name, + self.args, + self.is_const, + ) + + +class StaticMethod: + """ + Rule to parse all the static methods in a class. + + E.g. + ``` + class Hello { + static void changeGreeting(); + }; + ``` + """ + rule = ( + STATIC # + + ReturnType.rule("return_type") # + + IDENT("name") # + + LPAREN # + + ArgumentList.rule("args_list") # + + RPAREN # + + SEMI_COLON # BR + ).setParseAction( + lambda t: StaticMethod(t.name, t.return_type, t.args_list)) + + def __init__(self, + name: str, + return_type: ReturnType, + args: ArgumentList, + parent: Union[str, "Class"] = ''): + self.name = name + self.return_type = return_type + self.args = args + + self.parent = parent + + def __repr__(self) -> str: + return "static {} {}{}".format(self.return_type, self.name, self.args) + + def to_cpp(self) -> str: + """Generate the C++ code for wrapping.""" + return self.name + + +class Constructor: + """ + Rule to parse the class constructor. + Can have 0 or more arguments. + """ + rule = ( + IDENT("name") # + + LPAREN # + + ArgumentList.rule("args_list") # + + RPAREN # + + SEMI_COLON # BR + ).setParseAction(lambda t: Constructor(t.name, t.args_list)) + + def __init__(self, + name: str, + args: ArgumentList, + parent: Union["Class", str] = ''): + self.name = name + self.args = args + + self.parent = parent + + def __repr__(self) -> str: + return "Constructor: {}".format(self.name) + + +class Property: + """ + Rule to parse the variable members of a class. + + E.g. + ``` + class Hello { + string name; // This is a property. + }; + ```` + """ + rule = ( + Type.rule("ctype") # + + IDENT("name") # + + SEMI_COLON # + ).setParseAction(lambda t: Property(t.ctype, t.name)) + + def __init__(self, ctype: Type, name: str, parent=''): + self.ctype = ctype + self.name = name + self.parent = parent + + def __repr__(self) -> str: + return '{} {}'.format(self.ctype.__repr__(), self.name) + + +def collect_namespaces(obj): + """ + Get the chain of namespaces from the lowest to highest for the given object. + + Args: + obj: Object of type Namespace, Class or InstantiatedClass. + """ + namespaces = [] + ancestor = obj.parent + while ancestor and ancestor.name: + namespaces = [ancestor.name] + namespaces + ancestor = ancestor.parent + return [''] + namespaces + + +class Class: + """ + Rule to parse a class defined in the interface file. + + E.g. + ``` + class Hello { + ... + }; + ``` + """ + class MethodsAndProperties: + """ + Rule for all the methods and properties within a class. + """ + rule = ZeroOrMore(Constructor.rule ^ StaticMethod.rule ^ Method.rule + ^ Property.rule).setParseAction( + lambda t: Class.MethodsAndProperties(t.asList())) + + def __init__(self, methods_props: List[Union[Constructor, Method, + StaticMethod, Property]]): + self.ctors = [] + self.methods = [] + self.static_methods = [] + self.properties = [] + for m in methods_props: + if isinstance(m, Constructor): + self.ctors.append(m) + elif isinstance(m, Method): + self.methods.append(m) + elif isinstance(m, StaticMethod): + self.static_methods.append(m) + elif isinstance(m, Property): + self.properties.append(m) + + _parent = COLON + Typename.rule("parent_class") + rule = ( + Optional(Template.rule("template")) # + + Optional(VIRTUAL("is_virtual")) # + + CLASS # + + IDENT("name") # + + Optional(_parent) # + + LBRACE # + + MethodsAndProperties.rule("methods_props") # + + RBRACE # + + SEMI_COLON # BR + ).setParseAction(lambda t: Class( + t.template, + t.is_virtual, + t.name, + t.parent_class, + t.methods_props.ctors, + t.methods_props.methods, + t.methods_props.static_methods, + t.methods_props.properties, + )) + + def __init__( + self, + template: Template, + is_virtual: str, + name: str, + parent_class: list, + ctors: List[Constructor], + methods: List[Method], + static_methods: List[StaticMethod], + properties: List[Property], + parent: str = '', + ): + self.template = template + self.is_virtual = is_virtual + self.name = name + if parent_class: + self.parent_class = Typename.from_parse_result(parent_class) + else: + self.parent_class = '' + + self.ctors = ctors + self.methods = methods + self.static_methods = static_methods + self.properties = properties + self.parent = parent + # Make sure ctors' names and class name are the same. + for ctor in self.ctors: + if ctor.name != self.name: + raise ValueError("Error in constructor name! {} != {}".format( + ctor.name, self.name)) + + for ctor in self.ctors: + ctor.parent = self + for method in self.methods: + method.parent = self + for static_method in self.static_methods: + static_method.parent = self + for _property in self.properties: + _property.parent = self + + def namespaces(self) -> list: + """Get the namespaces which this class is nested under as a list.""" + return collect_namespaces(self) + + def __repr__(self): + return "Class: {self.name}".format(self=self) diff --git a/gtwrap/interface_parser/declaration.py b/gtwrap/interface_parser/declaration.py new file mode 100644 index 000000000..ad0b9d8d9 --- /dev/null +++ b/gtwrap/interface_parser/declaration.py @@ -0,0 +1,60 @@ +""" +GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Classes and rules for declarations such as includes and forward declarations. + +Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellaert +""" + +from pyparsing import CharsNotIn, Optional + +from .tokens import (CLASS, COLON, INCLUDE, LOPBRACK, ROPBRACK, SEMI_COLON, + VIRTUAL) +from .type import Typename + + +class Include: + """ + Rule to parse #include directives. + """ + rule = (INCLUDE + LOPBRACK + CharsNotIn('>')("header") + + ROPBRACK).setParseAction(lambda t: Include(t.header)) + + def __init__(self, header: CharsNotIn, parent: str = ''): + self.header = header + self.parent = parent + + def __repr__(self) -> str: + return "#include <{}>".format(self.header) + + +class ForwardDeclaration: + """ + Rule to parse forward declarations in the interface file. + """ + rule = (Optional(VIRTUAL("is_virtual")) + CLASS + Typename.rule("name") + + Optional(COLON + Typename.rule("parent_type")) + + SEMI_COLON).setParseAction(lambda t: ForwardDeclaration( + t.name, t.parent_type, t.is_virtual)) + + def __init__(self, + name: Typename, + parent_type: str, + is_virtual: str, + parent: str = ''): + self.name = name + if parent_type: + self.parent_type = Typename.from_parse_result(parent_type) + else: + self.parent_type = '' + + self.is_virtual = is_virtual + self.parent = parent + + def __repr__(self) -> str: + return "ForwardDeclaration: {} {}({})".format(self.is_virtual, + self.name, self.parent) diff --git a/gtwrap/interface_parser/function.py b/gtwrap/interface_parser/function.py new file mode 100644 index 000000000..453577e58 --- /dev/null +++ b/gtwrap/interface_parser/function.py @@ -0,0 +1,166 @@ +""" +GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Parser classes and rules for parsing C++ functions. + +Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellaert +""" + +from typing import List, Union + +from pyparsing import Optional, ParseResults, delimitedList + +from .template import Template +from .tokens import (COMMA, IDENT, LOPBRACK, LPAREN, PAIR, ROPBRACK, RPAREN, + SEMI_COLON) +from .type import Type + + +class Argument: + """ + The type and name of a function/method argument. + + E.g. + ``` + void sayHello(/*`s` is the method argument with type `const string&`*/ const string& s); + ``` + """ + rule = (Type.rule("ctype") + + IDENT("name")).setParseAction(lambda t: Argument(t.ctype, t.name)) + + def __init__(self, ctype: Type, name: str): + self.ctype = ctype + self.name = name + self.parent: Union[ArgumentList, None] = None + + def __repr__(self) -> str: + return '{} {}'.format(self.ctype.__repr__(), self.name) + + +class ArgumentList: + """ + List of Argument objects for all arguments in a function. + """ + rule = Optional(delimitedList(Argument.rule)("args_list")).setParseAction( + lambda t: ArgumentList.from_parse_result(t.args_list)) + + def __init__(self, args_list: List[Argument]): + self.args_list = args_list + for arg in args_list: + arg.parent = self + # The parent object which contains the argument list + # E.g. Method, StaticMethod, Template, Constructor, GlobalFunction + self.parent = None + + @staticmethod + def from_parse_result(parse_result: ParseResults): + """Return the result of parsing.""" + if parse_result: + return ArgumentList(parse_result.asList()) + else: + return ArgumentList([]) + + def __repr__(self) -> str: + return self.args_list.__repr__() + + def __len__(self) -> int: + return len(self.args_list) + + def args_names(self) -> List[str]: + """Return a list of the names of all the arguments.""" + return [arg.name for arg in self.args_list] + + def to_cpp(self, use_boost: bool) -> List[str]: + """Generate the C++ code for wrapping.""" + return [arg.ctype.to_cpp(use_boost) for arg in self.args_list] + + +class ReturnType: + """ + Rule to parse the return type. + + The return type can either be a single type or a pair such as . + """ + _pair = ( + PAIR.suppress() # + + LOPBRACK # + + Type.rule("type1") # + + COMMA # + + Type.rule("type2") # + + ROPBRACK # + ) + rule = (_pair ^ Type.rule("type1")).setParseAction( # BR + lambda t: ReturnType(t.type1, t.type2)) + + def __init__(self, type1: Type, type2: Type): + self.type1 = type1 + self.type2 = type2 + # The parent object which contains the return type + # E.g. Method, StaticMethod, Template, Constructor, GlobalFunction + self.parent = None + + def is_void(self) -> bool: + """ + Check if the return type is void. + """ + return self.type1.typename.name == "void" and not self.type2 + + def __repr__(self) -> str: + return "{}{}".format( + self.type1, (', ' + self.type2.__repr__()) if self.type2 else '') + + def to_cpp(self, use_boost: bool) -> str: + """ + Generate the C++ code for wrapping. + + If there are two return types, we return a pair<>, + otherwise we return the regular return type. + """ + if self.type2: + return "std::pair<{type1},{type2}>".format( + type1=self.type1.to_cpp(use_boost), + type2=self.type2.to_cpp(use_boost)) + else: + return self.type1.to_cpp(use_boost) + + +class GlobalFunction: + """ + Rule to parse functions defined in the global scope. + """ + rule = ( + Optional(Template.rule("template")) + ReturnType.rule("return_type") # + + IDENT("name") # + + LPAREN # + + ArgumentList.rule("args_list") # + + RPAREN # + + SEMI_COLON # + ).setParseAction(lambda t: GlobalFunction(t.name, t.return_type, t. + args_list, t.template)) + + def __init__(self, + name: str, + return_type: ReturnType, + args_list: ArgumentList, + template: Template, + parent: str = ''): + self.name = name + self.return_type = return_type + self.args = args_list + self.template = template + + self.parent = parent + self.return_type.parent = self + self.args.parent = self + + def __repr__(self) -> str: + return "GlobalFunction: {}{}({})".format(self.return_type, self.name, + self.args) + + def to_cpp(self) -> str: + """Generate the C++ code for wrapping.""" + return self.name diff --git a/gtwrap/interface_parser/module.py b/gtwrap/interface_parser/module.py new file mode 100644 index 000000000..5619c1f56 --- /dev/null +++ b/gtwrap/interface_parser/module.py @@ -0,0 +1,55 @@ +""" +GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Rules and classes for parsing a module. + +Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellaert +""" + +# pylint: disable=unnecessary-lambda, unused-import, expression-not-assigned, no-else-return, protected-access, too-few-public-methods, too-many-arguments + +import sys + +import pyparsing # type: ignore +from pyparsing import (ParserElement, ParseResults, ZeroOrMore, + cppStyleComment, stringEnd) + +from .classes import Class +from .declaration import ForwardDeclaration, Include +from .function import GlobalFunction +from .namespace import Namespace +from .template import TypedefTemplateInstantiation + + +class Module: + """ + Module is just a global namespace. + + E.g. + ``` + namespace gtsam { + ... + } + ``` + """ + + rule = ( + ZeroOrMore(ForwardDeclaration.rule # + ^ Include.rule # + ^ Class.rule # + ^ TypedefTemplateInstantiation.rule # + ^ GlobalFunction.rule # + ^ Namespace.rule # + ).setParseAction(lambda t: Namespace('', t.asList())) + + stringEnd) + + rule.ignore(cppStyleComment) + + @staticmethod + def parseString(s: str) -> ParseResults: + """Parse the source string and apply the rules.""" + return Module.rule.parseString(s)[0] diff --git a/gtwrap/interface_parser/namespace.py b/gtwrap/interface_parser/namespace.py new file mode 100644 index 000000000..da505d5f9 --- /dev/null +++ b/gtwrap/interface_parser/namespace.py @@ -0,0 +1,128 @@ +""" +GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Classes and rules to parse a namespace. + +Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellaert +""" + +# pylint: disable=unnecessary-lambda, expression-not-assigned + +from typing import List, Union + +from pyparsing import Forward, ParseResults, ZeroOrMore + +from .classes import Class, collect_namespaces +from .declaration import ForwardDeclaration, Include +from .function import GlobalFunction +from .template import TypedefTemplateInstantiation +from .tokens import IDENT, LBRACE, NAMESPACE, RBRACE +from .type import Typename + + +def find_sub_namespace(namespace: "Namespace", + str_namespaces: List["Namespace"]) -> list: + """ + Get the namespaces nested under `namespace`, filtered by a list of namespace strings. + + Args: + namespace: The top-level namespace under which to find sub-namespaces. + str_namespaces: The list of namespace strings to filter against. + """ + if not str_namespaces: + return [namespace] + + sub_namespaces = (ns for ns in namespace.content + if isinstance(ns, Namespace)) + + found_namespaces = [ + ns for ns in sub_namespaces if ns.name == str_namespaces[0] + ] + if not found_namespaces: + return [] + + res = [] + for found_namespace in found_namespaces: + ns = find_sub_namespace(found_namespace, str_namespaces[1:]) + if ns: + res += ns + return res + + +class Namespace: + """Rule for parsing a namespace in the interface file.""" + + rule = Forward() + rule << ( + NAMESPACE # + + IDENT("name") # + + LBRACE # + + ZeroOrMore( # BR + ForwardDeclaration.rule # + ^ Include.rule # + ^ Class.rule # + ^ TypedefTemplateInstantiation.rule # + ^ GlobalFunction.rule # + ^ rule # + )("content") # BR + + RBRACE # + ).setParseAction(lambda t: Namespace.from_parse_result(t)) + + def __init__(self, name: str, content: ZeroOrMore, parent=''): + self.name = name + self.content = content + self.parent = parent + for child in self.content: + child.parent = self + + @staticmethod + def from_parse_result(t: ParseResults): + """Return the result of parsing.""" + if t.content: + content = t.content.asList() + else: + content = [] + return Namespace(t.name, content) + + def find_class_or_function( + self, typename: Typename) -> Union[Class, GlobalFunction]: + """ + Find the Class or GlobalFunction object given its typename. + We have to traverse the tree of namespaces. + """ + found_namespaces = find_sub_namespace(self, typename.namespaces) + res = [] + for namespace in found_namespaces: + classes_and_funcs = (c for c in namespace.content + if isinstance(c, (Class, GlobalFunction))) + res += [c for c in classes_and_funcs if c.name == typename.name] + if not res: + raise ValueError("Cannot find class {} in module!".format( + typename.name)) + elif len(res) > 1: + raise ValueError( + "Found more than one classes {} in module!".format( + typename.name)) + else: + return res[0] + + def top_level(self) -> "Namespace": + """Return the top leve namespace.""" + if self.name == '' or self.parent == '': + return self + else: + return self.parent.top_level() + + def __repr__(self) -> str: + return "Namespace: {}\n\t{}".format(self.name, self.content) + + def full_namespaces(self) -> List["Namespace"]: + """Get the full namespace list.""" + ancestors = collect_namespaces(self) + if self.name: + ancestors.append(self.name) + return ancestors diff --git a/gtwrap/interface_parser/template.py b/gtwrap/interface_parser/template.py new file mode 100644 index 000000000..99e929d39 --- /dev/null +++ b/gtwrap/interface_parser/template.py @@ -0,0 +1,90 @@ +""" +GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Classes and rules for parsing C++ templates and typedefs for template instantiations. + +Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellaert +""" + +from typing import List + +from pyparsing import Optional, ParseResults, delimitedList + +from .tokens import (EQUAL, IDENT, LBRACE, LOPBRACK, RBRACE, ROPBRACK, + SEMI_COLON, TEMPLATE, TYPEDEF) +from .type import Typename + + +class Template: + """ + Rule to parse templated values in the interface file. + + E.g. + template // this is the Template. + class Camera { ... }; + """ + class TypenameAndInstantiations: + """ + Rule to parse the template parameters. + + template // POSE is the Instantiation. + """ + rule = ( + IDENT("typename") # + + Optional( # + EQUAL # + + LBRACE # + + ((delimitedList(Typename.rule)("instantiations"))) # + + RBRACE # + )).setParseAction(lambda t: Template.TypenameAndInstantiations( + t.typename, t.instantiations)) + + def __init__(self, typename: str, instantiations: ParseResults): + self.typename = typename + + if instantiations: + self.instantiations = instantiations.asList() + else: + self.instantiations = [] + + rule = ( # BR + TEMPLATE # + + LOPBRACK # + + delimitedList(TypenameAndInstantiations.rule)( + "typename_and_instantiations_list") # + + ROPBRACK # BR + ).setParseAction( + lambda t: Template(t.typename_and_instantiations_list.asList())) + + def __init__( + self, + typename_and_instantiations_list: List[TypenameAndInstantiations]): + ti_list = typename_and_instantiations_list + self.typenames = [ti.typename for ti in ti_list] + self.instantiations = [ti.instantiations for ti in ti_list] + + def __repr__(self) -> str: + return "<{0}>".format(", ".join(self.typenames)) + + +class TypedefTemplateInstantiation: + """ + Rule for parsing typedefs (with templates) within the interface file. + + E.g. + ``` + typedef SuperComplexName EasierName; + ``` + """ + rule = (TYPEDEF + Typename.rule("typename") + IDENT("new_name") + + SEMI_COLON).setParseAction(lambda t: TypedefTemplateInstantiation( + Typename.from_parse_result(t.typename), t.new_name)) + + def __init__(self, typename: Typename, new_name: str, parent: str = ''): + self.typename = typename + self.new_name = new_name + self.parent = parent diff --git a/gtwrap/interface_parser/tokens.py b/gtwrap/interface_parser/tokens.py new file mode 100644 index 000000000..6653812c4 --- /dev/null +++ b/gtwrap/interface_parser/tokens.py @@ -0,0 +1,48 @@ +""" +GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +All the token definitions. + +Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellaert +""" + +from pyparsing import Keyword, Literal, Suppress, Word, alphanums, alphas, nums + +# rule for identifiers (e.g. variable names) +IDENT = Word(alphas + '_', alphanums + '_') ^ Word(nums) + +RAW_POINTER, SHARED_POINTER, REF = map(Literal, "@*&") + +LPAREN, RPAREN, LBRACE, RBRACE, COLON, SEMI_COLON = map(Suppress, "(){}:;") +LOPBRACK, ROPBRACK, COMMA, EQUAL = map(Suppress, "<>,=") +CONST, VIRTUAL, CLASS, STATIC, PAIR, TEMPLATE, TYPEDEF, INCLUDE = map( + Keyword, + [ + "const", + "virtual", + "class", + "static", + "pair", + "template", + "typedef", + "#include", + ], +) +NAMESPACE = Keyword("namespace") +BASIS_TYPES = map( + Keyword, + [ + "void", + "bool", + "unsigned char", + "char", + "int", + "size_t", + "double", + "float", + ], +) diff --git a/gtwrap/interface_parser/type.py b/gtwrap/interface_parser/type.py new file mode 100644 index 000000000..4578b9f37 --- /dev/null +++ b/gtwrap/interface_parser/type.py @@ -0,0 +1,232 @@ +""" +GTSAM Copyright 2010-2020, Georgia Tech Research Corporation, +Atlanta, Georgia 30332-0415 +All Rights Reserved + +See LICENSE for the license information + +Define the parser rules and classes for various C++ types. + +Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellaert +""" + +# pylint: disable=unnecessary-lambda, expression-not-assigned + +from typing import Iterable, Union + +from pyparsing import Forward, Optional, Or, ParseResults, delimitedList + +from .tokens import (BASIS_TYPES, CONST, IDENT, LOPBRACK, RAW_POINTER, REF, + ROPBRACK, SHARED_POINTER) + + +class Typename: + """ + Generic type which can be either a basic type or a class type, + similar to C++'s `typename` aka a qualified dependent type. + Contains type name with full namespace and template arguments. + + E.g. + ``` + gtsam::PinholeCamera + ``` + + will give the name as `PinholeCamera`, namespace as `gtsam`, + and template instantiations as `[gtsam::Cal3S2]`. + + Args: + namespaces_and_name: A list representing the namespaces of the type + with the type being the last element. + instantiations: Template parameters to the type. + """ + + namespaces_name_rule = delimitedList(IDENT, "::") + instantiation_name_rule = delimitedList(IDENT, "::") + rule = Forward() + rule << ( + namespaces_name_rule("namespaces_and_name") # + + Optional( + (LOPBRACK + delimitedList(rule, ",") + ("instantiations") + ROPBRACK))).setParseAction( + lambda t: Typename(t.namespaces_and_name, t.instantiations)) + + def __init__(self, + namespaces_and_name: ParseResults, + instantiations: Union[tuple, list, str, ParseResults] = ()): + self.name = namespaces_and_name[ + -1] # the name is the last element in this list + self.namespaces = namespaces_and_name[:-1] + + if instantiations: + if isinstance(instantiations, Iterable): + self.instantiations = instantiations # type: ignore + else: + self.instantiations = instantiations.asList() + else: + self.instantiations = [] + + if self.name in ["Matrix", "Vector"] and not self.namespaces: + self.namespaces = ["gtsam"] + + @staticmethod + def from_parse_result(parse_result: Union[str, list]): + """Unpack the parsed result to get the Typename instance.""" + return parse_result[0] + + def __repr__(self) -> str: + return self.to_cpp() + + def instantiated_name(self) -> str: + """Get the instantiated name of the type.""" + res = self.name + for instantiation in self.instantiations: + res += instantiation.instantiated_name() + return res + + def to_cpp(self) -> str: + """Generate the C++ code for wrapping.""" + idx = 1 if self.namespaces and not self.namespaces[0] else 0 + if self.instantiations: + cpp_name = self.name + "<{}>".format(", ".join( + [inst.to_cpp() for inst in self.instantiations])) + else: + cpp_name = self.name + return '{}{}{}'.format( + "::".join(self.namespaces[idx:]), + "::" if self.namespaces[idx:] else "", + cpp_name, + ) + + def __eq__(self, other) -> bool: + if isinstance(other, Typename): + return str(self) == str(other) + else: + return False + + def __ne__(self, other) -> bool: + res = self.__eq__(other) + return not res + + +class QualifiedType: + """Type with qualifiers, such as `const`.""" + + rule = ( + Typename.rule("typename") # + + Optional( + SHARED_POINTER("is_shared_ptr") | RAW_POINTER("is_ptr") + | REF("is_ref"))).setParseAction(lambda t: QualifiedType(t)) + + def __init__(self, t: ParseResults): + self.typename = Typename.from_parse_result(t.typename) + self.is_shared_ptr = t.is_shared_ptr + self.is_ptr = t.is_ptr + self.is_ref = t.is_ref + + +class BasisType: + """ + Basis types are the built-in types in C++ such as double, int, char, etc. + + When using templates, the basis type will take on the same form as the template. + + E.g. + ``` + template + void func(const T& x); + ``` + + will give + + ``` + m_.def("CoolFunctionDoubleDouble",[](const double& s) { + return wrap_example::CoolFunction(s); + }, py::arg("s")); + ``` + """ + + rule = ( + Or(BASIS_TYPES)("typename") # + + Optional( + SHARED_POINTER("is_shared_ptr") | RAW_POINTER("is_ptr") + | REF("is_ref")) # + ).setParseAction(lambda t: BasisType(t)) + + def __init__(self, t: ParseResults): + self.typename = Typename([t.typename]) + self.is_ptr = t.is_ptr + self.is_shared_ptr = t.is_shared_ptr + self.is_ref = t.is_ref + + +class Type: + """The type value that is parsed, e.g. void, string, size_t.""" + rule = ( + Optional(CONST("is_const")) # + + (BasisType.rule("basis") | QualifiedType.rule("qualified")) # BR + ).setParseAction(lambda t: Type.from_parse_result(t)) + + def __init__(self, typename: Typename, is_const: str, is_shared_ptr: str, + is_ptr: str, is_ref: str, is_basis: bool): + self.typename = typename + self.is_const = is_const + self.is_shared_ptr = is_shared_ptr + self.is_ptr = is_ptr + self.is_ref = is_ref + self.is_basis = is_basis + + @staticmethod + def from_parse_result(t: ParseResults): + """Return the resulting Type from parsing the source.""" + if t.basis: + return Type( + typename=t.basis.typename, + is_const=t.is_const, + is_shared_ptr=t.basis.is_shared_ptr, + is_ptr=t.basis.is_ptr, + is_ref=t.basis.is_ref, + is_basis=True, + ) + elif t.qualified: + return Type( + typename=t.qualified.typename, + is_const=t.is_const, + is_shared_ptr=t.qualified.is_shared_ptr, + is_ptr=t.qualified.is_ptr, + is_ref=t.qualified.is_ref, + is_basis=False, + ) + else: + raise ValueError("Parse result is not a Type") + + def __repr__(self) -> str: + return "{self.typename} " \ + "{self.is_const}{self.is_shared_ptr}{self.is_ptr}{self.is_ref}".format( + self=self) + + def to_cpp(self, use_boost: bool) -> str: + """ + Generate the C++ code for wrapping. + + Treat all pointers as "const shared_ptr&" + Treat Matrix and Vector as "const Matrix&" and "const Vector&" resp. + """ + shared_ptr_ns = "boost" if use_boost else "std" + + if self.is_shared_ptr: + # always pass by reference: https://stackoverflow.com/a/8741626/1236990 + typename = "{ns}::shared_ptr<{typename}>&".format( + ns=shared_ptr_ns, typename=self.typename.to_cpp()) + elif self.is_ptr: + typename = "{typename}*".format(typename=self.typename.to_cpp()) + elif self.is_ref or self.typename.name in ["Matrix", "Vector"]: + typename = typename = "{typename}&".format( + typename=self.typename.to_cpp()) + else: + typename = self.typename.to_cpp() + + return ("{const}{typename}".format( + const="const " if + (self.is_const + or self.typename.name in ["Matrix", "Vector"]) else "", + typename=typename)) diff --git a/gtwrap/matlab_wrapper.py b/gtwrap/matlab_wrapper.py index 439a61fb4..520b76284 100755 --- a/gtwrap/matlab_wrapper.py +++ b/gtwrap/matlab_wrapper.py @@ -76,6 +76,10 @@ class MatlabWrapper(object): # Files and their content content: List[str] = [] + # Ensure the template file is always picked up from the correct directory. + dir_path = osp.dirname(osp.realpath(__file__)) + wrapper_file_template = osp.join(dir_path, "matlab_wrapper.tpl") + def __init__(self, module, module_name, @@ -664,10 +668,8 @@ class MatlabWrapper(object): """Generate the C++ file for the wrapper.""" file_name = self._wrapper_name() + '.cpp' - wrapper_file = textwrap.dedent('''\ - # include - # include - ''') + with open(self.wrapper_file_template) as f: + wrapper_file = f.read() return file_name, wrapper_file diff --git a/gtwrap/pybind_wrapper.py b/gtwrap/pybind_wrapper.py index 3d82298da..c275e575d 100755 --- a/gtwrap/pybind_wrapper.py +++ b/gtwrap/pybind_wrapper.py @@ -13,7 +13,6 @@ Author: Duy Nguyen Ta, Fan Jiang, Matthew Sklar, Varun Agrawal, and Frank Dellae # pylint: disable=too-many-arguments, too-many-instance-attributes, no-self-use, no-else-return, too-many-arguments, unused-format-string-argument, line-too-long import re -import textwrap import gtwrap.interface_parser as parser import gtwrap.template_instantiator as instantiator diff --git a/templates/matlab_wrapper.tpl.in b/templates/matlab_wrapper.tpl.in new file mode 100644 index 000000000..2885e9244 --- /dev/null +++ b/templates/matlab_wrapper.tpl.in @@ -0,0 +1,2 @@ +# include <${GTWRAP_INCLUDE_NAME}/matlab.h> +# include diff --git a/tests/test_interface_parser.py b/tests/test_interface_parser.py index c43802b2a..fad846365 100644 --- a/tests/test_interface_parser.py +++ b/tests/test_interface_parser.py @@ -16,16 +16,13 @@ import os import sys import unittest -from pyparsing import ParseException - sys.path.append(os.path.dirname(os.path.dirname(os.path.abspath(__file__)))) from gtwrap.interface_parser import (ArgumentList, Class, Constructor, ForwardDeclaration, GlobalFunction, Include, Method, Module, Namespace, ReturnType, StaticMethod, Type, - TypedefTemplateInstantiation, Typename, - find_sub_namespace) + TypedefTemplateInstantiation, Typename) class TestInterfaceParser(unittest.TestCase): @@ -35,7 +32,8 @@ class TestInterfaceParser(unittest.TestCase): typename = Typename.rule.parseString("size_t")[0] self.assertEqual("size_t", typename.name) - typename = Typename.rule.parseString("gtsam::PinholeCamera")[0] + typename = Typename.rule.parseString( + "gtsam::PinholeCamera")[0] self.assertEqual("PinholeCamera", typename.name) self.assertEqual(["gtsam"], typename.namespaces) self.assertEqual("Cal3S2", typename.instantiations[0].name) diff --git a/tests/test_pybind_wrapper.py b/tests/test_pybind_wrapper.py index 7896ab28b..e2fdbe3bb 100644 --- a/tests/test_pybind_wrapper.py +++ b/tests/test_pybind_wrapper.py @@ -13,7 +13,9 @@ import sys import unittest sys.path.append(os.path.dirname(os.path.dirname(os.path.abspath(__file__)))) -sys.path.append(os.path.normpath(os.path.abspath(os.path.join(__file__, '../../../build/wrap')))) +sys.path.append( + os.path.normpath( + os.path.abspath(os.path.join(__file__, '../../../build/wrap')))) import gtwrap.interface_parser as parser import gtwrap.template_instantiator as instantiator @@ -38,14 +40,12 @@ class TestWrap(unittest.TestCase): module_template = template_file.read() # Create Pybind wrapper instance - wrapper = PybindWrapper( - module=module, - module_name=module_name, - use_boost=False, - top_module_namespaces=[''], - ignore_classes=[''], - module_template=module_template - ) + wrapper = PybindWrapper(module=module, + module_name=module_name, + use_boost=False, + top_module_namespaces=[''], + ignore_classes=[''], + module_template=module_template) cc_content = wrapper.wrap() @@ -70,7 +70,8 @@ class TestWrap(unittest.TestCase): output = self.wrap_content(content, 'geometry_py', 'actual-python') - expected = path.join(self.TEST_DIR, 'expected-python/geometry_pybind.cpp') + expected = path.join(self.TEST_DIR, + 'expected-python/geometry_pybind.cpp') success = filecmp.cmp(output, expected) if not success: @@ -86,14 +87,17 @@ class TestWrap(unittest.TestCase): with open(os.path.join(self.TEST_DIR, 'testNamespaces.h'), 'r') as f: content = f.read() - output = self.wrap_content(content, 'testNamespaces_py', 'actual-python') + output = self.wrap_content(content, 'testNamespaces_py', + 'actual-python') - expected = path.join(self.TEST_DIR, 'expected-python/testNamespaces_py.cpp') + expected = path.join(self.TEST_DIR, + 'expected-python/testNamespaces_py.cpp') success = filecmp.cmp(output, expected) if not success: os.system("diff {} {}".format(output, expected)) self.assertTrue(success) + if __name__ == '__main__': unittest.main() From 30c84eabe4e0fdb47265e9fcc51a0f8b9ff51e6a Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Wed, 24 Mar 2021 16:58:44 -0400 Subject: [PATCH 10/21] added CMake variable to set the matlab.h include --- CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/CMakeLists.txt b/CMakeLists.txt index 6fc456609..2fdadc68a 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -82,6 +82,8 @@ if(GTSAM_BUILD_PYTHON OR GTSAM_INSTALL_MATLAB_TOOLBOX) # Need to set this for the wrap package so we don't use the default value. set(WRAP_PYTHON_VERSION ${GTSAM_PYTHON_VERSION} CACHE STRING "The Python version to use for wrapping") + # Set the include directory for matlab.h + set(GTWRAP_INCLUDE_NAME "wrap") add_subdirectory(wrap) list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/wrap/cmake") endif() From a62a986fbb4d60ab693bf9278bfe60850ef42ff8 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 25 Mar 2021 00:49:51 -0400 Subject: [PATCH 11/21] Squashed 'wrap/' changes from 548e61b1f..29628426d 29628426d Merge pull request #59 from borglab/fixes a95429ea0 Merge pull request #56 from borglab/fix/this-instantiation 3e22d6516 more documenatation and some formatting 526301499 updated the test to test for non-templated This cdb75f36f Merge branch 'master' into fix/this-instantiation 0f5ae3b7f moved example pybind template to templates directory d55f5db38 remove extra whitespace 21891ad3d skip tests until we figure out what's going on 2ea6307c3 better way of handling the matlab includes in the matlab wrapper d0f8a392c Merge pull request #55 from borglab/feature/refactor3 57d47cbd9 create directories to store generated output 4788a1e37 fixed This instantiation 61d2cbfc4 add namespace test to matlab wrapper ec39023e6 added more, smaller tests for Python wrapper 19c35b857 test for matlab class inheritance and some clean up 06ca5da13 test for matlab functions cb05d7379 minor clean up and separate tests for geometry and class 8d8145cc4 break down test interface file into smaller files that can be easily debugged 97328f057 restructured test files and added dedicated fixtures directory git-subtree-dir: wrap git-subtree-split: 29628426d2c1a7bb728e40307c0f25cb468cd1bc --- gtwrap/matlab_wrapper.py | 12 +- gtwrap/template_instantiator.py | 183 +- templates/matlab_wrapper.tpl.in | 4 +- .../pybind_wrapper.tpl.example | 0 tests/.gitignore | 4 +- tests/expected-matlab/PrimitiveRef.m | 54 - tests/expected-matlab/geometry_wrapper.cpp | 1590 ----------------- tests/expected-python/geometry_pybind.cpp | 157 -- .../matlab}/+gtsam/Point2.m | 0 .../matlab}/+gtsam/Point3.m | 0 tests/expected/matlab/+ns1/ClassA.m | 36 + tests/expected/matlab/+ns1/ClassB.m | 36 + .../matlab/+ns1}/aGlobalFunction.m | 2 +- tests/expected/matlab/+ns2/+ns3/ClassB.m | 36 + tests/expected/matlab/+ns2/ClassA.m | 89 + tests/expected/matlab/+ns2/ClassC.m | 36 + tests/expected/matlab/+ns2/aGlobalFunction.m | 6 + .../matlab/+ns2/overloadedGlobalFunction.m | 8 + tests/expected/matlab/ClassD.m | 36 + tests/expected/matlab/FunDouble.m | 62 + tests/expected/matlab/FunRange.m | 67 + ...MultiTemplatedFunctionDoubleSize_tDouble.m | 6 + ...MultiTemplatedFunctionStringSize_tDouble.m | 6 + .../matlab}/MultipleTemplatesIntDouble.m | 4 +- .../matlab}/MultipleTemplatesIntFloat.m | 4 +- .../matlab}/MyBase.m | 6 +- .../matlab}/MyFactorPosePoint2.m | 6 +- .../matlab}/MyTemplateMatrix.m | 32 +- .../matlab}/MyTemplatePoint2.m | 32 +- .../matlab}/MyVector12.m | 6 +- .../matlab}/MyVector3.m | 6 +- .../matlab/PrimitiveRefDouble.m} | 26 +- tests/expected/matlab/TemplatedFunctionRot3.m | 6 + .../matlab}/Test.m | 48 +- tests/expected/matlab/aGlobalFunction.m | 6 + tests/expected/matlab/class_wrapper.cpp | 791 ++++++++ tests/expected/matlab/functions_wrapper.cpp | 250 +++ tests/expected/matlab/geometry_wrapper.cpp | 480 +++++ tests/expected/matlab/inheritance_wrapper.cpp | 681 +++++++ .../matlab}/load2D.m | 6 +- tests/expected/matlab/namespaces_wrapper.cpp | 581 ++++++ .../matlab}/overloadedGlobalFunction.m | 4 +- tests/expected/python/class_pybind.cpp | 86 + tests/expected/python/functions_pybind.cpp | 37 + tests/expected/python/geometry_pybind.cpp | 67 + tests/expected/python/inheritance_pybind.cpp | 60 + .../python/namespaces_pybind.cpp} | 4 +- .../xml/JacobianFactorQ_8h.xml | 0 .../xml/NonlinearFactor_8h.xml | 0 .../xml/classgtsam_1_1JacobianFactorQ.xml | 0 .../xml/classgtsam_1_1NoiseModelFactor.xml | 0 .../xml/classgtsam_1_1NoiseModelFactor1.xml | 0 .../xml/classgtsam_1_1NoiseModelFactor2.xml | 0 .../xml/classgtsam_1_1NoiseModelFactor3.xml | 0 .../xml/classgtsam_1_1NoiseModelFactor4.xml | 0 .../xml/classgtsam_1_1NoiseModelFactor5.xml | 0 .../xml/classgtsam_1_1NoiseModelFactor6.xml | 0 .../xml/classgtsam_1_1NonlinearFactor.xml | 0 .../xml/combine.xslt | 0 .../xml/compound.xsd | 0 .../xml/deprecated.xml | 0 .../dir_59425e443f801f1f2fd8bbe4959a3ccf.xml | 0 .../dir_e4787312bc569bb879bb1171628269de.xml | 0 .../xml/index.xml | 0 .../xml/index.xsd | 0 .../xml/namespacegtsam.xml | 0 ...obianFactorQ_3_01D_00_01ZDim_01_4_01_4.xml | 0 ...sam_1_1traits_3_01NonlinearFactor_01_4.xml | 0 tests/fixtures/class.i | 101 ++ tests/fixtures/functions.i | 28 + tests/fixtures/geometry.i | 49 + tests/fixtures/inheritance.i | 24 + .../namespaces.i} | 0 tests/geometry.h | 185 -- tests/test_docs.py | 11 +- tests/test_matlab_wrapper.py | 198 +- tests/test_pybind_wrapper.py | 100 +- 77 files changed, 4128 insertions(+), 2227 deletions(-) rename pybind_wrapper.tpl.example => templates/pybind_wrapper.tpl.example (100%) delete mode 100644 tests/expected-matlab/PrimitiveRef.m delete mode 100644 tests/expected-matlab/geometry_wrapper.cpp delete mode 100644 tests/expected-python/geometry_pybind.cpp rename tests/{expected-matlab => expected/matlab}/+gtsam/Point2.m (100%) rename tests/{expected-matlab => expected/matlab}/+gtsam/Point3.m (100%) create mode 100644 tests/expected/matlab/+ns1/ClassA.m create mode 100644 tests/expected/matlab/+ns1/ClassB.m rename tests/{expected-matlab => expected/matlab/+ns1}/aGlobalFunction.m (75%) create mode 100644 tests/expected/matlab/+ns2/+ns3/ClassB.m create mode 100644 tests/expected/matlab/+ns2/ClassA.m create mode 100644 tests/expected/matlab/+ns2/ClassC.m create mode 100644 tests/expected/matlab/+ns2/aGlobalFunction.m create mode 100644 tests/expected/matlab/+ns2/overloadedGlobalFunction.m create mode 100644 tests/expected/matlab/ClassD.m create mode 100644 tests/expected/matlab/FunDouble.m create mode 100644 tests/expected/matlab/FunRange.m create mode 100644 tests/expected/matlab/MultiTemplatedFunctionDoubleSize_tDouble.m create mode 100644 tests/expected/matlab/MultiTemplatedFunctionStringSize_tDouble.m rename tests/{expected-matlab => expected/matlab}/MultipleTemplatesIntDouble.m (88%) rename tests/{expected-matlab => expected/matlab}/MultipleTemplatesIntFloat.m (88%) rename tests/{expected-matlab => expected/matlab}/MyBase.m (84%) rename tests/{expected-matlab => expected/matlab}/MyFactorPosePoint2.m (84%) rename tests/{expected-matlab => expected/matlab}/MyTemplateMatrix.m (86%) rename tests/{expected-matlab => expected/matlab}/MyTemplatePoint2.m (86%) rename tests/{expected-matlab => expected/matlab}/MyVector12.m (86%) rename tests/{expected-matlab => expected/matlab}/MyVector3.m (86%) rename tests/{expected-matlab/PrimitiveRefdouble.m => expected/matlab/PrimitiveRefDouble.m} (66%) create mode 100644 tests/expected/matlab/TemplatedFunctionRot3.m rename tests/{expected-matlab => expected/matlab}/Test.m (85%) create mode 100644 tests/expected/matlab/aGlobalFunction.m create mode 100644 tests/expected/matlab/class_wrapper.cpp create mode 100644 tests/expected/matlab/functions_wrapper.cpp create mode 100644 tests/expected/matlab/geometry_wrapper.cpp create mode 100644 tests/expected/matlab/inheritance_wrapper.cpp rename tests/{expected-matlab => expected/matlab}/load2D.m (73%) create mode 100644 tests/expected/matlab/namespaces_wrapper.cpp rename tests/{expected-matlab => expected/matlab}/overloadedGlobalFunction.m (73%) create mode 100644 tests/expected/python/class_pybind.cpp create mode 100644 tests/expected/python/functions_pybind.cpp create mode 100644 tests/expected/python/geometry_pybind.cpp create mode 100644 tests/expected/python/inheritance_pybind.cpp rename tests/{expected-python/testNamespaces_py.cpp => expected/python/namespaces_pybind.cpp} (95%) rename tests/{expected-xml-generation => expected}/xml/JacobianFactorQ_8h.xml (100%) rename tests/{expected-xml-generation => expected}/xml/NonlinearFactor_8h.xml (100%) rename tests/{expected-xml-generation => expected}/xml/classgtsam_1_1JacobianFactorQ.xml (100%) rename tests/{expected-xml-generation => expected}/xml/classgtsam_1_1NoiseModelFactor.xml (100%) rename tests/{expected-xml-generation => expected}/xml/classgtsam_1_1NoiseModelFactor1.xml (100%) rename tests/{expected-xml-generation => expected}/xml/classgtsam_1_1NoiseModelFactor2.xml (100%) rename tests/{expected-xml-generation => expected}/xml/classgtsam_1_1NoiseModelFactor3.xml (100%) rename tests/{expected-xml-generation => expected}/xml/classgtsam_1_1NoiseModelFactor4.xml (100%) rename tests/{expected-xml-generation => expected}/xml/classgtsam_1_1NoiseModelFactor5.xml (100%) rename tests/{expected-xml-generation => expected}/xml/classgtsam_1_1NoiseModelFactor6.xml (100%) rename tests/{expected-xml-generation => expected}/xml/classgtsam_1_1NonlinearFactor.xml (100%) rename tests/{expected-xml-generation => expected}/xml/combine.xslt (100%) rename tests/{expected-xml-generation => expected}/xml/compound.xsd (100%) rename tests/{expected-xml-generation => expected}/xml/deprecated.xml (100%) rename tests/{expected-xml-generation => expected}/xml/dir_59425e443f801f1f2fd8bbe4959a3ccf.xml (100%) rename tests/{expected-xml-generation => expected}/xml/dir_e4787312bc569bb879bb1171628269de.xml (100%) rename tests/{expected-xml-generation => expected}/xml/index.xml (100%) rename tests/{expected-xml-generation => expected}/xml/index.xsd (100%) rename tests/{expected-xml-generation => expected}/xml/namespacegtsam.xml (100%) rename tests/{expected-xml-generation => expected}/xml/structgtsam_1_1traits_3_01JacobianFactorQ_3_01D_00_01ZDim_01_4_01_4.xml (100%) rename tests/{expected-xml-generation => expected}/xml/structgtsam_1_1traits_3_01NonlinearFactor_01_4.xml (100%) create mode 100644 tests/fixtures/class.i create mode 100644 tests/fixtures/functions.i create mode 100644 tests/fixtures/geometry.i create mode 100644 tests/fixtures/inheritance.i rename tests/{testNamespaces.h => fixtures/namespaces.i} (100%) delete mode 100644 tests/geometry.h diff --git a/gtwrap/matlab_wrapper.py b/gtwrap/matlab_wrapper.py index 520b76284..0c5a6a4bc 100755 --- a/gtwrap/matlab_wrapper.py +++ b/gtwrap/matlab_wrapper.py @@ -78,7 +78,8 @@ class MatlabWrapper(object): # Ensure the template file is always picked up from the correct directory. dir_path = osp.dirname(osp.realpath(__file__)) - wrapper_file_template = osp.join(dir_path, "matlab_wrapper.tpl") + with open(osp.join(dir_path, "matlab_wrapper.tpl")) as f: + wrapper_file_header = f.read() def __init__(self, module, @@ -668,8 +669,7 @@ class MatlabWrapper(object): """Generate the C++ file for the wrapper.""" file_name = self._wrapper_name() + '.cpp' - with open(self.wrapper_file_template) as f: - wrapper_file = f.read() + wrapper_file = self.wrapper_file_header return file_name, wrapper_file @@ -1630,13 +1630,11 @@ class MatlabWrapper(object): def generate_wrapper(self, namespace): """Generate the c++ wrapper.""" # Includes - wrapper_file = textwrap.dedent('''\ - #include - #include \n + wrapper_file = self.wrapper_file_header + textwrap.dedent(""" #include #include #include \n - ''') + """) assert namespace diff --git a/gtwrap/template_instantiator.py b/gtwrap/template_instantiator.py index 8e918e297..65a1e7227 100644 --- a/gtwrap/template_instantiator.py +++ b/gtwrap/template_instantiator.py @@ -61,6 +61,7 @@ def instantiate_type(ctype: parser.Type, cpp_typename = parser.Typename( namespaces_name, instantiations=instantiated_class.instantiations) + return parser.Type( typename=cpp_typename, is_const=ctype.is_const, @@ -92,15 +93,18 @@ def instantiate_args_list(args_list, template_typenames, instantiations, """ instantiated_args = [] for arg in args_list: - new_type = instantiate_type( - arg.ctype, template_typenames, instantiations, cpp_typename) - instantiated_args.append( - parser.Argument(name=arg.name, ctype=new_type)) + new_type = instantiate_type(arg.ctype, template_typenames, + instantiations, cpp_typename) + instantiated_args.append(parser.Argument(name=arg.name, + ctype=new_type)) return instantiated_args -def instantiate_return_type(return_type, template_typenames, instantiations, - cpp_typename, instantiated_class=None): +def instantiate_return_type(return_type, + template_typenames, + instantiations, + cpp_typename, + instantiated_class=None): """Instantiate the return type.""" new_type1 = instantiate_type(return_type.type1, template_typenames, @@ -135,6 +139,7 @@ def instantiate_name(original_name, instantiations): return "{}{}".format(original_name, "".join(instantiated_names)) + class InstantiatedGlobalFunction(parser.GlobalFunction): """ Instantiate global functions. @@ -183,22 +188,24 @@ class InstantiatedGlobalFunction(parser.GlobalFunction): def to_cpp(self): """Generate the C++ code for wrapping.""" if self.original.template: - instantiated_names = [inst.instantiated_name() for inst in self.instantiations] - ret = "{}<{}>".format(self.original.name, ",".join(instantiated_names)) + instantiated_names = [ + inst.instantiated_name() for inst in self.instantiations + ] + ret = "{}<{}>".format(self.original.name, + ",".join(instantiated_names)) else: ret = self.original.name return ret def __repr__(self): return "Instantiated {}".format( - super(InstantiatedGlobalFunction, self).__repr__() - ) + super(InstantiatedGlobalFunction, self).__repr__()) + class InstantiatedMethod(parser.Method): """ We can only instantiate template methods with a single template parameter. """ - def __init__(self, original, instantiation=''): self.original = original self.instantiation = instantiation @@ -251,8 +258,7 @@ class InstantiatedMethod(parser.Method): def __repr__(self): return "Instantiated {}".format( - super(InstantiatedMethod, self).__repr__() - ) + super(InstantiatedMethod, self).__repr__()) class InstantiatedClass(parser.Class): @@ -272,28 +278,32 @@ class InstantiatedClass(parser.Class): self.parent_class = original.parent_class self.parent = original.parent - if not original.template: - self.name = original.name - self.ctors = list(original.ctors) - self.static_methods = list(original.static_methods) - class_instantiated_methods = list(original.methods) - self.properties = list(original.properties) - else: - # Check conditions. + # If the class is templated, check if the number of provided instantiations + # match the number of templates, else it's only a partial instantiation which is bad. + if original.template: assert len(original.template.typenames) == len( instantiations), "Typenames and instantiations mismatch!" - self.name = instantiate_name( - original.name, instantiations) if not new_name else new_name - self.ctors = self.instantiate_ctors() - self.static_methods = self.instantiate_static_methods() - class_instantiated_methods = \ - self.instantiate_class_templates_in_methods() - self.properties = self.instantiate_properties() + # Get the instantiated name of the class. E.g. FuncDouble + self.name = instantiate_name( + original.name, instantiations) if not new_name else new_name - # Second instantiation round to instantiate template methods. + # Check for typenames if templated. + # By passing in typenames, we can gracefully handle both templated and non-templated classes + # This will allow the `This` keyword to be used in both templated and non-templated classes. + typenames = self.original.template.typenames if self.original.template else [] + + # Instantiate the constructors, static methods, properties and instance methods, respectively. + self.ctors = self.instantiate_ctors(typenames) + self.static_methods = self.instantiate_static_methods(typenames) + self.properties = self.instantiate_properties(typenames) + instantiated_methods = self.instantiate_class_templates_in_methods( + typenames) + + # Second instantiation round to instantiate templated methods. + # This is done in case both the class and the method are templated. self.methods = [] - for method in class_instantiated_methods: + for method in instantiated_methods: if not method.template: self.methods.append(InstantiatedMethod(method, '')) else: @@ -328,83 +338,114 @@ class InstantiatedClass(parser.Class): for m in self.static_methods]), ) - def instantiate_ctors(self): - """Instantiate the class constructors.""" + def instantiate_ctors(self, typenames): + """ + Instantiate the class constructors. + + Args: + typenames: List of template types to instantiate. + + Return: List of constructors instantiated with provided template args. + """ instantiated_ctors = [] + for ctor in self.original.ctors: instantiated_args = instantiate_args_list( ctor.args.args_list, - self.original.template.typenames, + typenames, self.instantiations, self.cpp_typename(), ) - instantiated_ctors.append(parser.Constructor( - name=self.name, - args=parser.ArgumentList(instantiated_args), - parent=self, - )) + instantiated_ctors.append( + parser.Constructor( + name=self.name, + args=parser.ArgumentList(instantiated_args), + parent=self, + )) return instantiated_ctors - def instantiate_static_methods(self): - """Instantiate static methods in the class.""" + def instantiate_static_methods(self, typenames): + """ + Instantiate static methods in the class. + + Args: + typenames: List of template types to instantiate. + + Return: List of static methods instantiated with provided template args. + """ instantiated_static_methods = [] for static_method in self.original.static_methods: instantiated_args = instantiate_args_list( - static_method.args.args_list, - self.original.template.typenames, - self.instantiations, - self.cpp_typename() - ) + static_method.args.args_list, typenames, self.instantiations, + self.cpp_typename()) instantiated_static_methods.append( parser.StaticMethod( name=static_method.name, return_type=instantiate_return_type( static_method.return_type, - self.original.template.typenames, + typenames, self.instantiations, self.cpp_typename(), - instantiated_class=self - ), + instantiated_class=self), args=parser.ArgumentList(instantiated_args), parent=self, - ) - ) + )) return instantiated_static_methods - def instantiate_class_templates_in_methods(self): + def instantiate_class_templates_in_methods(self, typenames): """ - This function only instantiates class templates in the methods. + This function only instantiates the class-level templates in the methods. Template methods are instantiated in InstantiatedMethod in the second round. + + E.g. + ``` + template + class Greeter{ + void sayHello(T& name); + }; + + Args: + typenames: List of template types to instantiate. + + Return: List of methods instantiated with provided template args on the class. """ class_instantiated_methods = [] for method in self.original.methods: instantiated_args = instantiate_args_list( method.args.args_list, - self.original.template.typenames, + typenames, self.instantiations, self.cpp_typename(), ) - class_instantiated_methods.append(parser.Method( - template=method.template, - name=method.name, - return_type=instantiate_return_type( - method.return_type, - self.original.template.typenames, - self.instantiations, - self.cpp_typename(), - ), - args=parser.ArgumentList(instantiated_args), - is_const=method.is_const, - parent=self, - )) + class_instantiated_methods.append( + parser.Method( + template=method.template, + name=method.name, + return_type=instantiate_return_type( + method.return_type, + typenames, + self.instantiations, + self.cpp_typename(), + ), + args=parser.ArgumentList(instantiated_args), + is_const=method.is_const, + parent=self, + )) return class_instantiated_methods - def instantiate_properties(self): - """Instantiate the class properties.""" + def instantiate_properties(self, typenames): + """ + Instantiate the class properties. + + Args: + typenames: List of template types to instantiate. + + Return: List of properties instantiated with provided template args. + """ instantiated_properties = instantiate_args_list( self.original.properties, - self.original.template.typenames, + typenames, self.instantiations, self.cpp_typename(), ) @@ -448,6 +489,8 @@ def instantiate_namespace_inplace(namespace): instantiated_content.append( InstantiatedClass(original_class, [])) else: + # This case is for when the templates have enumerated instantiations. + # Use itertools to get all possible combinations of instantiations # Works even if one template does not have an instantiation list for instantiations in itertools.product( @@ -471,6 +514,8 @@ def instantiate_namespace_inplace(namespace): list(instantiations))) elif isinstance(element, parser.TypedefTemplateInstantiation): + # This is for the case where `typedef` statements are used + # to specify the template parameters. typedef_inst = element top_level = namespace.top_level() original_element = top_level.find_class_or_function( diff --git a/templates/matlab_wrapper.tpl.in b/templates/matlab_wrapper.tpl.in index 2885e9244..d42025726 100644 --- a/templates/matlab_wrapper.tpl.in +++ b/templates/matlab_wrapper.tpl.in @@ -1,2 +1,2 @@ -# include <${GTWRAP_INCLUDE_NAME}/matlab.h> -# include +#include <${GTWRAP_INCLUDE_NAME}/matlab.h> +#include diff --git a/pybind_wrapper.tpl.example b/templates/pybind_wrapper.tpl.example similarity index 100% rename from pybind_wrapper.tpl.example rename to templates/pybind_wrapper.tpl.example diff --git a/tests/.gitignore b/tests/.gitignore index 3169b1591..2981c977b 100644 --- a/tests/.gitignore +++ b/tests/.gitignore @@ -1,3 +1 @@ -actual-python/ -actual-matlab/ -actual-xml-generation/ \ No newline at end of file +actual/** diff --git a/tests/expected-matlab/PrimitiveRef.m b/tests/expected-matlab/PrimitiveRef.m deleted file mode 100644 index 63c295078..000000000 --- a/tests/expected-matlab/PrimitiveRef.m +++ /dev/null @@ -1,54 +0,0 @@ -%class PrimitiveRef, see Doxygen page for details -%at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html -% -%-------Constructors------- -%PrimitiveRef() -% -%-------Static Methods------- -%Brutal(double t) : returns This -% -%-------Serialization Interface------- -%string_serialize() : returns string -%string_deserialize(string serialized) : returns PrimitiveRef -% -classdef PrimitiveRef < handle - properties - ptr_PrimitiveRef = 0 - end - methods - function obj = PrimitiveRef(varargin) - if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) - my_ptr = varargin{2}; - geometry_wrapper(78, my_ptr); - elseif nargin == 0 - my_ptr = geometry_wrapper(79); - else - error('Arguments do not match any overload of PrimitiveRef constructor'); - end - obj.ptr_PrimitiveRef = my_ptr; - end - - function delete(obj) - geometry_wrapper(80, obj.ptr_PrimitiveRef); - end - - function display(obj), obj.print(''); end - %DISPLAY Calls print on the object - function disp(obj), obj.display; end - %DISP Calls print on the object - end - - methods(Static = true) - function varargout = Brutal(varargin) - % BRUTAL usage: Brutal(double t) : returns This - % Doxygen can be found at http://research.cc.gatech.edu/borg/sites/edu.borg/html/index.html - if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(81, varargin{:}); - return - end - - error('Arguments do not match any overload of function PrimitiveRef.Brutal'); - end - - end -end diff --git a/tests/expected-matlab/geometry_wrapper.cpp b/tests/expected-matlab/geometry_wrapper.cpp deleted file mode 100644 index 703ca76ae..000000000 --- a/tests/expected-matlab/geometry_wrapper.cpp +++ /dev/null @@ -1,1590 +0,0 @@ -#include -#include - -#include -#include -#include - -#include -#include -#include - -typedef MyTemplate MyTemplatePoint2; -typedef MyTemplate MyTemplateMatrix; -typedef PrimitiveRef PrimitiveRefDouble; -typedef MyVector<3> MyVector3; -typedef MyVector<12> MyVector12; -typedef MultipleTemplates MultipleTemplatesIntDouble; -typedef MultipleTemplates MultipleTemplatesIntFloat; -typedef MyFactor MyFactorPosePoint2; - -BOOST_CLASS_EXPORT_GUID(gtsam::Point2, "gtsamPoint2"); -BOOST_CLASS_EXPORT_GUID(gtsam::Point3, "gtsamPoint3"); - -typedef std::set*> Collector_gtsamPoint2; -static Collector_gtsamPoint2 collector_gtsamPoint2; -typedef std::set*> Collector_gtsamPoint3; -static Collector_gtsamPoint3 collector_gtsamPoint3; -typedef std::set*> Collector_Test; -static Collector_Test collector_Test; -typedef std::set*> Collector_MyBase; -static Collector_MyBase collector_MyBase; -typedef std::set*> Collector_MyTemplatePoint2; -static Collector_MyTemplatePoint2 collector_MyTemplatePoint2; -typedef std::set*> Collector_MyTemplateMatrix; -static Collector_MyTemplateMatrix collector_MyTemplateMatrix; -typedef std::set*> Collector_PrimitiveRefDouble; -static Collector_PrimitiveRefDouble collector_PrimitiveRefDouble; -typedef std::set*> Collector_MyVector3; -static Collector_MyVector3 collector_MyVector3; -typedef std::set*> Collector_MyVector12; -static Collector_MyVector12 collector_MyVector12; -typedef std::set*> Collector_MultipleTemplatesIntDouble; -static Collector_MultipleTemplatesIntDouble collector_MultipleTemplatesIntDouble; -typedef std::set*> Collector_MultipleTemplatesIntFloat; -static Collector_MultipleTemplatesIntFloat collector_MultipleTemplatesIntFloat; -typedef std::set*> Collector_MyFactorPosePoint2; -static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2; - -void _deleteAllObjects() -{ - mstream mout; - std::streambuf *outbuf = std::cout.rdbuf(&mout); - - bool anyDeleted = false; - { for(Collector_gtsamPoint2::iterator iter = collector_gtsamPoint2.begin(); - iter != collector_gtsamPoint2.end(); ) { - delete *iter; - collector_gtsamPoint2.erase(iter++); - anyDeleted = true; - } } - { for(Collector_gtsamPoint3::iterator iter = collector_gtsamPoint3.begin(); - iter != collector_gtsamPoint3.end(); ) { - delete *iter; - collector_gtsamPoint3.erase(iter++); - anyDeleted = true; - } } - { for(Collector_Test::iterator iter = collector_Test.begin(); - iter != collector_Test.end(); ) { - delete *iter; - collector_Test.erase(iter++); - anyDeleted = true; - } } - { for(Collector_MyBase::iterator iter = collector_MyBase.begin(); - iter != collector_MyBase.end(); ) { - delete *iter; - collector_MyBase.erase(iter++); - anyDeleted = true; - } } - { for(Collector_MyTemplatePoint2::iterator iter = collector_MyTemplatePoint2.begin(); - iter != collector_MyTemplatePoint2.end(); ) { - delete *iter; - collector_MyTemplatePoint2.erase(iter++); - anyDeleted = true; - } } - { for(Collector_MyTemplateMatrix::iterator iter = collector_MyTemplateMatrix.begin(); - iter != collector_MyTemplateMatrix.end(); ) { - delete *iter; - collector_MyTemplateMatrix.erase(iter++); - anyDeleted = true; - } } - { for(Collector_PrimitiveRefDouble::iterator iter = collector_PrimitiveRefDouble.begin(); - iter != collector_PrimitiveRefDouble.end(); ) { - delete *iter; - collector_PrimitiveRefDouble.erase(iter++); - anyDeleted = true; - } } - { for(Collector_MyVector3::iterator iter = collector_MyVector3.begin(); - iter != collector_MyVector3.end(); ) { - delete *iter; - collector_MyVector3.erase(iter++); - anyDeleted = true; - } } - { for(Collector_MyVector12::iterator iter = collector_MyVector12.begin(); - iter != collector_MyVector12.end(); ) { - delete *iter; - collector_MyVector12.erase(iter++); - anyDeleted = true; - } } - { for(Collector_MultipleTemplatesIntDouble::iterator iter = collector_MultipleTemplatesIntDouble.begin(); - iter != collector_MultipleTemplatesIntDouble.end(); ) { - delete *iter; - collector_MultipleTemplatesIntDouble.erase(iter++); - anyDeleted = true; - } } - { for(Collector_MultipleTemplatesIntFloat::iterator iter = collector_MultipleTemplatesIntFloat.begin(); - iter != collector_MultipleTemplatesIntFloat.end(); ) { - delete *iter; - collector_MultipleTemplatesIntFloat.erase(iter++); - anyDeleted = true; - } } - { for(Collector_MyFactorPosePoint2::iterator iter = collector_MyFactorPosePoint2.begin(); - iter != collector_MyFactorPosePoint2.end(); ) { - delete *iter; - collector_MyFactorPosePoint2.erase(iter++); - anyDeleted = true; - } } - if(anyDeleted) - cout << - "WARNING: Wrap modules with variables in the workspace have been reloaded due to\n" - "calling destructors, call 'clear all' again if you plan to now recompile a wrap\n" - "module, so that your recompiled module is used instead of the old one." << endl; - std::cout.rdbuf(outbuf); -} - -void _geometry_RTTIRegister() { - const mxArray *alreadyCreated = mexGetVariablePtr("global", "gtsam_geometry_rttiRegistry_created"); - if(!alreadyCreated) { - std::map types; - types.insert(std::make_pair(typeid(MyBase).name(), "MyBase")); - types.insert(std::make_pair(typeid(MyTemplatePoint2).name(), "MyTemplatePoint2")); - types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix")); - - mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); - if(!registry) - registry = mxCreateStructMatrix(1, 1, 0, NULL); - typedef std::pair StringPair; - for(const StringPair& rtti_matlab: types) { - int fieldId = mxAddField(registry, rtti_matlab.first.c_str()); - if(fieldId < 0) - mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); - mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str()); - mxSetFieldByNumber(registry, 0, fieldId, matlabName); - } - if(mexPutVariable("global", "gtsamwrap_rttiRegistry", registry) != 0) - mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); - mxDestroyArray(registry); - - mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL); - if(mexPutVariable("global", "gtsam_geometry_rttiRegistry_created", newAlreadyCreated) != 0) - mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); - mxDestroyArray(newAlreadyCreated); - } -} - -void gtsamPoint2_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; - - Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_gtsamPoint2.insert(self); -} - -void gtsamPoint2_constructor_1(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; - - Shared *self = new Shared(new gtsam::Point2()); - collector_gtsamPoint2.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetData(out[0])) = self; -} - -void gtsamPoint2_constructor_2(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; - - double x = unwrap< double >(in[0]); - double y = unwrap< double >(in[1]); - Shared *self = new Shared(new gtsam::Point2(x,y)); - collector_gtsamPoint2.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetData(out[0])) = self; -} - -void gtsamPoint2_deconstructor_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr Shared; - checkArguments("delete_gtsamPoint2",nargout,nargin,1); - Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_gtsamPoint2::iterator item; - item = collector_gtsamPoint2.find(self); - if(item != collector_gtsamPoint2.end()) { - delete self; - collector_gtsamPoint2.erase(item); - } -} - -void gtsamPoint2_argChar_4(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("argChar",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); - char a = unwrap< char >(in[1]); - obj->argChar(a); -} - -void gtsamPoint2_argChar_5(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("argChar",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); - boost::shared_ptr a = unwrap_shared_ptr< char >(in[1], "ptr_char"); - obj->argChar(a); -} - -void gtsamPoint2_argChar_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("argChar",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); - char a = unwrap< char >(in[1]); - obj->argChar(a); -} - -void gtsamPoint2_argChar_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("argChar",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); - boost::shared_ptr a = unwrap_shared_ptr< char >(in[1], "ptr_char"); - obj->argChar(a); -} - -void gtsamPoint2_argChar_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("argChar",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); - boost::shared_ptr a = unwrap_shared_ptr< char >(in[1], "ptr_char"); - obj->argChar(a); -} - -void gtsamPoint2_argChar_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("argChar",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); - char a = unwrap< char >(in[1]); - obj->argChar(a); -} - -void gtsamPoint2_argChar_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("argChar",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); - boost::shared_ptr a = unwrap_shared_ptr< char >(in[1], "ptr_char"); - obj->argChar(a); -} - -void gtsamPoint2_argUChar_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("argUChar",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); - unsigned char a = unwrap< unsigned char >(in[1]); - obj->argUChar(a); -} - -void gtsamPoint2_dim_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("dim",nargout,nargin-1,0); - auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); - out[0] = wrap< int >(obj->dim()); -} - -void gtsamPoint2_eigenArguments_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("eigenArguments",nargout,nargin-1,2); - auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); - Vector v = unwrap< Vector >(in[1]); - Matrix m = unwrap< Matrix >(in[2]); - obj->eigenArguments(v,m); -} - -void gtsamPoint2_returnChar_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("returnChar",nargout,nargin-1,0); - auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); - out[0] = wrap< char >(obj->returnChar()); -} - -void gtsamPoint2_vectorConfusion_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("vectorConfusion",nargout,nargin-1,0); - auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); - out[0] = wrap_shared_ptr(boost::make_shared(obj->vectorConfusion()),"VectorNotEigen", false); -} - -void gtsamPoint2_x_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("x",nargout,nargin-1,0); - auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); - out[0] = wrap< double >(obj->x()); -} - -void gtsamPoint2_y_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("y",nargout,nargin-1,0); - auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); - out[0] = wrap< double >(obj->y()); -} - -void gtsamPoint3_collectorInsertAndMakeBase_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; - - Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_gtsamPoint3.insert(self); -} - -void gtsamPoint3_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; - - double x = unwrap< double >(in[0]); - double y = unwrap< double >(in[1]); - double z = unwrap< double >(in[2]); - Shared *self = new Shared(new gtsam::Point3(x,y,z)); - collector_gtsamPoint3.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetData(out[0])) = self; -} - -void gtsamPoint3_deconstructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr Shared; - checkArguments("delete_gtsamPoint3",nargout,nargin,1); - Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_gtsamPoint3::iterator item; - item = collector_gtsamPoint3.find(self); - if(item != collector_gtsamPoint3.end()) { - delete self; - collector_gtsamPoint3.erase(item); - } -} - -void gtsamPoint3_norm_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("norm",nargout,nargin-1,0); - auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint3"); - out[0] = wrap< double >(obj->norm()); -} - -void gtsamPoint3_string_serialize_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr Shared; - checkArguments("string_serialize",nargout,nargin-1,0); - Shared obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint3"); - ostringstream out_archive_stream; - boost::archive::text_oarchive out_archive(out_archive_stream); - out_archive << *obj; - out[0] = wrap< string >(out_archive_stream.str()); -} -void gtsamPoint3_StaticFunctionRet_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("gtsamPoint3.StaticFunctionRet",nargout,nargin,1); - double z = unwrap< double >(in[0]); - out[0] = wrap< Point3 >(gtsam::Point3::StaticFunctionRet(z)); -} - -void gtsamPoint3_staticFunction_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("gtsamPoint3.staticFunction",nargout,nargin,0); - out[0] = wrap< double >(gtsam::Point3::staticFunction()); -} - -void gtsamPoint3_string_deserialize_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr Shared; - checkArguments("gtsamPoint3.string_deserialize",nargout,nargin,1); - string serialized = unwrap< string >(in[0]); - istringstream in_archive_stream(serialized); - boost::archive::text_iarchive in_archive(in_archive_stream); - Shared output(new gtsam::Point3()); - in_archive >> *output; - out[0] = wrap_shared_ptr(output,"gtsam.Point3", false); -} -void Test_collectorInsertAndMakeBase_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; - - Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_Test.insert(self); -} - -void Test_constructor_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; - - Shared *self = new Shared(new Test()); - collector_Test.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetData(out[0])) = self; -} - -void Test_constructor_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; - - double a = unwrap< double >(in[0]); - Matrix b = unwrap< Matrix >(in[1]); - Shared *self = new Shared(new Test(a,b)); - collector_Test.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetData(out[0])) = self; -} - -void Test_deconstructor_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr Shared; - checkArguments("delete_Test",nargout,nargin,1); - Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_Test::iterator item; - item = collector_Test.find(self); - if(item != collector_Test.end()) { - delete self; - collector_Test.erase(item); - } -} - -void Test_arg_EigenConstRef_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("arg_EigenConstRef",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - Matrix value = unwrap< Matrix >(in[1]); - obj->arg_EigenConstRef(value); -} - -void Test_create_MixedPtrs_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("create_MixedPtrs",nargout,nargin-1,0); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - auto pairResult = obj->create_MixedPtrs(); - out[0] = wrap_shared_ptr(boost::make_shared(pairResult.first),"Test", false); - out[1] = wrap_shared_ptr(pairResult.second,"Test", false); -} - -void Test_create_ptrs_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("create_ptrs",nargout,nargin-1,0); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - auto pairResult = obj->create_ptrs(); - out[0] = wrap_shared_ptr(pairResult.first,"Test", false); - out[1] = wrap_shared_ptr(pairResult.second,"Test", false); -} - -void Test_print_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("print",nargout,nargin-1,0); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - obj->print(); -} - -void Test_return_Point2Ptr_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_Point2Ptr",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - bool value = unwrap< bool >(in[1]); - { - boost::shared_ptr shared(obj->return_Point2Ptr(value)); - out[0] = wrap_shared_ptr(shared,"Point2"); - } -} - -void Test_return_Test_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_Test",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); - out[0] = wrap_shared_ptr(boost::make_shared(obj->return_Test(value)),"Test", false); -} - -void Test_return_TestPtr_36(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_TestPtr",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); - out[0] = wrap_shared_ptr(obj->return_TestPtr(value),"Test", false); -} - -void Test_return_bool_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_bool",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - bool value = unwrap< bool >(in[1]); - out[0] = wrap< bool >(obj->return_bool(value)); -} - -void Test_return_double_38(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_double",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - double value = unwrap< double >(in[1]); - out[0] = wrap< double >(obj->return_double(value)); -} - -void Test_return_field_39(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_field",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - Test& t = *unwrap_shared_ptr< Test >(in[1], "ptr_Test"); - out[0] = wrap< bool >(obj->return_field(t)); -} - -void Test_return_int_40(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_int",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - int value = unwrap< int >(in[1]); - out[0] = wrap< int >(obj->return_int(value)); -} - -void Test_return_matrix1_41(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_matrix1",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - Matrix value = unwrap< Matrix >(in[1]); - out[0] = wrap< Matrix >(obj->return_matrix1(value)); -} - -void Test_return_matrix2_42(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_matrix2",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - Matrix value = unwrap< Matrix >(in[1]); - out[0] = wrap< Matrix >(obj->return_matrix2(value)); -} - -void Test_return_pair_43(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_pair",nargout,nargin-1,2); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - Vector v = unwrap< Vector >(in[1]); - Matrix A = unwrap< Matrix >(in[2]); - auto pairResult = obj->return_pair(v,A); - out[0] = wrap< Vector >(pairResult.first); - out[1] = wrap< Matrix >(pairResult.second); -} - -void Test_return_pair_44(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_pair",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - Vector v = unwrap< Vector >(in[1]); - auto pairResult = obj->return_pair(v); - out[0] = wrap< Vector >(pairResult.first); - out[1] = wrap< Matrix >(pairResult.second); -} - -void Test_return_ptrs_45(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_ptrs",nargout,nargin-1,2); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - boost::shared_ptr p1 = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); - boost::shared_ptr p2 = unwrap_shared_ptr< Test >(in[2], "ptr_Test"); - auto pairResult = obj->return_ptrs(p1,p2); - out[0] = wrap_shared_ptr(pairResult.first,"Test", false); - out[1] = wrap_shared_ptr(pairResult.second,"Test", false); -} - -void Test_return_size_t_46(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_size_t",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - size_t value = unwrap< size_t >(in[1]); - out[0] = wrap< size_t >(obj->return_size_t(value)); -} - -void Test_return_string_47(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_string",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - string value = unwrap< string >(in[1]); - out[0] = wrap< string >(obj->return_string(value)); -} - -void Test_return_vector1_48(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_vector1",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - Vector value = unwrap< Vector >(in[1]); - out[0] = wrap< Vector >(obj->return_vector1(value)); -} - -void Test_return_vector2_49(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_vector2",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); - Vector value = unwrap< Vector >(in[1]); - out[0] = wrap< Vector >(obj->return_vector2(value)); -} - -void MyBase_collectorInsertAndMakeBase_50(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; - - Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_MyBase.insert(self); -} - -void MyBase_upcastFromVoid_51(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr Shared; - boost::shared_ptr *asVoid = *reinterpret_cast**> (mxGetData(in[0])); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - Shared *self = new Shared(boost::static_pointer_cast(*asVoid)); - *reinterpret_cast(mxGetData(out[0])) = self; -} - -void MyBase_deconstructor_52(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr Shared; - checkArguments("delete_MyBase",nargout,nargin,1); - Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_MyBase::iterator item; - item = collector_MyBase.find(self); - if(item != collector_MyBase.end()) { - delete self; - collector_MyBase.erase(item); - } -} - -void MyTemplatePoint2_collectorInsertAndMakeBase_53(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - - Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_MyTemplatePoint2.insert(self); - - typedef boost::shared_ptr SharedBase; - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast(mxGetData(out[0])) = new SharedBase(*self); -} - -void MyTemplatePoint2_upcastFromVoid_54(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - boost::shared_ptr *asVoid = *reinterpret_cast**> (mxGetData(in[0])); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - Shared *self = new Shared(boost::static_pointer_cast>(*asVoid)); - *reinterpret_cast(mxGetData(out[0])) = self; -} - -void MyTemplatePoint2_constructor_55(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - - Shared *self = new Shared(new MyTemplate()); - collector_MyTemplatePoint2.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetData(out[0])) = self; - - typedef boost::shared_ptr SharedBase; - out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast(mxGetData(out[1])) = new SharedBase(*self); -} - -void MyTemplatePoint2_deconstructor_56(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr> Shared; - checkArguments("delete_MyTemplatePoint2",nargout,nargin,1); - Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_MyTemplatePoint2::iterator item; - item = collector_MyTemplatePoint2.find(self); - if(item != collector_MyTemplatePoint2.end()) { - delete self; - collector_MyTemplatePoint2.erase(item); - } -} - -void MyTemplatePoint2_accept_T_57(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("accept_T",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); - Point2 value = unwrap< Point2 >(in[1]); - obj->accept_T(value); -} - -void MyTemplatePoint2_accept_Tptr_58(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("accept_Tptr",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); - Point2 value = unwrap< Point2 >(in[1]); - obj->accept_Tptr(value); -} - -void MyTemplatePoint2_create_MixedPtrs_59(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("create_MixedPtrs",nargout,nargin-1,0); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); - auto pairResult = obj->create_MixedPtrs(); - out[0] = wrap< Point2 >(pairResult.first); - { - boost::shared_ptr shared(pairResult.second); - out[1] = wrap_shared_ptr(shared,"Point2"); - } -} - -void MyTemplatePoint2_create_ptrs_60(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("create_ptrs",nargout,nargin-1,0); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); - auto pairResult = obj->create_ptrs(); - { - boost::shared_ptr shared(pairResult.first); - out[0] = wrap_shared_ptr(shared,"Point2"); - } - { - boost::shared_ptr shared(pairResult.second); - out[1] = wrap_shared_ptr(shared,"Point2"); - } -} - -void MyTemplatePoint2_return_T_61(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_T",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); - Point2 value = unwrap< Point2 >(in[1]); - out[0] = wrap< Point2 >(obj->return_T(value)); -} - -void MyTemplatePoint2_return_Tptr_62(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_Tptr",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); - Point2 value = unwrap< Point2 >(in[1]); - { - boost::shared_ptr shared(obj->return_Tptr(value)); - out[0] = wrap_shared_ptr(shared,"Point2"); - } -} - -void MyTemplatePoint2_return_ptrs_63(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_ptrs",nargout,nargin-1,2); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); - Point2 p1 = unwrap< Point2 >(in[1]); - Point2 p2 = unwrap< Point2 >(in[2]); - auto pairResult = obj->return_ptrs(p1,p2); - { - boost::shared_ptr shared(pairResult.first); - out[0] = wrap_shared_ptr(shared,"Point2"); - } - { - boost::shared_ptr shared(pairResult.second); - out[1] = wrap_shared_ptr(shared,"Point2"); - } -} - -void MyTemplatePoint2_templatedMethod_64(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("templatedMethodMatrix",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); - Matrix t = unwrap< Matrix >(in[1]); - out[0] = wrap< Matrix >(obj->templatedMethod(t)); -} - -void MyTemplatePoint2_templatedMethod_65(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("templatedMethodPoint2",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); - Point2 t = unwrap< Point2 >(in[1]); - out[0] = wrap< Point2 >(obj->templatedMethod(t)); -} - -void MyTemplatePoint2_templatedMethod_66(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("templatedMethodPoint3",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); - Point3 t = unwrap< Point3 >(in[1]); - out[0] = wrap< Point3 >(obj->templatedMethod(t)); -} - -void MyTemplatePoint2_templatedMethod_67(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("templatedMethodVector",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); - Vector t = unwrap< Vector >(in[1]); - out[0] = wrap< Vector >(obj->templatedMethod(t)); -} - -void MyTemplatePoint2_Level_68(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("MyTemplatePoint2.Level",nargout,nargin,1); - Point2 K = unwrap< Point2 >(in[0]); - out[0] = wrap_shared_ptr(boost::make_shared>(MyTemplate::Level(K)),"MyTemplatePoint2", false); -} - -void MyTemplateMatrix_collectorInsertAndMakeBase_69(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - - Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_MyTemplateMatrix.insert(self); - - typedef boost::shared_ptr SharedBase; - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast(mxGetData(out[0])) = new SharedBase(*self); -} - -void MyTemplateMatrix_upcastFromVoid_70(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - boost::shared_ptr *asVoid = *reinterpret_cast**> (mxGetData(in[0])); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - Shared *self = new Shared(boost::static_pointer_cast>(*asVoid)); - *reinterpret_cast(mxGetData(out[0])) = self; -} - -void MyTemplateMatrix_constructor_71(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - - Shared *self = new Shared(new MyTemplate()); - collector_MyTemplateMatrix.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetData(out[0])) = self; - - typedef boost::shared_ptr SharedBase; - out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast(mxGetData(out[1])) = new SharedBase(*self); -} - -void MyTemplateMatrix_deconstructor_72(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr> Shared; - checkArguments("delete_MyTemplateMatrix",nargout,nargin,1); - Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_MyTemplateMatrix::iterator item; - item = collector_MyTemplateMatrix.find(self); - if(item != collector_MyTemplateMatrix.end()) { - delete self; - collector_MyTemplateMatrix.erase(item); - } -} - -void MyTemplateMatrix_accept_T_73(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("accept_T",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); - Matrix value = unwrap< Matrix >(in[1]); - obj->accept_T(value); -} - -void MyTemplateMatrix_accept_Tptr_74(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("accept_Tptr",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); - Matrix value = unwrap< Matrix >(in[1]); - obj->accept_Tptr(value); -} - -void MyTemplateMatrix_create_MixedPtrs_75(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("create_MixedPtrs",nargout,nargin-1,0); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); - auto pairResult = obj->create_MixedPtrs(); - out[0] = wrap< Matrix >(pairResult.first); - { - boost::shared_ptr shared(pairResult.second); - out[1] = wrap_shared_ptr(shared,"Matrix"); - } -} - -void MyTemplateMatrix_create_ptrs_76(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("create_ptrs",nargout,nargin-1,0); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); - auto pairResult = obj->create_ptrs(); - { - boost::shared_ptr shared(pairResult.first); - out[0] = wrap_shared_ptr(shared,"Matrix"); - } - { - boost::shared_ptr shared(pairResult.second); - out[1] = wrap_shared_ptr(shared,"Matrix"); - } -} - -void MyTemplateMatrix_return_T_77(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_T",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); - Matrix value = unwrap< Matrix >(in[1]); - out[0] = wrap< Matrix >(obj->return_T(value)); -} - -void MyTemplateMatrix_return_Tptr_78(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_Tptr",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); - Matrix value = unwrap< Matrix >(in[1]); - { - boost::shared_ptr shared(obj->return_Tptr(value)); - out[0] = wrap_shared_ptr(shared,"Matrix"); - } -} - -void MyTemplateMatrix_return_ptrs_79(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("return_ptrs",nargout,nargin-1,2); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); - Matrix p1 = unwrap< Matrix >(in[1]); - Matrix p2 = unwrap< Matrix >(in[2]); - auto pairResult = obj->return_ptrs(p1,p2); - { - boost::shared_ptr shared(pairResult.first); - out[0] = wrap_shared_ptr(shared,"Matrix"); - } - { - boost::shared_ptr shared(pairResult.second); - out[1] = wrap_shared_ptr(shared,"Matrix"); - } -} - -void MyTemplateMatrix_templatedMethod_80(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("templatedMethodMatrix",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); - Matrix t = unwrap< Matrix >(in[1]); - out[0] = wrap< Matrix >(obj->templatedMethod(t)); -} - -void MyTemplateMatrix_templatedMethod_81(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("templatedMethodPoint2",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); - Point2 t = unwrap< Point2 >(in[1]); - out[0] = wrap< Point2 >(obj->templatedMethod(t)); -} - -void MyTemplateMatrix_templatedMethod_82(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("templatedMethodPoint3",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); - Point3 t = unwrap< Point3 >(in[1]); - out[0] = wrap< Point3 >(obj->templatedMethod(t)); -} - -void MyTemplateMatrix_templatedMethod_83(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("templatedMethodVector",nargout,nargin-1,1); - auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); - Vector t = unwrap< Vector >(in[1]); - out[0] = wrap< Vector >(obj->templatedMethod(t)); -} - -void MyTemplateMatrix_Level_84(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("MyTemplateMatrix.Level",nargout,nargin,1); - Matrix K = unwrap< Matrix >(in[0]); - out[0] = wrap_shared_ptr(boost::make_shared>(MyTemplate::Level(K)),"MyTemplateMatrix", false); -} - -void PrimitiveRefDouble_collectorInsertAndMakeBase_85(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - - Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_PrimitiveRefDouble.insert(self); -} - -void PrimitiveRefDouble_constructor_86(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - - Shared *self = new Shared(new PrimitiveRef()); - collector_PrimitiveRefDouble.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetData(out[0])) = self; -} - -void PrimitiveRefDouble_deconstructor_87(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr> Shared; - checkArguments("delete_PrimitiveRefDouble",nargout,nargin,1); - Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_PrimitiveRefDouble::iterator item; - item = collector_PrimitiveRefDouble.find(self); - if(item != collector_PrimitiveRefDouble.end()) { - delete self; - collector_PrimitiveRefDouble.erase(item); - } -} - -void PrimitiveRefDouble_Brutal_88(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("PrimitiveRefDouble.Brutal",nargout,nargin,1); - double t = unwrap< double >(in[0]); - out[0] = wrap_shared_ptr(boost::make_shared>(PrimitiveRef::Brutal(t)),"PrimitiveRefdouble", false); -} - -void MyVector3_collectorInsertAndMakeBase_89(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - - Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_MyVector3.insert(self); -} - -void MyVector3_constructor_90(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - - Shared *self = new Shared(new MyVector<3>()); - collector_MyVector3.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetData(out[0])) = self; -} - -void MyVector3_deconstructor_91(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr> Shared; - checkArguments("delete_MyVector3",nargout,nargin,1); - Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_MyVector3::iterator item; - item = collector_MyVector3.find(self); - if(item != collector_MyVector3.end()) { - delete self; - collector_MyVector3.erase(item); - } -} - -void MyVector12_collectorInsertAndMakeBase_92(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - - Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_MyVector12.insert(self); -} - -void MyVector12_constructor_93(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - - Shared *self = new Shared(new MyVector<12>()); - collector_MyVector12.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetData(out[0])) = self; -} - -void MyVector12_deconstructor_94(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr> Shared; - checkArguments("delete_MyVector12",nargout,nargin,1); - Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_MyVector12::iterator item; - item = collector_MyVector12.find(self); - if(item != collector_MyVector12.end()) { - delete self; - collector_MyVector12.erase(item); - } -} - -void MultipleTemplatesIntDouble_collectorInsertAndMakeBase_95(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - - Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_MultipleTemplatesIntDouble.insert(self); -} - -void MultipleTemplatesIntDouble_deconstructor_96(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr> Shared; - checkArguments("delete_MultipleTemplatesIntDouble",nargout,nargin,1); - Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_MultipleTemplatesIntDouble::iterator item; - item = collector_MultipleTemplatesIntDouble.find(self); - if(item != collector_MultipleTemplatesIntDouble.end()) { - delete self; - collector_MultipleTemplatesIntDouble.erase(item); - } -} - -void MultipleTemplatesIntFloat_collectorInsertAndMakeBase_97(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - - Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_MultipleTemplatesIntFloat.insert(self); -} - -void MultipleTemplatesIntFloat_deconstructor_98(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr> Shared; - checkArguments("delete_MultipleTemplatesIntFloat",nargout,nargin,1); - Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_MultipleTemplatesIntFloat::iterator item; - item = collector_MultipleTemplatesIntFloat.find(self); - if(item != collector_MultipleTemplatesIntFloat.end()) { - delete self; - collector_MultipleTemplatesIntFloat.erase(item); - } -} - -void MyFactorPosePoint2_collectorInsertAndMakeBase_99(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - - Shared *self = *reinterpret_cast (mxGetData(in[0])); - collector_MyFactorPosePoint2.insert(self); -} - -void MyFactorPosePoint2_constructor_100(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mexAtExit(&_deleteAllObjects); - typedef boost::shared_ptr> Shared; - - size_t key1 = unwrap< size_t >(in[0]); - size_t key2 = unwrap< size_t >(in[1]); - double measured = unwrap< double >(in[2]); - boost::shared_ptr noiseModel = unwrap_shared_ptr< gtsam::noiseModel::Base >(in[3], "ptr_gtsamnoiseModelBase"); - Shared *self = new Shared(new MyFactor(key1,key2,measured,noiseModel)); - collector_MyFactorPosePoint2.insert(self); - out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); - *reinterpret_cast (mxGetData(out[0])) = self; -} - -void MyFactorPosePoint2_deconstructor_101(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - typedef boost::shared_ptr> Shared; - checkArguments("delete_MyFactorPosePoint2",nargout,nargin,1); - Shared *self = *reinterpret_cast(mxGetData(in[0])); - Collector_MyFactorPosePoint2::iterator item; - item = collector_MyFactorPosePoint2.find(self); - if(item != collector_MyFactorPosePoint2.end()) { - delete self; - collector_MyFactorPosePoint2.erase(item); - } -} - -void load2D_102(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("load2D",nargout,nargin,5); - string filename = unwrap< string >(in[0]); - boost::shared_ptr model = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); - int maxID = unwrap< int >(in[2]); - bool addNoise = unwrap< bool >(in[3]); - bool smart = unwrap< bool >(in[4]); - auto pairResult = load2D(filename,model,maxID,addNoise,smart); - out[0] = wrap_shared_ptr(pairResult.first,"gtsam.NonlinearFactorGraph", false); - out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Values", false); -} -void load2D_103(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("load2D",nargout,nargin,5); - string filename = unwrap< string >(in[0]); - boost::shared_ptr model = unwrap_shared_ptr< gtsam::noiseModel::Diagonal >(in[1], "ptr_gtsamnoiseModelDiagonal"); - int maxID = unwrap< int >(in[2]); - bool addNoise = unwrap< bool >(in[3]); - bool smart = unwrap< bool >(in[4]); - auto pairResult = load2D(filename,model,maxID,addNoise,smart); - out[0] = wrap_shared_ptr(pairResult.first,"gtsam.NonlinearFactorGraph", false); - out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Values", false); -} -void load2D_104(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("load2D",nargout,nargin,2); - string filename = unwrap< string >(in[0]); - boost::shared_ptr model = unwrap_shared_ptr< gtsam::noiseModel::Diagonal >(in[1], "ptr_gtsamnoiseModelDiagonal"); - auto pairResult = load2D(filename,model); - out[0] = wrap_shared_ptr(pairResult.first,"gtsam.NonlinearFactorGraph", false); - out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Values", false); -} -void aGlobalFunction_105(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("aGlobalFunction",nargout,nargin,0); - out[0] = wrap< Vector >(aGlobalFunction()); -} -void overloadedGlobalFunction_106(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("overloadedGlobalFunction",nargout,nargin,1); - int a = unwrap< int >(in[0]); - out[0] = wrap< Vector >(overloadedGlobalFunction(a)); -} -void overloadedGlobalFunction_107(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("overloadedGlobalFunction",nargout,nargin,2); - int a = unwrap< int >(in[0]); - double b = unwrap< double >(in[1]); - out[0] = wrap< Vector >(overloadedGlobalFunction(a,b)); -} -void MultiTemplatedFunctionStringSize_tDouble_108(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("MultiTemplatedFunctionStringSize_tDouble",nargout,nargin,2); - T& x = *unwrap_shared_ptr< T >(in[0], "ptr_T"); - size_t y = unwrap< size_t >(in[1]); - out[0] = wrap< double >(MultiTemplatedFunctionStringSize_tDouble(x,y)); -} -void MultiTemplatedFunctionDoubleSize_tDouble_109(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("MultiTemplatedFunctionDoubleSize_tDouble",nargout,nargin,2); - T& x = *unwrap_shared_ptr< T >(in[0], "ptr_T"); - size_t y = unwrap< size_t >(in[1]); - out[0] = wrap< double >(MultiTemplatedFunctionDoubleSize_tDouble(x,y)); -} -void TemplatedFunctionRot3_110(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - checkArguments("TemplatedFunctionRot3",nargout,nargin,1); - gtsam::Rot3& t = *unwrap_shared_ptr< gtsam::Rot3 >(in[0], "ptr_gtsamRot3"); - TemplatedFunctionRot3(t); -} - -void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) -{ - mstream mout; - std::streambuf *outbuf = std::cout.rdbuf(&mout); - - _geometry_RTTIRegister(); - - int id = unwrap(in[0]); - - try { - switch(id) { - case 0: - gtsamPoint2_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); - break; - case 1: - gtsamPoint2_constructor_1(nargout, out, nargin-1, in+1); - break; - case 2: - gtsamPoint2_constructor_2(nargout, out, nargin-1, in+1); - break; - case 3: - gtsamPoint2_deconstructor_3(nargout, out, nargin-1, in+1); - break; - case 4: - gtsamPoint2_argChar_4(nargout, out, nargin-1, in+1); - break; - case 5: - gtsamPoint2_argChar_5(nargout, out, nargin-1, in+1); - break; - case 6: - gtsamPoint2_argChar_6(nargout, out, nargin-1, in+1); - break; - case 7: - gtsamPoint2_argChar_7(nargout, out, nargin-1, in+1); - break; - case 8: - gtsamPoint2_argChar_8(nargout, out, nargin-1, in+1); - break; - case 9: - gtsamPoint2_argChar_9(nargout, out, nargin-1, in+1); - break; - case 10: - gtsamPoint2_argChar_10(nargout, out, nargin-1, in+1); - break; - case 11: - gtsamPoint2_argUChar_11(nargout, out, nargin-1, in+1); - break; - case 12: - gtsamPoint2_dim_12(nargout, out, nargin-1, in+1); - break; - case 13: - gtsamPoint2_eigenArguments_13(nargout, out, nargin-1, in+1); - break; - case 14: - gtsamPoint2_returnChar_14(nargout, out, nargin-1, in+1); - break; - case 15: - gtsamPoint2_vectorConfusion_15(nargout, out, nargin-1, in+1); - break; - case 16: - gtsamPoint2_x_16(nargout, out, nargin-1, in+1); - break; - case 17: - gtsamPoint2_y_17(nargout, out, nargin-1, in+1); - break; - case 18: - gtsamPoint3_collectorInsertAndMakeBase_18(nargout, out, nargin-1, in+1); - break; - case 19: - gtsamPoint3_constructor_19(nargout, out, nargin-1, in+1); - break; - case 20: - gtsamPoint3_deconstructor_20(nargout, out, nargin-1, in+1); - break; - case 21: - gtsamPoint3_norm_21(nargout, out, nargin-1, in+1); - break; - case 22: - gtsamPoint3_string_serialize_22(nargout, out, nargin-1, in+1); - break; - case 23: - gtsamPoint3_StaticFunctionRet_23(nargout, out, nargin-1, in+1); - break; - case 24: - gtsamPoint3_staticFunction_24(nargout, out, nargin-1, in+1); - break; - case 25: - gtsamPoint3_string_deserialize_25(nargout, out, nargin-1, in+1); - break; - case 26: - Test_collectorInsertAndMakeBase_26(nargout, out, nargin-1, in+1); - break; - case 27: - Test_constructor_27(nargout, out, nargin-1, in+1); - break; - case 28: - Test_constructor_28(nargout, out, nargin-1, in+1); - break; - case 29: - Test_deconstructor_29(nargout, out, nargin-1, in+1); - break; - case 30: - Test_arg_EigenConstRef_30(nargout, out, nargin-1, in+1); - break; - case 31: - Test_create_MixedPtrs_31(nargout, out, nargin-1, in+1); - break; - case 32: - Test_create_ptrs_32(nargout, out, nargin-1, in+1); - break; - case 33: - Test_print_33(nargout, out, nargin-1, in+1); - break; - case 34: - Test_return_Point2Ptr_34(nargout, out, nargin-1, in+1); - break; - case 35: - Test_return_Test_35(nargout, out, nargin-1, in+1); - break; - case 36: - Test_return_TestPtr_36(nargout, out, nargin-1, in+1); - break; - case 37: - Test_return_bool_37(nargout, out, nargin-1, in+1); - break; - case 38: - Test_return_double_38(nargout, out, nargin-1, in+1); - break; - case 39: - Test_return_field_39(nargout, out, nargin-1, in+1); - break; - case 40: - Test_return_int_40(nargout, out, nargin-1, in+1); - break; - case 41: - Test_return_matrix1_41(nargout, out, nargin-1, in+1); - break; - case 42: - Test_return_matrix2_42(nargout, out, nargin-1, in+1); - break; - case 43: - Test_return_pair_43(nargout, out, nargin-1, in+1); - break; - case 44: - Test_return_pair_44(nargout, out, nargin-1, in+1); - break; - case 45: - Test_return_ptrs_45(nargout, out, nargin-1, in+1); - break; - case 46: - Test_return_size_t_46(nargout, out, nargin-1, in+1); - break; - case 47: - Test_return_string_47(nargout, out, nargin-1, in+1); - break; - case 48: - Test_return_vector1_48(nargout, out, nargin-1, in+1); - break; - case 49: - Test_return_vector2_49(nargout, out, nargin-1, in+1); - break; - case 50: - MyBase_collectorInsertAndMakeBase_50(nargout, out, nargin-1, in+1); - break; - case 51: - MyBase_upcastFromVoid_51(nargout, out, nargin-1, in+1); - break; - case 52: - MyBase_deconstructor_52(nargout, out, nargin-1, in+1); - break; - case 53: - MyTemplatePoint2_collectorInsertAndMakeBase_53(nargout, out, nargin-1, in+1); - break; - case 54: - MyTemplatePoint2_upcastFromVoid_54(nargout, out, nargin-1, in+1); - break; - case 55: - MyTemplatePoint2_constructor_55(nargout, out, nargin-1, in+1); - break; - case 56: - MyTemplatePoint2_deconstructor_56(nargout, out, nargin-1, in+1); - break; - case 57: - MyTemplatePoint2_accept_T_57(nargout, out, nargin-1, in+1); - break; - case 58: - MyTemplatePoint2_accept_Tptr_58(nargout, out, nargin-1, in+1); - break; - case 59: - MyTemplatePoint2_create_MixedPtrs_59(nargout, out, nargin-1, in+1); - break; - case 60: - MyTemplatePoint2_create_ptrs_60(nargout, out, nargin-1, in+1); - break; - case 61: - MyTemplatePoint2_return_T_61(nargout, out, nargin-1, in+1); - break; - case 62: - MyTemplatePoint2_return_Tptr_62(nargout, out, nargin-1, in+1); - break; - case 63: - MyTemplatePoint2_return_ptrs_63(nargout, out, nargin-1, in+1); - break; - case 64: - MyTemplatePoint2_templatedMethod_64(nargout, out, nargin-1, in+1); - break; - case 65: - MyTemplatePoint2_templatedMethod_65(nargout, out, nargin-1, in+1); - break; - case 66: - MyTemplatePoint2_templatedMethod_66(nargout, out, nargin-1, in+1); - break; - case 67: - MyTemplatePoint2_templatedMethod_67(nargout, out, nargin-1, in+1); - break; - case 68: - MyTemplatePoint2_Level_68(nargout, out, nargin-1, in+1); - break; - case 69: - MyTemplateMatrix_collectorInsertAndMakeBase_69(nargout, out, nargin-1, in+1); - break; - case 70: - MyTemplateMatrix_upcastFromVoid_70(nargout, out, nargin-1, in+1); - break; - case 71: - MyTemplateMatrix_constructor_71(nargout, out, nargin-1, in+1); - break; - case 72: - MyTemplateMatrix_deconstructor_72(nargout, out, nargin-1, in+1); - break; - case 73: - MyTemplateMatrix_accept_T_73(nargout, out, nargin-1, in+1); - break; - case 74: - MyTemplateMatrix_accept_Tptr_74(nargout, out, nargin-1, in+1); - break; - case 75: - MyTemplateMatrix_create_MixedPtrs_75(nargout, out, nargin-1, in+1); - break; - case 76: - MyTemplateMatrix_create_ptrs_76(nargout, out, nargin-1, in+1); - break; - case 77: - MyTemplateMatrix_return_T_77(nargout, out, nargin-1, in+1); - break; - case 78: - MyTemplateMatrix_return_Tptr_78(nargout, out, nargin-1, in+1); - break; - case 79: - MyTemplateMatrix_return_ptrs_79(nargout, out, nargin-1, in+1); - break; - case 80: - MyTemplateMatrix_templatedMethod_80(nargout, out, nargin-1, in+1); - break; - case 81: - MyTemplateMatrix_templatedMethod_81(nargout, out, nargin-1, in+1); - break; - case 82: - MyTemplateMatrix_templatedMethod_82(nargout, out, nargin-1, in+1); - break; - case 83: - MyTemplateMatrix_templatedMethod_83(nargout, out, nargin-1, in+1); - break; - case 84: - MyTemplateMatrix_Level_84(nargout, out, nargin-1, in+1); - break; - case 85: - PrimitiveRefDouble_collectorInsertAndMakeBase_85(nargout, out, nargin-1, in+1); - break; - case 86: - PrimitiveRefDouble_constructor_86(nargout, out, nargin-1, in+1); - break; - case 87: - PrimitiveRefDouble_deconstructor_87(nargout, out, nargin-1, in+1); - break; - case 88: - PrimitiveRefDouble_Brutal_88(nargout, out, nargin-1, in+1); - break; - case 89: - MyVector3_collectorInsertAndMakeBase_89(nargout, out, nargin-1, in+1); - break; - case 90: - MyVector3_constructor_90(nargout, out, nargin-1, in+1); - break; - case 91: - MyVector3_deconstructor_91(nargout, out, nargin-1, in+1); - break; - case 92: - MyVector12_collectorInsertAndMakeBase_92(nargout, out, nargin-1, in+1); - break; - case 93: - MyVector12_constructor_93(nargout, out, nargin-1, in+1); - break; - case 94: - MyVector12_deconstructor_94(nargout, out, nargin-1, in+1); - break; - case 95: - MultipleTemplatesIntDouble_collectorInsertAndMakeBase_95(nargout, out, nargin-1, in+1); - break; - case 96: - MultipleTemplatesIntDouble_deconstructor_96(nargout, out, nargin-1, in+1); - break; - case 97: - MultipleTemplatesIntFloat_collectorInsertAndMakeBase_97(nargout, out, nargin-1, in+1); - break; - case 98: - MultipleTemplatesIntFloat_deconstructor_98(nargout, out, nargin-1, in+1); - break; - case 99: - MyFactorPosePoint2_collectorInsertAndMakeBase_99(nargout, out, nargin-1, in+1); - break; - case 100: - MyFactorPosePoint2_constructor_100(nargout, out, nargin-1, in+1); - break; - case 101: - MyFactorPosePoint2_deconstructor_101(nargout, out, nargin-1, in+1); - break; - case 102: - load2D_102(nargout, out, nargin-1, in+1); - break; - case 103: - load2D_103(nargout, out, nargin-1, in+1); - break; - case 104: - load2D_104(nargout, out, nargin-1, in+1); - break; - case 105: - aGlobalFunction_105(nargout, out, nargin-1, in+1); - break; - case 106: - overloadedGlobalFunction_106(nargout, out, nargin-1, in+1); - break; - case 107: - overloadedGlobalFunction_107(nargout, out, nargin-1, in+1); - break; - case 108: - MultiTemplatedFunctionStringSize_tDouble_108(nargout, out, nargin-1, in+1); - break; - case 109: - MultiTemplatedFunctionDoubleSize_tDouble_109(nargout, out, nargin-1, in+1); - break; - case 110: - TemplatedFunctionRot3_110(nargout, out, nargin-1, in+1); - break; - } - } catch(const std::exception& e) { - mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str()); - } - - std::cout.rdbuf(outbuf); -} diff --git a/tests/expected-python/geometry_pybind.cpp b/tests/expected-python/geometry_pybind.cpp deleted file mode 100644 index 7aa150d30..000000000 --- a/tests/expected-python/geometry_pybind.cpp +++ /dev/null @@ -1,157 +0,0 @@ - - -#include -#include -#include -#include "gtsam/nonlinear/utilities.h" // for RedirectCout. - -#include "gtsam/geometry/Point2.h" -#include "gtsam/geometry/Point3.h" -#include "folder/path/to/Test.h" - -#include "wrap/serialization.h" -#include - -BOOST_CLASS_EXPORT(gtsam::Point2) -BOOST_CLASS_EXPORT(gtsam::Point3) - - - - -using namespace std; - -namespace py = pybind11; - -PYBIND11_MODULE(geometry_py, m_) { - m_.doc() = "pybind11 wrapper of geometry_py"; - - pybind11::module m_gtsam = m_.def_submodule("gtsam", "gtsam submodule"); - - py::class_>(m_gtsam, "Point2") - .def(py::init<>()) - .def(py::init(), py::arg("x"), py::arg("y")) - .def("x",[](gtsam::Point2* self){return self->x();}) - .def("y",[](gtsam::Point2* self){return self->y();}) - .def("dim",[](gtsam::Point2* self){return self->dim();}) - .def("returnChar",[](gtsam::Point2* self){return self->returnChar();}) - .def("argChar",[](gtsam::Point2* self, char a){ self->argChar(a);}, py::arg("a")) - .def("argChar",[](gtsam::Point2* self, std::shared_ptr& a){ self->argChar(a);}, py::arg("a")) - .def("argChar",[](gtsam::Point2* self, char& a){ self->argChar(a);}, py::arg("a")) - .def("argChar",[](gtsam::Point2* self, char* a){ self->argChar(a);}, py::arg("a")) - .def("argChar",[](gtsam::Point2* self, const std::shared_ptr& a){ self->argChar(a);}, py::arg("a")) - .def("argChar",[](gtsam::Point2* self, const char& a){ self->argChar(a);}, py::arg("a")) - .def("argChar",[](gtsam::Point2* self, const char* a){ self->argChar(a);}, py::arg("a")) - .def("argUChar",[](gtsam::Point2* self, unsigned char a){ self->argUChar(a);}, py::arg("a")) - .def("eigenArguments",[](gtsam::Point2* self, const gtsam::Vector& v, const gtsam::Matrix& m){ self->eigenArguments(v, m);}, py::arg("v"), py::arg("m")) - .def("vectorConfusion",[](gtsam::Point2* self){return self->vectorConfusion();}) - .def("serialize", [](gtsam::Point2* self){ return gtsam::serialize(*self); }) - .def("deserialize", [](gtsam::Point2* self, string serialized){ gtsam::deserialize(serialized, *self); }, py::arg("serialized")) - .def(py::pickle( - [](const gtsam::Point2 &a){ /* __getstate__: Returns a string that encodes the state of the object */ return py::make_tuple(gtsam::serialize(a)); }, - [](py::tuple t){ /* __setstate__ */ gtsam::Point2 obj; gtsam::deserialize(t[0].cast(), obj); return obj; })); - - py::class_>(m_gtsam, "Point3") - .def(py::init(), py::arg("x"), py::arg("y"), py::arg("z")) - .def("norm",[](gtsam::Point3* self){return self->norm();}) - .def("serialize", [](gtsam::Point3* self){ return gtsam::serialize(*self); }) - .def("deserialize", [](gtsam::Point3* self, string serialized){ gtsam::deserialize(serialized, *self); }, py::arg("serialized")) - .def(py::pickle( - [](const gtsam::Point3 &a){ /* __getstate__: Returns a string that encodes the state of the object */ return py::make_tuple(gtsam::serialize(a)); }, - [](py::tuple t){ /* __setstate__ */ gtsam::Point3 obj; gtsam::deserialize(t[0].cast(), obj); return obj; })) - .def_static("staticFunction",[](){return gtsam::Point3::staticFunction();}) - .def_static("StaticFunctionRet",[](double z){return gtsam::Point3::StaticFunctionRet(z);}, py::arg("z")); - - py::class_>(m_, "Test") - .def(py::init<>()) - .def(py::init(), py::arg("a"), py::arg("b")) - .def("return_pair",[](Test* self, const gtsam::Vector& v, const gtsam::Matrix& A){return self->return_pair(v, A);}, py::arg("v"), py::arg("A")) - .def("return_pair",[](Test* self, const gtsam::Vector& v){return self->return_pair(v);}, py::arg("v")) - .def("return_bool",[](Test* self, bool value){return self->return_bool(value);}, py::arg("value")) - .def("return_size_t",[](Test* self, size_t value){return self->return_size_t(value);}, py::arg("value")) - .def("return_int",[](Test* self, int value){return self->return_int(value);}, py::arg("value")) - .def("return_double",[](Test* self, double value){return self->return_double(value);}, py::arg("value")) - .def("return_string",[](Test* self, string value){return self->return_string(value);}, py::arg("value")) - .def("return_vector1",[](Test* self, const gtsam::Vector& value){return self->return_vector1(value);}, py::arg("value")) - .def("return_matrix1",[](Test* self, const gtsam::Matrix& value){return self->return_matrix1(value);}, py::arg("value")) - .def("return_vector2",[](Test* self, const gtsam::Vector& value){return self->return_vector2(value);}, py::arg("value")) - .def("return_matrix2",[](Test* self, const gtsam::Matrix& value){return self->return_matrix2(value);}, py::arg("value")) - .def("arg_EigenConstRef",[](Test* self, const gtsam::Matrix& value){ self->arg_EigenConstRef(value);}, py::arg("value")) - .def("return_field",[](Test* self, const Test& t){return self->return_field(t);}, py::arg("t")) - .def("return_TestPtr",[](Test* self, const std::shared_ptr& value){return self->return_TestPtr(value);}, py::arg("value")) - .def("return_Test",[](Test* self, std::shared_ptr& value){return self->return_Test(value);}, py::arg("value")) - .def("return_Point2Ptr",[](Test* self, bool value){return self->return_Point2Ptr(value);}, py::arg("value")) - .def("create_ptrs",[](Test* self){return self->create_ptrs();}) - .def("create_MixedPtrs",[](Test* self){return self->create_MixedPtrs();}) - .def("return_ptrs",[](Test* self, std::shared_ptr& p1, std::shared_ptr& p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2")) - .def("print_",[](Test* self){ self->print();}) - .def("__repr__", - [](const Test &a) { - gtsam::RedirectCout redirect; - a.print(); - return redirect.str(); - }) - .def_readwrite("model_ptr", &Test::model_ptr); - - py::class_>(m_, "MyBase"); - - py::class_, MyBase, std::shared_ptr>>(m_, "MyTemplatePoint2") - .def(py::init<>()) - .def("templatedMethodPoint2",[](MyTemplate* self, const gtsam::Point2& t){return self->templatedMethod(t);}, py::arg("t")) - .def("templatedMethodPoint3",[](MyTemplate* self, const gtsam::Point3& t){return self->templatedMethod(t);}, py::arg("t")) - .def("templatedMethodVector",[](MyTemplate* self, const gtsam::Vector& t){return self->templatedMethod(t);}, py::arg("t")) - .def("templatedMethodMatrix",[](MyTemplate* self, const gtsam::Matrix& t){return self->templatedMethod(t);}, py::arg("t")) - .def("accept_T",[](MyTemplate* self, const gtsam::Point2& value){ self->accept_T(value);}, py::arg("value")) - .def("accept_Tptr",[](MyTemplate* self, std::shared_ptr& value){ self->accept_Tptr(value);}, py::arg("value")) - .def("return_Tptr",[](MyTemplate* self, std::shared_ptr& value){return self->return_Tptr(value);}, py::arg("value")) - .def("return_T",[](MyTemplate* self, gtsam::Point2* value){return self->return_T(value);}, py::arg("value")) - .def("create_ptrs",[](MyTemplate* self){return self->create_ptrs();}) - .def("create_MixedPtrs",[](MyTemplate* self){return self->create_MixedPtrs();}) - .def("return_ptrs",[](MyTemplate* self, std::shared_ptr& p1, std::shared_ptr& p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2")) - .def_static("Level",[](const gtsam::Point2& K){return MyTemplate::Level(K);}, py::arg("K")); - - py::class_, MyBase, std::shared_ptr>>(m_, "MyTemplateMatrix") - .def(py::init<>()) - .def("templatedMethodPoint2",[](MyTemplate* self, const gtsam::Point2& t){return self->templatedMethod(t);}, py::arg("t")) - .def("templatedMethodPoint3",[](MyTemplate* self, const gtsam::Point3& t){return self->templatedMethod(t);}, py::arg("t")) - .def("templatedMethodVector",[](MyTemplate* self, const gtsam::Vector& t){return self->templatedMethod(t);}, py::arg("t")) - .def("templatedMethodMatrix",[](MyTemplate* self, const gtsam::Matrix& t){return self->templatedMethod(t);}, py::arg("t")) - .def("accept_T",[](MyTemplate* self, const gtsam::Matrix& value){ self->accept_T(value);}, py::arg("value")) - .def("accept_Tptr",[](MyTemplate* self, const std::shared_ptr& value){ self->accept_Tptr(value);}, py::arg("value")) - .def("return_Tptr",[](MyTemplate* self, const std::shared_ptr& value){return self->return_Tptr(value);}, py::arg("value")) - .def("return_T",[](MyTemplate* self, const gtsam::Matrix* value){return self->return_T(value);}, py::arg("value")) - .def("create_ptrs",[](MyTemplate* self){return self->create_ptrs();}) - .def("create_MixedPtrs",[](MyTemplate* self){return self->create_MixedPtrs();}) - .def("return_ptrs",[](MyTemplate* self, const std::shared_ptr& p1, const std::shared_ptr& p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2")) - .def_static("Level",[](const gtsam::Matrix& K){return MyTemplate::Level(K);}, py::arg("K")); - - py::class_, std::shared_ptr>>(m_, "PrimitiveRefDouble") - .def(py::init<>()) - .def_static("Brutal",[](const double& t){return PrimitiveRef::Brutal(t);}, py::arg("t")); - - py::class_, std::shared_ptr>>(m_, "MyVector3") - .def(py::init<>()); - - py::class_, std::shared_ptr>>(m_, "MyVector12") - .def(py::init<>()); - - py::class_, std::shared_ptr>>(m_, "MultipleTemplatesIntDouble"); - - py::class_, std::shared_ptr>>(m_, "MultipleTemplatesIntFloat"); - - py::class_, std::shared_ptr>>(m_, "MyFactorPosePoint2") - .def(py::init&>(), py::arg("key1"), py::arg("key2"), py::arg("measured"), py::arg("noiseModel")); - - m_.def("load2D",[](string filename, std::shared_ptr& model, int maxID, bool addNoise, bool smart){return ::load2D(filename, model, maxID, addNoise, smart);}, py::arg("filename"), py::arg("model"), py::arg("maxID"), py::arg("addNoise"), py::arg("smart")); - m_.def("load2D",[](string filename, const std::shared_ptr& model, int maxID, bool addNoise, bool smart){return ::load2D(filename, model, maxID, addNoise, smart);}, py::arg("filename"), py::arg("model"), py::arg("maxID"), py::arg("addNoise"), py::arg("smart")); - m_.def("load2D",[](string filename, gtsam::noiseModel::Diagonal* model){return ::load2D(filename, model);}, py::arg("filename"), py::arg("model")); - m_.def("aGlobalFunction",[](){return ::aGlobalFunction();}); - m_.def("overloadedGlobalFunction",[](int a){return ::overloadedGlobalFunction(a);}, py::arg("a")); - m_.def("overloadedGlobalFunction",[](int a, double b){return ::overloadedGlobalFunction(a, b);}, py::arg("a"), py::arg("b")); - m_.def("MultiTemplatedFunctionStringSize_tDouble",[](const T& x, size_t y){return ::MultiTemplatedFunction(x, y);}, py::arg("x"), py::arg("y")); - m_.def("MultiTemplatedFunctionDoubleSize_tDouble",[](const T& x, size_t y){return ::MultiTemplatedFunction(x, y);}, py::arg("x"), py::arg("y")); - m_.def("TemplatedFunctionRot3",[](const gtsam::Rot3& t){ ::TemplatedFunction(t);}, py::arg("t")); - -#include "python/specializations.h" - -} - diff --git a/tests/expected-matlab/+gtsam/Point2.m b/tests/expected/matlab/+gtsam/Point2.m similarity index 100% rename from tests/expected-matlab/+gtsam/Point2.m rename to tests/expected/matlab/+gtsam/Point2.m diff --git a/tests/expected-matlab/+gtsam/Point3.m b/tests/expected/matlab/+gtsam/Point3.m similarity index 100% rename from tests/expected-matlab/+gtsam/Point3.m rename to tests/expected/matlab/+gtsam/Point3.m diff --git a/tests/expected/matlab/+ns1/ClassA.m b/tests/expected/matlab/+ns1/ClassA.m new file mode 100644 index 000000000..12ebc0d70 --- /dev/null +++ b/tests/expected/matlab/+ns1/ClassA.m @@ -0,0 +1,36 @@ +%class ClassA, see Doxygen page for details +%at https://gtsam.org/doxygen/ +% +%-------Constructors------- +%ClassA() +% +classdef ClassA < handle + properties + ptr_ns1ClassA = 0 + end + methods + function obj = ClassA(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + namespaces_wrapper(0, my_ptr); + elseif nargin == 0 + my_ptr = namespaces_wrapper(1); + else + error('Arguments do not match any overload of ns1.ClassA constructor'); + end + obj.ptr_ns1ClassA = my_ptr; + end + + function delete(obj) + namespaces_wrapper(2, obj.ptr_ns1ClassA); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + end + + methods(Static = true) + end +end diff --git a/tests/expected/matlab/+ns1/ClassB.m b/tests/expected/matlab/+ns1/ClassB.m new file mode 100644 index 000000000..837f67fe6 --- /dev/null +++ b/tests/expected/matlab/+ns1/ClassB.m @@ -0,0 +1,36 @@ +%class ClassB, see Doxygen page for details +%at https://gtsam.org/doxygen/ +% +%-------Constructors------- +%ClassB() +% +classdef ClassB < handle + properties + ptr_ns1ClassB = 0 + end + methods + function obj = ClassB(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + namespaces_wrapper(3, my_ptr); + elseif nargin == 0 + my_ptr = namespaces_wrapper(4); + else + error('Arguments do not match any overload of ns1.ClassB constructor'); + end + obj.ptr_ns1ClassB = my_ptr; + end + + function delete(obj) + namespaces_wrapper(5, obj.ptr_ns1ClassB); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + end + + methods(Static = true) + end +end diff --git a/tests/expected-matlab/aGlobalFunction.m b/tests/expected/matlab/+ns1/aGlobalFunction.m similarity index 75% rename from tests/expected-matlab/aGlobalFunction.m rename to tests/expected/matlab/+ns1/aGlobalFunction.m index d262d9ed0..b57f727bd 100644 --- a/tests/expected-matlab/aGlobalFunction.m +++ b/tests/expected/matlab/+ns1/aGlobalFunction.m @@ -1,6 +1,6 @@ function varargout = aGlobalFunction(varargin) if length(varargin) == 0 - varargout{1} = geometry_wrapper(105, varargin{:}); + varargout{1} = namespaces_wrapper(6, varargin{:}); else error('Arguments do not match any overload of function aGlobalFunction'); end diff --git a/tests/expected/matlab/+ns2/+ns3/ClassB.m b/tests/expected/matlab/+ns2/+ns3/ClassB.m new file mode 100644 index 000000000..6f105a209 --- /dev/null +++ b/tests/expected/matlab/+ns2/+ns3/ClassB.m @@ -0,0 +1,36 @@ +%class ClassB, see Doxygen page for details +%at https://gtsam.org/doxygen/ +% +%-------Constructors------- +%ClassB() +% +classdef ClassB < handle + properties + ptr_ns2ns3ClassB = 0 + end + methods + function obj = ClassB(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + namespaces_wrapper(14, my_ptr); + elseif nargin == 0 + my_ptr = namespaces_wrapper(15); + else + error('Arguments do not match any overload of ns2.ns3.ClassB constructor'); + end + obj.ptr_ns2ns3ClassB = my_ptr; + end + + function delete(obj) + namespaces_wrapper(16, obj.ptr_ns2ns3ClassB); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + end + + methods(Static = true) + end +end diff --git a/tests/expected/matlab/+ns2/ClassA.m b/tests/expected/matlab/+ns2/ClassA.m new file mode 100644 index 000000000..4640e7cca --- /dev/null +++ b/tests/expected/matlab/+ns2/ClassA.m @@ -0,0 +1,89 @@ +%class ClassA, see Doxygen page for details +%at https://gtsam.org/doxygen/ +% +%-------Constructors------- +%ClassA() +% +%-------Methods------- +%memberFunction() : returns double +%nsArg(ClassB arg) : returns int +%nsReturn(double q) : returns ns2::ns3::ClassB +% +%-------Static Methods------- +%afunction() : returns double +% +%-------Serialization Interface------- +%string_serialize() : returns string +%string_deserialize(string serialized) : returns ClassA +% +classdef ClassA < handle + properties + ptr_ns2ClassA = 0 + end + methods + function obj = ClassA(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + namespaces_wrapper(7, my_ptr); + elseif nargin == 0 + my_ptr = namespaces_wrapper(8); + else + error('Arguments do not match any overload of ns2.ClassA constructor'); + end + obj.ptr_ns2ClassA = my_ptr; + end + + function delete(obj) + namespaces_wrapper(9, obj.ptr_ns2ClassA); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + function varargout = memberFunction(this, varargin) + % MEMBERFUNCTION usage: memberFunction() : returns double + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 0 + varargout{1} = namespaces_wrapper(10, this, varargin{:}); + return + end + error('Arguments do not match any overload of function ns2.ClassA.memberFunction'); + end + + function varargout = nsArg(this, varargin) + % NSARG usage: nsArg(ClassB arg) : returns int + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 1 && isa(varargin{1},'ns1.ClassB') + varargout{1} = namespaces_wrapper(11, this, varargin{:}); + return + end + error('Arguments do not match any overload of function ns2.ClassA.nsArg'); + end + + function varargout = nsReturn(this, varargin) + % NSRETURN usage: nsReturn(double q) : returns ns2.ns3.ClassB + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = namespaces_wrapper(12, this, varargin{:}); + return + end + error('Arguments do not match any overload of function ns2.ClassA.nsReturn'); + end + + end + + methods(Static = true) + function varargout = Afunction(varargin) + % AFUNCTION usage: afunction() : returns double + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 0 + varargout{1} = namespaces_wrapper(13, varargin{:}); + return + end + + error('Arguments do not match any overload of function ClassA.afunction'); + end + + end +end diff --git a/tests/expected/matlab/+ns2/ClassC.m b/tests/expected/matlab/+ns2/ClassC.m new file mode 100644 index 000000000..a0267beb5 --- /dev/null +++ b/tests/expected/matlab/+ns2/ClassC.m @@ -0,0 +1,36 @@ +%class ClassC, see Doxygen page for details +%at https://gtsam.org/doxygen/ +% +%-------Constructors------- +%ClassC() +% +classdef ClassC < handle + properties + ptr_ns2ClassC = 0 + end + methods + function obj = ClassC(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + namespaces_wrapper(17, my_ptr); + elseif nargin == 0 + my_ptr = namespaces_wrapper(18); + else + error('Arguments do not match any overload of ns2.ClassC constructor'); + end + obj.ptr_ns2ClassC = my_ptr; + end + + function delete(obj) + namespaces_wrapper(19, obj.ptr_ns2ClassC); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + end + + methods(Static = true) + end +end diff --git a/tests/expected/matlab/+ns2/aGlobalFunction.m b/tests/expected/matlab/+ns2/aGlobalFunction.m new file mode 100644 index 000000000..b8c5a339b --- /dev/null +++ b/tests/expected/matlab/+ns2/aGlobalFunction.m @@ -0,0 +1,6 @@ +function varargout = aGlobalFunction(varargin) + if length(varargin) == 0 + varargout{1} = namespaces_wrapper(20, varargin{:}); + else + error('Arguments do not match any overload of function aGlobalFunction'); + end diff --git a/tests/expected/matlab/+ns2/overloadedGlobalFunction.m b/tests/expected/matlab/+ns2/overloadedGlobalFunction.m new file mode 100644 index 000000000..2ba3a9c74 --- /dev/null +++ b/tests/expected/matlab/+ns2/overloadedGlobalFunction.m @@ -0,0 +1,8 @@ +function varargout = overloadedGlobalFunction(varargin) + if length(varargin) == 1 && isa(varargin{1},'ns1.ClassA') + varargout{1} = namespaces_wrapper(21, varargin{:}); + elseif length(varargin) == 2 && isa(varargin{1},'ns1.ClassA') && isa(varargin{2},'double') + varargout{1} = namespaces_wrapper(22, varargin{:}); + else + error('Arguments do not match any overload of function overloadedGlobalFunction'); + end diff --git a/tests/expected/matlab/ClassD.m b/tests/expected/matlab/ClassD.m new file mode 100644 index 000000000..890839677 --- /dev/null +++ b/tests/expected/matlab/ClassD.m @@ -0,0 +1,36 @@ +%class ClassD, see Doxygen page for details +%at https://gtsam.org/doxygen/ +% +%-------Constructors------- +%ClassD() +% +classdef ClassD < handle + properties + ptr_ClassD = 0 + end + methods + function obj = ClassD(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + namespaces_wrapper(23, my_ptr); + elseif nargin == 0 + my_ptr = namespaces_wrapper(24); + else + error('Arguments do not match any overload of ClassD constructor'); + end + obj.ptr_ClassD = my_ptr; + end + + function delete(obj) + namespaces_wrapper(25, obj.ptr_ClassD); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + end + + methods(Static = true) + end +end diff --git a/tests/expected/matlab/FunDouble.m b/tests/expected/matlab/FunDouble.m new file mode 100644 index 000000000..b6c57cd0c --- /dev/null +++ b/tests/expected/matlab/FunDouble.m @@ -0,0 +1,62 @@ +%class FunDouble, see Doxygen page for details +%at https://gtsam.org/doxygen/ +% +%-------Methods------- +%dhamaalString(double d, string t) : returns Fun +% +%-------Static Methods------- +%divertido() : returns Fun +% +%-------Serialization Interface------- +%string_serialize() : returns string +%string_deserialize(string serialized) : returns FunDouble +% +classdef FunDouble < handle + properties + ptr_FunDouble = 0 + end + methods + function obj = FunDouble(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + class_wrapper(5, my_ptr); + else + error('Arguments do not match any overload of FunDouble constructor'); + end + obj.ptr_FunDouble = my_ptr; + end + + function delete(obj) + class_wrapper(6, obj.ptr_FunDouble); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + function varargout = dhamaalString(this, varargin) + % DHAMAALSTRING usage: dhamaalString(double d, string t) : returns Fun + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 2 && isa(varargin{1},'double') && isa(varargin{2},'char') + varargout{1} = class_wrapper(7, this, varargin{:}); + return + end + error('Arguments do not match any overload of function FunDouble.dhamaalString'); + end + + end + + methods(Static = true) + function varargout = Divertido(varargin) + % DIVERTIDO usage: divertido() : returns Fundouble + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 0 + varargout{1} = class_wrapper(8, varargin{:}); + return + end + + error('Arguments do not match any overload of function FunDouble.divertido'); + end + + end +end diff --git a/tests/expected/matlab/FunRange.m b/tests/expected/matlab/FunRange.m new file mode 100644 index 000000000..1d1a6f7b8 --- /dev/null +++ b/tests/expected/matlab/FunRange.m @@ -0,0 +1,67 @@ +%class FunRange, see Doxygen page for details +%at https://gtsam.org/doxygen/ +% +%-------Constructors------- +%FunRange() +% +%-------Methods------- +%range(double d) : returns FunRange +% +%-------Static Methods------- +%create() : returns FunRange +% +%-------Serialization Interface------- +%string_serialize() : returns string +%string_deserialize(string serialized) : returns FunRange +% +classdef FunRange < handle + properties + ptr_FunRange = 0 + end + methods + function obj = FunRange(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + class_wrapper(0, my_ptr); + elseif nargin == 0 + my_ptr = class_wrapper(1); + else + error('Arguments do not match any overload of FunRange constructor'); + end + obj.ptr_FunRange = my_ptr; + end + + function delete(obj) + class_wrapper(2, obj.ptr_FunRange); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + function varargout = range(this, varargin) + % RANGE usage: range(double d) : returns FunRange + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 1 && isa(varargin{1},'double') + varargout{1} = class_wrapper(3, this, varargin{:}); + return + end + error('Arguments do not match any overload of function FunRange.range'); + end + + end + + methods(Static = true) + function varargout = Create(varargin) + % CREATE usage: create() : returns FunRange + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 0 + varargout{1} = class_wrapper(4, varargin{:}); + return + end + + error('Arguments do not match any overload of function FunRange.create'); + end + + end +end diff --git a/tests/expected/matlab/MultiTemplatedFunctionDoubleSize_tDouble.m b/tests/expected/matlab/MultiTemplatedFunctionDoubleSize_tDouble.m new file mode 100644 index 000000000..e106ad4d2 --- /dev/null +++ b/tests/expected/matlab/MultiTemplatedFunctionDoubleSize_tDouble.m @@ -0,0 +1,6 @@ +function varargout = MultiTemplatedFunctionDoubleSize_tDouble(varargin) + if length(varargin) == 2 && isa(varargin{1},'T') && isa(varargin{2},'numeric') + varargout{1} = functions_wrapper(7, varargin{:}); + else + error('Arguments do not match any overload of function MultiTemplatedFunctionDoubleSize_tDouble'); + end diff --git a/tests/expected/matlab/MultiTemplatedFunctionStringSize_tDouble.m b/tests/expected/matlab/MultiTemplatedFunctionStringSize_tDouble.m new file mode 100644 index 000000000..70557f3aa --- /dev/null +++ b/tests/expected/matlab/MultiTemplatedFunctionStringSize_tDouble.m @@ -0,0 +1,6 @@ +function varargout = MultiTemplatedFunctionStringSize_tDouble(varargin) + if length(varargin) == 2 && isa(varargin{1},'T') && isa(varargin{2},'numeric') + varargout{1} = functions_wrapper(6, varargin{:}); + else + error('Arguments do not match any overload of function MultiTemplatedFunctionStringSize_tDouble'); + end diff --git a/tests/expected-matlab/MultipleTemplatesIntDouble.m b/tests/expected/matlab/MultipleTemplatesIntDouble.m similarity index 88% rename from tests/expected-matlab/MultipleTemplatesIntDouble.m rename to tests/expected/matlab/MultipleTemplatesIntDouble.m index d5a27b199..bea6a3e6c 100644 --- a/tests/expected-matlab/MultipleTemplatesIntDouble.m +++ b/tests/expected/matlab/MultipleTemplatesIntDouble.m @@ -9,7 +9,7 @@ classdef MultipleTemplatesIntDouble < handle function obj = MultipleTemplatesIntDouble(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - geometry_wrapper(89, my_ptr); + class_wrapper(43, my_ptr); else error('Arguments do not match any overload of MultipleTemplatesIntDouble constructor'); end @@ -17,7 +17,7 @@ classdef MultipleTemplatesIntDouble < handle end function delete(obj) - geometry_wrapper(90, obj.ptr_MultipleTemplatesIntDouble); + class_wrapper(44, obj.ptr_MultipleTemplatesIntDouble); end function display(obj), obj.print(''); end diff --git a/tests/expected-matlab/MultipleTemplatesIntFloat.m b/tests/expected/matlab/MultipleTemplatesIntFloat.m similarity index 88% rename from tests/expected-matlab/MultipleTemplatesIntFloat.m rename to tests/expected/matlab/MultipleTemplatesIntFloat.m index 0434c6c79..8c09e1685 100644 --- a/tests/expected-matlab/MultipleTemplatesIntFloat.m +++ b/tests/expected/matlab/MultipleTemplatesIntFloat.m @@ -9,7 +9,7 @@ classdef MultipleTemplatesIntFloat < handle function obj = MultipleTemplatesIntFloat(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - geometry_wrapper(91, my_ptr); + class_wrapper(45, my_ptr); else error('Arguments do not match any overload of MultipleTemplatesIntFloat constructor'); end @@ -17,7 +17,7 @@ classdef MultipleTemplatesIntFloat < handle end function delete(obj) - geometry_wrapper(92, obj.ptr_MultipleTemplatesIntFloat); + class_wrapper(46, obj.ptr_MultipleTemplatesIntFloat); end function display(obj), obj.print(''); end diff --git a/tests/expected-matlab/MyBase.m b/tests/expected/matlab/MyBase.m similarity index 84% rename from tests/expected-matlab/MyBase.m rename to tests/expected/matlab/MyBase.m index 57654626f..2691677a9 100644 --- a/tests/expected-matlab/MyBase.m +++ b/tests/expected/matlab/MyBase.m @@ -11,9 +11,9 @@ classdef MyBase < handle if nargin == 2 my_ptr = varargin{2}; else - my_ptr = geometry_wrapper(51, varargin{2}); + my_ptr = inheritance_wrapper(1, varargin{2}); end - geometry_wrapper(50, my_ptr); + inheritance_wrapper(0, my_ptr); else error('Arguments do not match any overload of MyBase constructor'); end @@ -21,7 +21,7 @@ classdef MyBase < handle end function delete(obj) - geometry_wrapper(52, obj.ptr_MyBase); + inheritance_wrapper(2, obj.ptr_MyBase); end function display(obj), obj.print(''); end diff --git a/tests/expected-matlab/MyFactorPosePoint2.m b/tests/expected/matlab/MyFactorPosePoint2.m similarity index 84% rename from tests/expected-matlab/MyFactorPosePoint2.m rename to tests/expected/matlab/MyFactorPosePoint2.m index 3466e9291..22eb3aaa9 100644 --- a/tests/expected-matlab/MyFactorPosePoint2.m +++ b/tests/expected/matlab/MyFactorPosePoint2.m @@ -12,9 +12,9 @@ classdef MyFactorPosePoint2 < handle function obj = MyFactorPosePoint2(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - geometry_wrapper(99, my_ptr); + class_wrapper(47, my_ptr); elseif nargin == 4 && isa(varargin{1},'numeric') && isa(varargin{2},'numeric') && isa(varargin{3},'double') && isa(varargin{4},'gtsam.noiseModel.Base') - my_ptr = geometry_wrapper(100, varargin{1}, varargin{2}, varargin{3}, varargin{4}); + my_ptr = class_wrapper(48, varargin{1}, varargin{2}, varargin{3}, varargin{4}); else error('Arguments do not match any overload of MyFactorPosePoint2 constructor'); end @@ -22,7 +22,7 @@ classdef MyFactorPosePoint2 < handle end function delete(obj) - geometry_wrapper(101, obj.ptr_MyFactorPosePoint2); + class_wrapper(49, obj.ptr_MyFactorPosePoint2); end function display(obj), obj.print(''); end diff --git a/tests/expected-matlab/MyTemplateMatrix.m b/tests/expected/matlab/MyTemplateMatrix.m similarity index 86% rename from tests/expected-matlab/MyTemplateMatrix.m rename to tests/expected/matlab/MyTemplateMatrix.m index 839b3809e..03ec7b741 100644 --- a/tests/expected-matlab/MyTemplateMatrix.m +++ b/tests/expected/matlab/MyTemplateMatrix.m @@ -34,11 +34,11 @@ classdef MyTemplateMatrix < MyBase if nargin == 2 my_ptr = varargin{2}; else - my_ptr = geometry_wrapper(70, varargin{2}); + my_ptr = inheritance_wrapper(20, varargin{2}); end - base_ptr = geometry_wrapper(69, my_ptr); + base_ptr = inheritance_wrapper(19, my_ptr); elseif nargin == 0 - [ my_ptr, base_ptr ] = geometry_wrapper(71); + [ my_ptr, base_ptr ] = inheritance_wrapper(21); else error('Arguments do not match any overload of MyTemplateMatrix constructor'); end @@ -47,7 +47,7 @@ classdef MyTemplateMatrix < MyBase end function delete(obj) - geometry_wrapper(72, obj.ptr_MyTemplateMatrix); + inheritance_wrapper(22, obj.ptr_MyTemplateMatrix); end function display(obj), obj.print(''); end @@ -58,7 +58,7 @@ classdef MyTemplateMatrix < MyBase % ACCEPT_T usage: accept_T(Matrix value) : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - geometry_wrapper(73, this, varargin{:}); + inheritance_wrapper(23, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.accept_T'); @@ -68,7 +68,7 @@ classdef MyTemplateMatrix < MyBase % ACCEPT_TPTR usage: accept_Tptr(Matrix value) : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - geometry_wrapper(74, this, varargin{:}); + inheritance_wrapper(24, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.accept_Tptr'); @@ -78,7 +78,7 @@ classdef MyTemplateMatrix < MyBase % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Matrix, Matrix > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(75, this, varargin{:}); + [ varargout{1} varargout{2} ] = inheritance_wrapper(25, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.create_MixedPtrs'); @@ -88,7 +88,7 @@ classdef MyTemplateMatrix < MyBase % CREATE_PTRS usage: create_ptrs() : returns pair< Matrix, Matrix > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(76, this, varargin{:}); + [ varargout{1} varargout{2} ] = inheritance_wrapper(26, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.create_ptrs'); @@ -98,7 +98,7 @@ classdef MyTemplateMatrix < MyBase % RETURN_T usage: return_T(Matrix value) : returns Matrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(77, this, varargin{:}); + varargout{1} = inheritance_wrapper(27, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.return_T'); @@ -108,7 +108,7 @@ classdef MyTemplateMatrix < MyBase % RETURN_TPTR usage: return_Tptr(Matrix value) : returns Matrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(78, this, varargin{:}); + varargout{1} = inheritance_wrapper(28, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.return_Tptr'); @@ -118,7 +118,7 @@ classdef MyTemplateMatrix < MyBase % RETURN_PTRS usage: return_ptrs(Matrix p1, Matrix p2) : returns pair< Matrix, Matrix > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') - [ varargout{1} varargout{2} ] = geometry_wrapper(79, this, varargin{:}); + [ varargout{1} varargout{2} ] = inheritance_wrapper(29, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.return_ptrs'); @@ -128,7 +128,7 @@ classdef MyTemplateMatrix < MyBase % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns Matrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(80, this, varargin{:}); + varargout{1} = inheritance_wrapper(30, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethodMatrix'); @@ -138,7 +138,7 @@ classdef MyTemplateMatrix < MyBase % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns Point2 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(81, this, varargin{:}); + varargout{1} = inheritance_wrapper(31, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethodPoint2'); @@ -148,7 +148,7 @@ classdef MyTemplateMatrix < MyBase % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns Point3 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==3 && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(82, this, varargin{:}); + varargout{1} = inheritance_wrapper(32, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethodPoint3'); @@ -158,7 +158,7 @@ classdef MyTemplateMatrix < MyBase % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns Vector % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(83, this, varargin{:}); + varargout{1} = inheritance_wrapper(33, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplateMatrix.templatedMethodVector'); @@ -171,7 +171,7 @@ classdef MyTemplateMatrix < MyBase % LEVEL usage: Level(Matrix K) : returns MyTemplateMatrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(84, varargin{:}); + varargout{1} = inheritance_wrapper(34, varargin{:}); return end diff --git a/tests/expected-matlab/MyTemplatePoint2.m b/tests/expected/matlab/MyTemplatePoint2.m similarity index 86% rename from tests/expected-matlab/MyTemplatePoint2.m rename to tests/expected/matlab/MyTemplatePoint2.m index 2a73f98da..bf3d37a07 100644 --- a/tests/expected-matlab/MyTemplatePoint2.m +++ b/tests/expected/matlab/MyTemplatePoint2.m @@ -34,11 +34,11 @@ classdef MyTemplatePoint2 < MyBase if nargin == 2 my_ptr = varargin{2}; else - my_ptr = geometry_wrapper(54, varargin{2}); + my_ptr = inheritance_wrapper(4, varargin{2}); end - base_ptr = geometry_wrapper(53, my_ptr); + base_ptr = inheritance_wrapper(3, my_ptr); elseif nargin == 0 - [ my_ptr, base_ptr ] = geometry_wrapper(55); + [ my_ptr, base_ptr ] = inheritance_wrapper(5); else error('Arguments do not match any overload of MyTemplatePoint2 constructor'); end @@ -47,7 +47,7 @@ classdef MyTemplatePoint2 < MyBase end function delete(obj) - geometry_wrapper(56, obj.ptr_MyTemplatePoint2); + inheritance_wrapper(6, obj.ptr_MyTemplatePoint2); end function display(obj), obj.print(''); end @@ -58,7 +58,7 @@ classdef MyTemplatePoint2 < MyBase % ACCEPT_T usage: accept_T(Point2 value) : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 - geometry_wrapper(57, this, varargin{:}); + inheritance_wrapper(7, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.accept_T'); @@ -68,7 +68,7 @@ classdef MyTemplatePoint2 < MyBase % ACCEPT_TPTR usage: accept_Tptr(Point2 value) : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 - geometry_wrapper(58, this, varargin{:}); + inheritance_wrapper(8, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.accept_Tptr'); @@ -78,7 +78,7 @@ classdef MyTemplatePoint2 < MyBase % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Point2, Point2 > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(59, this, varargin{:}); + [ varargout{1} varargout{2} ] = inheritance_wrapper(9, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.create_MixedPtrs'); @@ -88,7 +88,7 @@ classdef MyTemplatePoint2 < MyBase % CREATE_PTRS usage: create_ptrs() : returns pair< Point2, Point2 > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(60, this, varargin{:}); + [ varargout{1} varargout{2} ] = inheritance_wrapper(10, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.create_ptrs'); @@ -98,7 +98,7 @@ classdef MyTemplatePoint2 < MyBase % RETURN_T usage: return_T(Point2 value) : returns Point2 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(61, this, varargin{:}); + varargout{1} = inheritance_wrapper(11, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.return_T'); @@ -108,7 +108,7 @@ classdef MyTemplatePoint2 < MyBase % RETURN_TPTR usage: return_Tptr(Point2 value) : returns Point2 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(62, this, varargin{:}); + varargout{1} = inheritance_wrapper(12, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.return_Tptr'); @@ -118,7 +118,7 @@ classdef MyTemplatePoint2 < MyBase % RETURN_PTRS usage: return_ptrs(Point2 p1, Point2 p2) : returns pair< Point2, Point2 > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 2 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 && isa(varargin{2},'double') && size(varargin{2},1)==2 && size(varargin{2},2)==1 - [ varargout{1} varargout{2} ] = geometry_wrapper(63, this, varargin{:}); + [ varargout{1} varargout{2} ] = inheritance_wrapper(13, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.return_ptrs'); @@ -128,7 +128,7 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODMATRIX usage: templatedMethodMatrix(Matrix t) : returns Matrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(64, this, varargin{:}); + varargout{1} = inheritance_wrapper(14, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethodMatrix'); @@ -138,7 +138,7 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODPOINT2 usage: templatedMethodPoint2(Point2 t) : returns Point2 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(65, this, varargin{:}); + varargout{1} = inheritance_wrapper(15, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethodPoint2'); @@ -148,7 +148,7 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODPOINT3 usage: templatedMethodPoint3(Point3 t) : returns Point3 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==3 && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(66, this, varargin{:}); + varargout{1} = inheritance_wrapper(16, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethodPoint3'); @@ -158,7 +158,7 @@ classdef MyTemplatePoint2 < MyBase % TEMPLATEDMETHODVECTOR usage: templatedMethodVector(Vector t) : returns Vector % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(67, this, varargin{:}); + varargout{1} = inheritance_wrapper(17, this, varargin{:}); return end error('Arguments do not match any overload of function MyTemplatePoint2.templatedMethodVector'); @@ -171,7 +171,7 @@ classdef MyTemplatePoint2 < MyBase % LEVEL usage: Level(Point2 K) : returns MyTemplatePoint2 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},1)==2 && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(68, varargin{:}); + varargout{1} = inheritance_wrapper(18, varargin{:}); return end diff --git a/tests/expected-matlab/MyVector12.m b/tests/expected/matlab/MyVector12.m similarity index 86% rename from tests/expected-matlab/MyVector12.m rename to tests/expected/matlab/MyVector12.m index 0cba5c7c1..df7e73250 100644 --- a/tests/expected-matlab/MyVector12.m +++ b/tests/expected/matlab/MyVector12.m @@ -12,9 +12,9 @@ classdef MyVector12 < handle function obj = MyVector12(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - geometry_wrapper(92, my_ptr); + class_wrapper(40, my_ptr); elseif nargin == 0 - my_ptr = geometry_wrapper(93); + my_ptr = class_wrapper(41); else error('Arguments do not match any overload of MyVector12 constructor'); end @@ -22,7 +22,7 @@ classdef MyVector12 < handle end function delete(obj) - geometry_wrapper(94, obj.ptr_MyVector12); + class_wrapper(42, obj.ptr_MyVector12); end function display(obj), obj.print(''); end diff --git a/tests/expected-matlab/MyVector3.m b/tests/expected/matlab/MyVector3.m similarity index 86% rename from tests/expected-matlab/MyVector3.m rename to tests/expected/matlab/MyVector3.m index a619c5133..10c7ad203 100644 --- a/tests/expected-matlab/MyVector3.m +++ b/tests/expected/matlab/MyVector3.m @@ -12,9 +12,9 @@ classdef MyVector3 < handle function obj = MyVector3(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - geometry_wrapper(89, my_ptr); + class_wrapper(37, my_ptr); elseif nargin == 0 - my_ptr = geometry_wrapper(90); + my_ptr = class_wrapper(38); else error('Arguments do not match any overload of MyVector3 constructor'); end @@ -22,7 +22,7 @@ classdef MyVector3 < handle end function delete(obj) - geometry_wrapper(91, obj.ptr_MyVector3); + class_wrapper(39, obj.ptr_MyVector3); end function display(obj), obj.print(''); end diff --git a/tests/expected-matlab/PrimitiveRefdouble.m b/tests/expected/matlab/PrimitiveRefDouble.m similarity index 66% rename from tests/expected-matlab/PrimitiveRefdouble.m rename to tests/expected/matlab/PrimitiveRefDouble.m index 095c132e2..8a6aca56c 100644 --- a/tests/expected-matlab/PrimitiveRefdouble.m +++ b/tests/expected/matlab/PrimitiveRefDouble.m @@ -1,35 +1,35 @@ -%class PrimitiveRefdouble, see Doxygen page for details +%class PrimitiveRefDouble, see Doxygen page for details %at https://gtsam.org/doxygen/ % %-------Constructors------- -%PrimitiveRefdouble() +%PrimitiveRefDouble() % %-------Static Methods------- %Brutal(double t) : returns PrimitiveRef % %-------Serialization Interface------- %string_serialize() : returns string -%string_deserialize(string serialized) : returns PrimitiveRefdouble +%string_deserialize(string serialized) : returns PrimitiveRefDouble % -classdef PrimitiveRefdouble < handle +classdef PrimitiveRefDouble < handle properties - ptr_PrimitiveRefdouble = 0 + ptr_PrimitiveRefDouble = 0 end methods - function obj = PrimitiveRefdouble(varargin) + function obj = PrimitiveRefDouble(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - geometry_wrapper(79, my_ptr); + class_wrapper(33, my_ptr); elseif nargin == 0 - my_ptr = geometry_wrapper(80); + my_ptr = class_wrapper(34); else - error('Arguments do not match any overload of PrimitiveRefdouble constructor'); + error('Arguments do not match any overload of PrimitiveRefDouble constructor'); end - obj.ptr_PrimitiveRefdouble = my_ptr; + obj.ptr_PrimitiveRefDouble = my_ptr; end function delete(obj) - geometry_wrapper(81, obj.ptr_PrimitiveRefdouble); + class_wrapper(35, obj.ptr_PrimitiveRefDouble); end function display(obj), obj.print(''); end @@ -43,11 +43,11 @@ classdef PrimitiveRefdouble < handle % BRUTAL usage: Brutal(double t) : returns PrimitiveRefdouble % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(82, varargin{:}); + varargout{1} = class_wrapper(36, varargin{:}); return end - error('Arguments do not match any overload of function PrimitiveRefdouble.Brutal'); + error('Arguments do not match any overload of function PrimitiveRefDouble.Brutal'); end end diff --git a/tests/expected/matlab/TemplatedFunctionRot3.m b/tests/expected/matlab/TemplatedFunctionRot3.m new file mode 100644 index 000000000..132db92da --- /dev/null +++ b/tests/expected/matlab/TemplatedFunctionRot3.m @@ -0,0 +1,6 @@ +function varargout = TemplatedFunctionRot3(varargin) + if length(varargin) == 1 && isa(varargin{1},'gtsam.Rot3') + functions_wrapper(8, varargin{:}); + else + error('Arguments do not match any overload of function TemplatedFunctionRot3'); + end diff --git a/tests/expected-matlab/Test.m b/tests/expected/matlab/Test.m similarity index 85% rename from tests/expected-matlab/Test.m rename to tests/expected/matlab/Test.m index d6d375fdf..62a363644 100644 --- a/tests/expected-matlab/Test.m +++ b/tests/expected/matlab/Test.m @@ -35,11 +35,11 @@ classdef Test < handle function obj = Test(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - geometry_wrapper(26, my_ptr); + class_wrapper(9, my_ptr); elseif nargin == 0 - my_ptr = geometry_wrapper(27); + my_ptr = class_wrapper(10); elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') - my_ptr = geometry_wrapper(28, varargin{1}, varargin{2}); + my_ptr = class_wrapper(11, varargin{1}, varargin{2}); else error('Arguments do not match any overload of Test constructor'); end @@ -47,7 +47,7 @@ classdef Test < handle end function delete(obj) - geometry_wrapper(29, obj.ptr_Test); + class_wrapper(12, obj.ptr_Test); end function display(obj), obj.print(''); end @@ -58,7 +58,7 @@ classdef Test < handle % ARG_EIGENCONSTREF usage: arg_EigenConstRef(Matrix value) : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - geometry_wrapper(30, this, varargin{:}); + class_wrapper(13, this, varargin{:}); return end error('Arguments do not match any overload of function Test.arg_EigenConstRef'); @@ -68,7 +68,7 @@ classdef Test < handle % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Test, Test > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(31, this, varargin{:}); + [ varargout{1} varargout{2} ] = class_wrapper(14, this, varargin{:}); return end error('Arguments do not match any overload of function Test.create_MixedPtrs'); @@ -78,7 +78,7 @@ classdef Test < handle % CREATE_PTRS usage: create_ptrs() : returns pair< Test, Test > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - [ varargout{1} varargout{2} ] = geometry_wrapper(32, this, varargin{:}); + [ varargout{1} varargout{2} ] = class_wrapper(15, this, varargin{:}); return end error('Arguments do not match any overload of function Test.create_ptrs'); @@ -88,7 +88,7 @@ classdef Test < handle % PRINT usage: print() : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - geometry_wrapper(33, this, varargin{:}); + class_wrapper(16, this, varargin{:}); return end error('Arguments do not match any overload of function Test.print'); @@ -98,7 +98,7 @@ classdef Test < handle % RETURN_POINT2PTR usage: return_Point2Ptr(bool value) : returns Point2 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'logical') - varargout{1} = geometry_wrapper(34, this, varargin{:}); + varargout{1} = class_wrapper(17, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_Point2Ptr'); @@ -108,7 +108,7 @@ classdef Test < handle % RETURN_TEST usage: return_Test(Test value) : returns Test % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(35, this, varargin{:}); + varargout{1} = class_wrapper(18, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_Test'); @@ -118,7 +118,7 @@ classdef Test < handle % RETURN_TESTPTR usage: return_TestPtr(Test value) : returns Test % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(36, this, varargin{:}); + varargout{1} = class_wrapper(19, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_TestPtr'); @@ -128,7 +128,7 @@ classdef Test < handle % RETURN_BOOL usage: return_bool(bool value) : returns bool % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'logical') - varargout{1} = geometry_wrapper(37, this, varargin{:}); + varargout{1} = class_wrapper(20, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_bool'); @@ -138,7 +138,7 @@ classdef Test < handle % RETURN_DOUBLE usage: return_double(double value) : returns double % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(38, this, varargin{:}); + varargout{1} = class_wrapper(21, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_double'); @@ -148,7 +148,7 @@ classdef Test < handle % RETURN_FIELD usage: return_field(Test t) : returns bool % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = geometry_wrapper(39, this, varargin{:}); + varargout{1} = class_wrapper(22, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_field'); @@ -158,7 +158,7 @@ classdef Test < handle % RETURN_INT usage: return_int(int value) : returns int % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = geometry_wrapper(40, this, varargin{:}); + varargout{1} = class_wrapper(23, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_int'); @@ -168,7 +168,7 @@ classdef Test < handle % RETURN_MATRIX1 usage: return_matrix1(Matrix value) : returns Matrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(41, this, varargin{:}); + varargout{1} = class_wrapper(24, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_matrix1'); @@ -178,7 +178,7 @@ classdef Test < handle % RETURN_MATRIX2 usage: return_matrix2(Matrix value) : returns Matrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = geometry_wrapper(42, this, varargin{:}); + varargout{1} = class_wrapper(25, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_matrix2'); @@ -188,13 +188,13 @@ classdef Test < handle % RETURN_PAIR usage: return_pair(Vector v, Matrix A) : returns pair< Vector, Matrix > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 2 && isa(varargin{1},'double') && size(varargin{1},2)==1 && isa(varargin{2},'double') - [ varargout{1} varargout{2} ] = geometry_wrapper(43, this, varargin{:}); + [ varargout{1} varargout{2} ] = class_wrapper(26, this, varargin{:}); return end % RETURN_PAIR usage: return_pair(Vector v) : returns pair< Vector, Matrix > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 - [ varargout{1} varargout{2} ] = geometry_wrapper(44, this, varargin{:}); + [ varargout{1} varargout{2} ] = class_wrapper(27, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_pair'); @@ -204,7 +204,7 @@ classdef Test < handle % RETURN_PTRS usage: return_ptrs(Test p1, Test p2) : returns pair< Test, Test > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 2 && isa(varargin{1},'Test') && isa(varargin{2},'Test') - [ varargout{1} varargout{2} ] = geometry_wrapper(45, this, varargin{:}); + [ varargout{1} varargout{2} ] = class_wrapper(28, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_ptrs'); @@ -214,7 +214,7 @@ classdef Test < handle % RETURN_SIZE_T usage: return_size_t(size_t value) : returns size_t % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = geometry_wrapper(46, this, varargin{:}); + varargout{1} = class_wrapper(29, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_size_t'); @@ -224,7 +224,7 @@ classdef Test < handle % RETURN_STRING usage: return_string(string value) : returns string % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'char') - varargout{1} = geometry_wrapper(47, this, varargin{:}); + varargout{1} = class_wrapper(30, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_string'); @@ -234,7 +234,7 @@ classdef Test < handle % RETURN_VECTOR1 usage: return_vector1(Vector value) : returns Vector % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(48, this, varargin{:}); + varargout{1} = class_wrapper(31, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_vector1'); @@ -244,7 +244,7 @@ classdef Test < handle % RETURN_VECTOR2 usage: return_vector2(Vector value) : returns Vector % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 - varargout{1} = geometry_wrapper(49, this, varargin{:}); + varargout{1} = class_wrapper(32, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_vector2'); diff --git a/tests/expected/matlab/aGlobalFunction.m b/tests/expected/matlab/aGlobalFunction.m new file mode 100644 index 000000000..49850fc3e --- /dev/null +++ b/tests/expected/matlab/aGlobalFunction.m @@ -0,0 +1,6 @@ +function varargout = aGlobalFunction(varargin) + if length(varargin) == 0 + varargout{1} = functions_wrapper(3, varargin{:}); + else + error('Arguments do not match any overload of function aGlobalFunction'); + end diff --git a/tests/expected/matlab/class_wrapper.cpp b/tests/expected/matlab/class_wrapper.cpp new file mode 100644 index 000000000..a74306675 --- /dev/null +++ b/tests/expected/matlab/class_wrapper.cpp @@ -0,0 +1,791 @@ +#include +#include + +#include +#include +#include + +#include + + +typedef Fun FunDouble; +typedef PrimitiveRef PrimitiveRefDouble; +typedef MyVector<3> MyVector3; +typedef MyVector<12> MyVector12; +typedef MultipleTemplates MultipleTemplatesIntDouble; +typedef MultipleTemplates MultipleTemplatesIntFloat; +typedef MyFactor MyFactorPosePoint2; + + +typedef std::set*> Collector_FunRange; +static Collector_FunRange collector_FunRange; +typedef std::set*> Collector_FunDouble; +static Collector_FunDouble collector_FunDouble; +typedef std::set*> Collector_Test; +static Collector_Test collector_Test; +typedef std::set*> Collector_PrimitiveRefDouble; +static Collector_PrimitiveRefDouble collector_PrimitiveRefDouble; +typedef std::set*> Collector_MyVector3; +static Collector_MyVector3 collector_MyVector3; +typedef std::set*> Collector_MyVector12; +static Collector_MyVector12 collector_MyVector12; +typedef std::set*> Collector_MultipleTemplatesIntDouble; +static Collector_MultipleTemplatesIntDouble collector_MultipleTemplatesIntDouble; +typedef std::set*> Collector_MultipleTemplatesIntFloat; +static Collector_MultipleTemplatesIntFloat collector_MultipleTemplatesIntFloat; +typedef std::set*> Collector_MyFactorPosePoint2; +static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2; + +void _deleteAllObjects() +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + bool anyDeleted = false; + { for(Collector_FunRange::iterator iter = collector_FunRange.begin(); + iter != collector_FunRange.end(); ) { + delete *iter; + collector_FunRange.erase(iter++); + anyDeleted = true; + } } + { for(Collector_FunDouble::iterator iter = collector_FunDouble.begin(); + iter != collector_FunDouble.end(); ) { + delete *iter; + collector_FunDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_Test::iterator iter = collector_Test.begin(); + iter != collector_Test.end(); ) { + delete *iter; + collector_Test.erase(iter++); + anyDeleted = true; + } } + { for(Collector_PrimitiveRefDouble::iterator iter = collector_PrimitiveRefDouble.begin(); + iter != collector_PrimitiveRefDouble.end(); ) { + delete *iter; + collector_PrimitiveRefDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyVector3::iterator iter = collector_MyVector3.begin(); + iter != collector_MyVector3.end(); ) { + delete *iter; + collector_MyVector3.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyVector12::iterator iter = collector_MyVector12.begin(); + iter != collector_MyVector12.end(); ) { + delete *iter; + collector_MyVector12.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MultipleTemplatesIntDouble::iterator iter = collector_MultipleTemplatesIntDouble.begin(); + iter != collector_MultipleTemplatesIntDouble.end(); ) { + delete *iter; + collector_MultipleTemplatesIntDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MultipleTemplatesIntFloat::iterator iter = collector_MultipleTemplatesIntFloat.begin(); + iter != collector_MultipleTemplatesIntFloat.end(); ) { + delete *iter; + collector_MultipleTemplatesIntFloat.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyFactorPosePoint2::iterator iter = collector_MyFactorPosePoint2.begin(); + iter != collector_MyFactorPosePoint2.end(); ) { + delete *iter; + collector_MyFactorPosePoint2.erase(iter++); + anyDeleted = true; + } } + if(anyDeleted) + cout << + "WARNING: Wrap modules with variables in the workspace have been reloaded due to\n" + "calling destructors, call 'clear all' again if you plan to now recompile a wrap\n" + "module, so that your recompiled module is used instead of the old one." << endl; + std::cout.rdbuf(outbuf); +} + +void _class_RTTIRegister() { + const mxArray *alreadyCreated = mexGetVariablePtr("global", "gtsam_class_rttiRegistry_created"); + if(!alreadyCreated) { + std::map types; + + mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); + if(!registry) + registry = mxCreateStructMatrix(1, 1, 0, NULL); + typedef std::pair StringPair; + for(const StringPair& rtti_matlab: types) { + int fieldId = mxAddField(registry, rtti_matlab.first.c_str()); + if(fieldId < 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str()); + mxSetFieldByNumber(registry, 0, fieldId, matlabName); + } + if(mexPutVariable("global", "gtsamwrap_rttiRegistry", registry) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(registry); + + mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL); + if(mexPutVariable("global", "gtsam_geometry_rttiRegistry_created", newAlreadyCreated) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(newAlreadyCreated); + } +} + +void FunRange_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_FunRange.insert(self); +} + +void FunRange_constructor_1(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new FunRange()); + collector_FunRange.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void FunRange_deconstructor_2(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_FunRange",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_FunRange::iterator item; + item = collector_FunRange.find(self); + if(item != collector_FunRange.end()) { + delete self; + collector_FunRange.erase(item); + } +} + +void FunRange_range_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("range",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_FunRange"); + double d = unwrap< double >(in[1]); + out[0] = wrap_shared_ptr(boost::make_shared(obj->range(d)),"FunRange", false); +} + +void FunRange_create_4(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("FunRange.create",nargout,nargin,0); + out[0] = wrap_shared_ptr(boost::make_shared(FunRange::create()),"FunRange", false); +} + +void FunDouble_collectorInsertAndMakeBase_5(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_FunDouble.insert(self); +} + +void FunDouble_deconstructor_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr> Shared; + checkArguments("delete_FunDouble",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_FunDouble::iterator item; + item = collector_FunDouble.find(self); + if(item != collector_FunDouble.end()) { + delete self; + collector_FunDouble.erase(item); + } +} + +void FunDouble_dhamaal_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("dhamaalString",nargout,nargin-1,2); + auto obj = unwrap_shared_ptr>(in[0], "ptr_FunDouble"); + double d = unwrap< double >(in[1]); + string t = unwrap< string >(in[2]); + out[0] = wrap_shared_ptr(boost::make_shared>(obj->dhamaal(d,t)),"Fun", false); +} + +void FunDouble_divertido_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("FunDouble.divertido",nargout,nargin,0); + out[0] = wrap_shared_ptr(boost::make_shared>(Fun::divertido()),"Fundouble", false); +} + +void Test_collectorInsertAndMakeBase_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_Test.insert(self); +} + +void Test_constructor_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new Test()); + collector_Test.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void Test_constructor_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + double a = unwrap< double >(in[0]); + Matrix b = unwrap< Matrix >(in[1]); + Shared *self = new Shared(new Test(a,b)); + collector_Test.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void Test_deconstructor_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_Test",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_Test::iterator item; + item = collector_Test.find(self); + if(item != collector_Test.end()) { + delete self; + collector_Test.erase(item); + } +} + +void Test_arg_EigenConstRef_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("arg_EigenConstRef",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Matrix value = unwrap< Matrix >(in[1]); + obj->arg_EigenConstRef(value); +} + +void Test_create_MixedPtrs_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("create_MixedPtrs",nargout,nargin-1,0); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + auto pairResult = obj->create_MixedPtrs(); + out[0] = wrap_shared_ptr(boost::make_shared(pairResult.first),"Test", false); + out[1] = wrap_shared_ptr(pairResult.second,"Test", false); +} + +void Test_create_ptrs_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("create_ptrs",nargout,nargin-1,0); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + auto pairResult = obj->create_ptrs(); + out[0] = wrap_shared_ptr(pairResult.first,"Test", false); + out[1] = wrap_shared_ptr(pairResult.second,"Test", false); +} + +void Test_print_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("print",nargout,nargin-1,0); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + obj->print(); +} + +void Test_return_Point2Ptr_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_Point2Ptr",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + bool value = unwrap< bool >(in[1]); + { + boost::shared_ptr shared(obj->return_Point2Ptr(value)); + out[0] = wrap_shared_ptr(shared,"Point2"); + } +} + +void Test_return_Test_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_Test",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + out[0] = wrap_shared_ptr(boost::make_shared(obj->return_Test(value)),"Test", false); +} + +void Test_return_TestPtr_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_TestPtr",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + boost::shared_ptr value = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + out[0] = wrap_shared_ptr(obj->return_TestPtr(value),"Test", false); +} + +void Test_return_bool_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_bool",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + bool value = unwrap< bool >(in[1]); + out[0] = wrap< bool >(obj->return_bool(value)); +} + +void Test_return_double_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_double",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + double value = unwrap< double >(in[1]); + out[0] = wrap< double >(obj->return_double(value)); +} + +void Test_return_field_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_field",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Test& t = *unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + out[0] = wrap< bool >(obj->return_field(t)); +} + +void Test_return_int_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_int",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + int value = unwrap< int >(in[1]); + out[0] = wrap< int >(obj->return_int(value)); +} + +void Test_return_matrix1_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_matrix1",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Matrix value = unwrap< Matrix >(in[1]); + out[0] = wrap< Matrix >(obj->return_matrix1(value)); +} + +void Test_return_matrix2_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_matrix2",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Matrix value = unwrap< Matrix >(in[1]); + out[0] = wrap< Matrix >(obj->return_matrix2(value)); +} + +void Test_return_pair_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_pair",nargout,nargin-1,2); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Vector v = unwrap< Vector >(in[1]); + Matrix A = unwrap< Matrix >(in[2]); + auto pairResult = obj->return_pair(v,A); + out[0] = wrap< Vector >(pairResult.first); + out[1] = wrap< Matrix >(pairResult.second); +} + +void Test_return_pair_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_pair",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Vector v = unwrap< Vector >(in[1]); + auto pairResult = obj->return_pair(v); + out[0] = wrap< Vector >(pairResult.first); + out[1] = wrap< Matrix >(pairResult.second); +} + +void Test_return_ptrs_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_ptrs",nargout,nargin-1,2); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + boost::shared_ptr p1 = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + boost::shared_ptr p2 = unwrap_shared_ptr< Test >(in[2], "ptr_Test"); + auto pairResult = obj->return_ptrs(p1,p2); + out[0] = wrap_shared_ptr(pairResult.first,"Test", false); + out[1] = wrap_shared_ptr(pairResult.second,"Test", false); +} + +void Test_return_size_t_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_size_t",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + size_t value = unwrap< size_t >(in[1]); + out[0] = wrap< size_t >(obj->return_size_t(value)); +} + +void Test_return_string_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_string",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + string value = unwrap< string >(in[1]); + out[0] = wrap< string >(obj->return_string(value)); +} + +void Test_return_vector1_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_vector1",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Vector value = unwrap< Vector >(in[1]); + out[0] = wrap< Vector >(obj->return_vector1(value)); +} + +void Test_return_vector2_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_vector2",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); + Vector value = unwrap< Vector >(in[1]); + out[0] = wrap< Vector >(obj->return_vector2(value)); +} + +void PrimitiveRefDouble_collectorInsertAndMakeBase_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_PrimitiveRefDouble.insert(self); +} + +void PrimitiveRefDouble_constructor_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + Shared *self = new Shared(new PrimitiveRef()); + collector_PrimitiveRefDouble.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void PrimitiveRefDouble_deconstructor_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr> Shared; + checkArguments("delete_PrimitiveRefDouble",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_PrimitiveRefDouble::iterator item; + item = collector_PrimitiveRefDouble.find(self); + if(item != collector_PrimitiveRefDouble.end()) { + delete self; + collector_PrimitiveRefDouble.erase(item); + } +} + +void PrimitiveRefDouble_Brutal_36(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("PrimitiveRefDouble.Brutal",nargout,nargin,1); + double t = unwrap< double >(in[0]); + out[0] = wrap_shared_ptr(boost::make_shared>(PrimitiveRef::Brutal(t)),"PrimitiveRefdouble", false); +} + +void MyVector3_collectorInsertAndMakeBase_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_MyVector3.insert(self); +} + +void MyVector3_constructor_38(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + Shared *self = new Shared(new MyVector<3>()); + collector_MyVector3.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void MyVector3_deconstructor_39(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr> Shared; + checkArguments("delete_MyVector3",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_MyVector3::iterator item; + item = collector_MyVector3.find(self); + if(item != collector_MyVector3.end()) { + delete self; + collector_MyVector3.erase(item); + } +} + +void MyVector12_collectorInsertAndMakeBase_40(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_MyVector12.insert(self); +} + +void MyVector12_constructor_41(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + Shared *self = new Shared(new MyVector<12>()); + collector_MyVector12.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void MyVector12_deconstructor_42(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr> Shared; + checkArguments("delete_MyVector12",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_MyVector12::iterator item; + item = collector_MyVector12.find(self); + if(item != collector_MyVector12.end()) { + delete self; + collector_MyVector12.erase(item); + } +} + +void MultipleTemplatesIntDouble_collectorInsertAndMakeBase_43(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_MultipleTemplatesIntDouble.insert(self); +} + +void MultipleTemplatesIntDouble_deconstructor_44(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr> Shared; + checkArguments("delete_MultipleTemplatesIntDouble",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_MultipleTemplatesIntDouble::iterator item; + item = collector_MultipleTemplatesIntDouble.find(self); + if(item != collector_MultipleTemplatesIntDouble.end()) { + delete self; + collector_MultipleTemplatesIntDouble.erase(item); + } +} + +void MultipleTemplatesIntFloat_collectorInsertAndMakeBase_45(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_MultipleTemplatesIntFloat.insert(self); +} + +void MultipleTemplatesIntFloat_deconstructor_46(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr> Shared; + checkArguments("delete_MultipleTemplatesIntFloat",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_MultipleTemplatesIntFloat::iterator item; + item = collector_MultipleTemplatesIntFloat.find(self); + if(item != collector_MultipleTemplatesIntFloat.end()) { + delete self; + collector_MultipleTemplatesIntFloat.erase(item); + } +} + +void MyFactorPosePoint2_collectorInsertAndMakeBase_47(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_MyFactorPosePoint2.insert(self); +} + +void MyFactorPosePoint2_constructor_48(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + size_t key1 = unwrap< size_t >(in[0]); + size_t key2 = unwrap< size_t >(in[1]); + double measured = unwrap< double >(in[2]); + boost::shared_ptr noiseModel = unwrap_shared_ptr< gtsam::noiseModel::Base >(in[3], "ptr_gtsamnoiseModelBase"); + Shared *self = new Shared(new MyFactor(key1,key2,measured,noiseModel)); + collector_MyFactorPosePoint2.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void MyFactorPosePoint2_deconstructor_49(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr> Shared; + checkArguments("delete_MyFactorPosePoint2",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_MyFactorPosePoint2::iterator item; + item = collector_MyFactorPosePoint2.find(self); + if(item != collector_MyFactorPosePoint2.end()) { + delete self; + collector_MyFactorPosePoint2.erase(item); + } +} + + +void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + _class_RTTIRegister(); + + int id = unwrap(in[0]); + + try { + switch(id) { + case 0: + FunRange_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); + break; + case 1: + FunRange_constructor_1(nargout, out, nargin-1, in+1); + break; + case 2: + FunRange_deconstructor_2(nargout, out, nargin-1, in+1); + break; + case 3: + FunRange_range_3(nargout, out, nargin-1, in+1); + break; + case 4: + FunRange_create_4(nargout, out, nargin-1, in+1); + break; + case 5: + FunDouble_collectorInsertAndMakeBase_5(nargout, out, nargin-1, in+1); + break; + case 6: + FunDouble_deconstructor_6(nargout, out, nargin-1, in+1); + break; + case 7: + FunDouble_dhamaal_7(nargout, out, nargin-1, in+1); + break; + case 8: + FunDouble_divertido_8(nargout, out, nargin-1, in+1); + break; + case 9: + Test_collectorInsertAndMakeBase_9(nargout, out, nargin-1, in+1); + break; + case 10: + Test_constructor_10(nargout, out, nargin-1, in+1); + break; + case 11: + Test_constructor_11(nargout, out, nargin-1, in+1); + break; + case 12: + Test_deconstructor_12(nargout, out, nargin-1, in+1); + break; + case 13: + Test_arg_EigenConstRef_13(nargout, out, nargin-1, in+1); + break; + case 14: + Test_create_MixedPtrs_14(nargout, out, nargin-1, in+1); + break; + case 15: + Test_create_ptrs_15(nargout, out, nargin-1, in+1); + break; + case 16: + Test_print_16(nargout, out, nargin-1, in+1); + break; + case 17: + Test_return_Point2Ptr_17(nargout, out, nargin-1, in+1); + break; + case 18: + Test_return_Test_18(nargout, out, nargin-1, in+1); + break; + case 19: + Test_return_TestPtr_19(nargout, out, nargin-1, in+1); + break; + case 20: + Test_return_bool_20(nargout, out, nargin-1, in+1); + break; + case 21: + Test_return_double_21(nargout, out, nargin-1, in+1); + break; + case 22: + Test_return_field_22(nargout, out, nargin-1, in+1); + break; + case 23: + Test_return_int_23(nargout, out, nargin-1, in+1); + break; + case 24: + Test_return_matrix1_24(nargout, out, nargin-1, in+1); + break; + case 25: + Test_return_matrix2_25(nargout, out, nargin-1, in+1); + break; + case 26: + Test_return_pair_26(nargout, out, nargin-1, in+1); + break; + case 27: + Test_return_pair_27(nargout, out, nargin-1, in+1); + break; + case 28: + Test_return_ptrs_28(nargout, out, nargin-1, in+1); + break; + case 29: + Test_return_size_t_29(nargout, out, nargin-1, in+1); + break; + case 30: + Test_return_string_30(nargout, out, nargin-1, in+1); + break; + case 31: + Test_return_vector1_31(nargout, out, nargin-1, in+1); + break; + case 32: + Test_return_vector2_32(nargout, out, nargin-1, in+1); + break; + case 33: + PrimitiveRefDouble_collectorInsertAndMakeBase_33(nargout, out, nargin-1, in+1); + break; + case 34: + PrimitiveRefDouble_constructor_34(nargout, out, nargin-1, in+1); + break; + case 35: + PrimitiveRefDouble_deconstructor_35(nargout, out, nargin-1, in+1); + break; + case 36: + PrimitiveRefDouble_Brutal_36(nargout, out, nargin-1, in+1); + break; + case 37: + MyVector3_collectorInsertAndMakeBase_37(nargout, out, nargin-1, in+1); + break; + case 38: + MyVector3_constructor_38(nargout, out, nargin-1, in+1); + break; + case 39: + MyVector3_deconstructor_39(nargout, out, nargin-1, in+1); + break; + case 40: + MyVector12_collectorInsertAndMakeBase_40(nargout, out, nargin-1, in+1); + break; + case 41: + MyVector12_constructor_41(nargout, out, nargin-1, in+1); + break; + case 42: + MyVector12_deconstructor_42(nargout, out, nargin-1, in+1); + break; + case 43: + MultipleTemplatesIntDouble_collectorInsertAndMakeBase_43(nargout, out, nargin-1, in+1); + break; + case 44: + MultipleTemplatesIntDouble_deconstructor_44(nargout, out, nargin-1, in+1); + break; + case 45: + MultipleTemplatesIntFloat_collectorInsertAndMakeBase_45(nargout, out, nargin-1, in+1); + break; + case 46: + MultipleTemplatesIntFloat_deconstructor_46(nargout, out, nargin-1, in+1); + break; + case 47: + MyFactorPosePoint2_collectorInsertAndMakeBase_47(nargout, out, nargin-1, in+1); + break; + case 48: + MyFactorPosePoint2_constructor_48(nargout, out, nargin-1, in+1); + break; + case 49: + MyFactorPosePoint2_deconstructor_49(nargout, out, nargin-1, in+1); + break; + } + } catch(const std::exception& e) { + mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str()); + } + + std::cout.rdbuf(outbuf); +} diff --git a/tests/expected/matlab/functions_wrapper.cpp b/tests/expected/matlab/functions_wrapper.cpp new file mode 100644 index 000000000..c17c98ead --- /dev/null +++ b/tests/expected/matlab/functions_wrapper.cpp @@ -0,0 +1,250 @@ +#include +#include + +#include +#include +#include + +#include + + +typedef Fun FunDouble; +typedef PrimitiveRef PrimitiveRefDouble; +typedef MyVector<3> MyVector3; +typedef MyVector<12> MyVector12; +typedef MultipleTemplates MultipleTemplatesIntDouble; +typedef MultipleTemplates MultipleTemplatesIntFloat; +typedef MyFactor MyFactorPosePoint2; + + +typedef std::set*> Collector_FunRange; +static Collector_FunRange collector_FunRange; +typedef std::set*> Collector_FunDouble; +static Collector_FunDouble collector_FunDouble; +typedef std::set*> Collector_Test; +static Collector_Test collector_Test; +typedef std::set*> Collector_PrimitiveRefDouble; +static Collector_PrimitiveRefDouble collector_PrimitiveRefDouble; +typedef std::set*> Collector_MyVector3; +static Collector_MyVector3 collector_MyVector3; +typedef std::set*> Collector_MyVector12; +static Collector_MyVector12 collector_MyVector12; +typedef std::set*> Collector_MultipleTemplatesIntDouble; +static Collector_MultipleTemplatesIntDouble collector_MultipleTemplatesIntDouble; +typedef std::set*> Collector_MultipleTemplatesIntFloat; +static Collector_MultipleTemplatesIntFloat collector_MultipleTemplatesIntFloat; +typedef std::set*> Collector_MyFactorPosePoint2; +static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2; + +void _deleteAllObjects() +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + bool anyDeleted = false; + { for(Collector_FunRange::iterator iter = collector_FunRange.begin(); + iter != collector_FunRange.end(); ) { + delete *iter; + collector_FunRange.erase(iter++); + anyDeleted = true; + } } + { for(Collector_FunDouble::iterator iter = collector_FunDouble.begin(); + iter != collector_FunDouble.end(); ) { + delete *iter; + collector_FunDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_Test::iterator iter = collector_Test.begin(); + iter != collector_Test.end(); ) { + delete *iter; + collector_Test.erase(iter++); + anyDeleted = true; + } } + { for(Collector_PrimitiveRefDouble::iterator iter = collector_PrimitiveRefDouble.begin(); + iter != collector_PrimitiveRefDouble.end(); ) { + delete *iter; + collector_PrimitiveRefDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyVector3::iterator iter = collector_MyVector3.begin(); + iter != collector_MyVector3.end(); ) { + delete *iter; + collector_MyVector3.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyVector12::iterator iter = collector_MyVector12.begin(); + iter != collector_MyVector12.end(); ) { + delete *iter; + collector_MyVector12.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MultipleTemplatesIntDouble::iterator iter = collector_MultipleTemplatesIntDouble.begin(); + iter != collector_MultipleTemplatesIntDouble.end(); ) { + delete *iter; + collector_MultipleTemplatesIntDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MultipleTemplatesIntFloat::iterator iter = collector_MultipleTemplatesIntFloat.begin(); + iter != collector_MultipleTemplatesIntFloat.end(); ) { + delete *iter; + collector_MultipleTemplatesIntFloat.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyFactorPosePoint2::iterator iter = collector_MyFactorPosePoint2.begin(); + iter != collector_MyFactorPosePoint2.end(); ) { + delete *iter; + collector_MyFactorPosePoint2.erase(iter++); + anyDeleted = true; + } } + if(anyDeleted) + cout << + "WARNING: Wrap modules with variables in the workspace have been reloaded due to\n" + "calling destructors, call 'clear all' again if you plan to now recompile a wrap\n" + "module, so that your recompiled module is used instead of the old one." << endl; + std::cout.rdbuf(outbuf); +} + +void _functions_RTTIRegister() { + const mxArray *alreadyCreated = mexGetVariablePtr("global", "gtsam_functions_rttiRegistry_created"); + if(!alreadyCreated) { + std::map types; + + mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); + if(!registry) + registry = mxCreateStructMatrix(1, 1, 0, NULL); + typedef std::pair StringPair; + for(const StringPair& rtti_matlab: types) { + int fieldId = mxAddField(registry, rtti_matlab.first.c_str()); + if(fieldId < 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str()); + mxSetFieldByNumber(registry, 0, fieldId, matlabName); + } + if(mexPutVariable("global", "gtsamwrap_rttiRegistry", registry) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(registry); + + mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL); + if(mexPutVariable("global", "gtsam_geometry_rttiRegistry_created", newAlreadyCreated) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(newAlreadyCreated); + } +} + +void load2D_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("load2D",nargout,nargin,5); + string filename = unwrap< string >(in[0]); + boost::shared_ptr model = unwrap_shared_ptr< Test >(in[1], "ptr_Test"); + int maxID = unwrap< int >(in[2]); + bool addNoise = unwrap< bool >(in[3]); + bool smart = unwrap< bool >(in[4]); + auto pairResult = load2D(filename,model,maxID,addNoise,smart); + out[0] = wrap_shared_ptr(pairResult.first,"gtsam.NonlinearFactorGraph", false); + out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Values", false); +} +void load2D_1(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("load2D",nargout,nargin,5); + string filename = unwrap< string >(in[0]); + boost::shared_ptr model = unwrap_shared_ptr< gtsam::noiseModel::Diagonal >(in[1], "ptr_gtsamnoiseModelDiagonal"); + int maxID = unwrap< int >(in[2]); + bool addNoise = unwrap< bool >(in[3]); + bool smart = unwrap< bool >(in[4]); + auto pairResult = load2D(filename,model,maxID,addNoise,smart); + out[0] = wrap_shared_ptr(pairResult.first,"gtsam.NonlinearFactorGraph", false); + out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Values", false); +} +void load2D_2(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("load2D",nargout,nargin,2); + string filename = unwrap< string >(in[0]); + boost::shared_ptr model = unwrap_shared_ptr< gtsam::noiseModel::Diagonal >(in[1], "ptr_gtsamnoiseModelDiagonal"); + auto pairResult = load2D(filename,model); + out[0] = wrap_shared_ptr(pairResult.first,"gtsam.NonlinearFactorGraph", false); + out[1] = wrap_shared_ptr(pairResult.second,"gtsam.Values", false); +} +void aGlobalFunction_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("aGlobalFunction",nargout,nargin,0); + out[0] = wrap< Vector >(aGlobalFunction()); +} +void overloadedGlobalFunction_4(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("overloadedGlobalFunction",nargout,nargin,1); + int a = unwrap< int >(in[0]); + out[0] = wrap< Vector >(overloadedGlobalFunction(a)); +} +void overloadedGlobalFunction_5(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("overloadedGlobalFunction",nargout,nargin,2); + int a = unwrap< int >(in[0]); + double b = unwrap< double >(in[1]); + out[0] = wrap< Vector >(overloadedGlobalFunction(a,b)); +} +void MultiTemplatedFunctionStringSize_tDouble_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("MultiTemplatedFunctionStringSize_tDouble",nargout,nargin,2); + T& x = *unwrap_shared_ptr< T >(in[0], "ptr_T"); + size_t y = unwrap< size_t >(in[1]); + out[0] = wrap< double >(MultiTemplatedFunctionStringSize_tDouble(x,y)); +} +void MultiTemplatedFunctionDoubleSize_tDouble_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("MultiTemplatedFunctionDoubleSize_tDouble",nargout,nargin,2); + T& x = *unwrap_shared_ptr< T >(in[0], "ptr_T"); + size_t y = unwrap< size_t >(in[1]); + out[0] = wrap< double >(MultiTemplatedFunctionDoubleSize_tDouble(x,y)); +} +void TemplatedFunctionRot3_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("TemplatedFunctionRot3",nargout,nargin,1); + gtsam::Rot3& t = *unwrap_shared_ptr< gtsam::Rot3 >(in[0], "ptr_gtsamRot3"); + TemplatedFunctionRot3(t); +} + +void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + _functions_RTTIRegister(); + + int id = unwrap(in[0]); + + try { + switch(id) { + case 0: + load2D_0(nargout, out, nargin-1, in+1); + break; + case 1: + load2D_1(nargout, out, nargin-1, in+1); + break; + case 2: + load2D_2(nargout, out, nargin-1, in+1); + break; + case 3: + aGlobalFunction_3(nargout, out, nargin-1, in+1); + break; + case 4: + overloadedGlobalFunction_4(nargout, out, nargin-1, in+1); + break; + case 5: + overloadedGlobalFunction_5(nargout, out, nargin-1, in+1); + break; + case 6: + MultiTemplatedFunctionStringSize_tDouble_6(nargout, out, nargin-1, in+1); + break; + case 7: + MultiTemplatedFunctionDoubleSize_tDouble_7(nargout, out, nargin-1, in+1); + break; + case 8: + TemplatedFunctionRot3_8(nargout, out, nargin-1, in+1); + break; + } + } catch(const std::exception& e) { + mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str()); + } + + std::cout.rdbuf(outbuf); +} diff --git a/tests/expected/matlab/geometry_wrapper.cpp b/tests/expected/matlab/geometry_wrapper.cpp new file mode 100644 index 000000000..766c64bb3 --- /dev/null +++ b/tests/expected/matlab/geometry_wrapper.cpp @@ -0,0 +1,480 @@ +#include +#include + +#include +#include +#include + +#include +#include +#include + +typedef Fun FunDouble; +typedef PrimitiveRef PrimitiveRefDouble; +typedef MyVector<3> MyVector3; +typedef MyVector<12> MyVector12; +typedef MultipleTemplates MultipleTemplatesIntDouble; +typedef MultipleTemplates MultipleTemplatesIntFloat; +typedef MyFactor MyFactorPosePoint2; + +BOOST_CLASS_EXPORT_GUID(gtsam::Point2, "gtsamPoint2"); +BOOST_CLASS_EXPORT_GUID(gtsam::Point3, "gtsamPoint3"); + +typedef std::set*> Collector_FunRange; +static Collector_FunRange collector_FunRange; +typedef std::set*> Collector_FunDouble; +static Collector_FunDouble collector_FunDouble; +typedef std::set*> Collector_Test; +static Collector_Test collector_Test; +typedef std::set*> Collector_PrimitiveRefDouble; +static Collector_PrimitiveRefDouble collector_PrimitiveRefDouble; +typedef std::set*> Collector_MyVector3; +static Collector_MyVector3 collector_MyVector3; +typedef std::set*> Collector_MyVector12; +static Collector_MyVector12 collector_MyVector12; +typedef std::set*> Collector_MultipleTemplatesIntDouble; +static Collector_MultipleTemplatesIntDouble collector_MultipleTemplatesIntDouble; +typedef std::set*> Collector_MultipleTemplatesIntFloat; +static Collector_MultipleTemplatesIntFloat collector_MultipleTemplatesIntFloat; +typedef std::set*> Collector_MyFactorPosePoint2; +static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2; +typedef std::set*> Collector_gtsamPoint2; +static Collector_gtsamPoint2 collector_gtsamPoint2; +typedef std::set*> Collector_gtsamPoint3; +static Collector_gtsamPoint3 collector_gtsamPoint3; + +void _deleteAllObjects() +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + bool anyDeleted = false; + { for(Collector_FunRange::iterator iter = collector_FunRange.begin(); + iter != collector_FunRange.end(); ) { + delete *iter; + collector_FunRange.erase(iter++); + anyDeleted = true; + } } + { for(Collector_FunDouble::iterator iter = collector_FunDouble.begin(); + iter != collector_FunDouble.end(); ) { + delete *iter; + collector_FunDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_Test::iterator iter = collector_Test.begin(); + iter != collector_Test.end(); ) { + delete *iter; + collector_Test.erase(iter++); + anyDeleted = true; + } } + { for(Collector_PrimitiveRefDouble::iterator iter = collector_PrimitiveRefDouble.begin(); + iter != collector_PrimitiveRefDouble.end(); ) { + delete *iter; + collector_PrimitiveRefDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyVector3::iterator iter = collector_MyVector3.begin(); + iter != collector_MyVector3.end(); ) { + delete *iter; + collector_MyVector3.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyVector12::iterator iter = collector_MyVector12.begin(); + iter != collector_MyVector12.end(); ) { + delete *iter; + collector_MyVector12.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MultipleTemplatesIntDouble::iterator iter = collector_MultipleTemplatesIntDouble.begin(); + iter != collector_MultipleTemplatesIntDouble.end(); ) { + delete *iter; + collector_MultipleTemplatesIntDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MultipleTemplatesIntFloat::iterator iter = collector_MultipleTemplatesIntFloat.begin(); + iter != collector_MultipleTemplatesIntFloat.end(); ) { + delete *iter; + collector_MultipleTemplatesIntFloat.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyFactorPosePoint2::iterator iter = collector_MyFactorPosePoint2.begin(); + iter != collector_MyFactorPosePoint2.end(); ) { + delete *iter; + collector_MyFactorPosePoint2.erase(iter++); + anyDeleted = true; + } } + { for(Collector_gtsamPoint2::iterator iter = collector_gtsamPoint2.begin(); + iter != collector_gtsamPoint2.end(); ) { + delete *iter; + collector_gtsamPoint2.erase(iter++); + anyDeleted = true; + } } + { for(Collector_gtsamPoint3::iterator iter = collector_gtsamPoint3.begin(); + iter != collector_gtsamPoint3.end(); ) { + delete *iter; + collector_gtsamPoint3.erase(iter++); + anyDeleted = true; + } } + if(anyDeleted) + cout << + "WARNING: Wrap modules with variables in the workspace have been reloaded due to\n" + "calling destructors, call 'clear all' again if you plan to now recompile a wrap\n" + "module, so that your recompiled module is used instead of the old one." << endl; + std::cout.rdbuf(outbuf); +} + +void _geometry_RTTIRegister() { + const mxArray *alreadyCreated = mexGetVariablePtr("global", "gtsam_geometry_rttiRegistry_created"); + if(!alreadyCreated) { + std::map types; + + mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); + if(!registry) + registry = mxCreateStructMatrix(1, 1, 0, NULL); + typedef std::pair StringPair; + for(const StringPair& rtti_matlab: types) { + int fieldId = mxAddField(registry, rtti_matlab.first.c_str()); + if(fieldId < 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str()); + mxSetFieldByNumber(registry, 0, fieldId, matlabName); + } + if(mexPutVariable("global", "gtsamwrap_rttiRegistry", registry) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(registry); + + mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL); + if(mexPutVariable("global", "gtsam_geometry_rttiRegistry_created", newAlreadyCreated) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(newAlreadyCreated); + } +} + +void gtsamPoint2_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_gtsamPoint2.insert(self); +} + +void gtsamPoint2_constructor_1(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new gtsam::Point2()); + collector_gtsamPoint2.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void gtsamPoint2_constructor_2(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + double x = unwrap< double >(in[0]); + double y = unwrap< double >(in[1]); + Shared *self = new Shared(new gtsam::Point2(x,y)); + collector_gtsamPoint2.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void gtsamPoint2_deconstructor_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_gtsamPoint2",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_gtsamPoint2::iterator item; + item = collector_gtsamPoint2.find(self); + if(item != collector_gtsamPoint2.end()) { + delete self; + collector_gtsamPoint2.erase(item); + } +} + +void gtsamPoint2_argChar_4(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("argChar",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + char a = unwrap< char >(in[1]); + obj->argChar(a); +} + +void gtsamPoint2_argChar_5(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("argChar",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + boost::shared_ptr a = unwrap_shared_ptr< char >(in[1], "ptr_char"); + obj->argChar(a); +} + +void gtsamPoint2_argChar_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("argChar",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + char a = unwrap< char >(in[1]); + obj->argChar(a); +} + +void gtsamPoint2_argChar_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("argChar",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + boost::shared_ptr a = unwrap_shared_ptr< char >(in[1], "ptr_char"); + obj->argChar(a); +} + +void gtsamPoint2_argChar_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("argChar",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + boost::shared_ptr a = unwrap_shared_ptr< char >(in[1], "ptr_char"); + obj->argChar(a); +} + +void gtsamPoint2_argChar_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("argChar",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + char a = unwrap< char >(in[1]); + obj->argChar(a); +} + +void gtsamPoint2_argChar_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("argChar",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + boost::shared_ptr a = unwrap_shared_ptr< char >(in[1], "ptr_char"); + obj->argChar(a); +} + +void gtsamPoint2_argUChar_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("argUChar",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + unsigned char a = unwrap< unsigned char >(in[1]); + obj->argUChar(a); +} + +void gtsamPoint2_dim_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("dim",nargout,nargin-1,0); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + out[0] = wrap< int >(obj->dim()); +} + +void gtsamPoint2_eigenArguments_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("eigenArguments",nargout,nargin-1,2); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + Vector v = unwrap< Vector >(in[1]); + Matrix m = unwrap< Matrix >(in[2]); + obj->eigenArguments(v,m); +} + +void gtsamPoint2_returnChar_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("returnChar",nargout,nargin-1,0); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + out[0] = wrap< char >(obj->returnChar()); +} + +void gtsamPoint2_vectorConfusion_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("vectorConfusion",nargout,nargin-1,0); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + out[0] = wrap_shared_ptr(boost::make_shared(obj->vectorConfusion()),"VectorNotEigen", false); +} + +void gtsamPoint2_x_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("x",nargout,nargin-1,0); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + out[0] = wrap< double >(obj->x()); +} + +void gtsamPoint2_y_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("y",nargout,nargin-1,0); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint2"); + out[0] = wrap< double >(obj->y()); +} + +void gtsamPoint3_collectorInsertAndMakeBase_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_gtsamPoint3.insert(self); +} + +void gtsamPoint3_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + double x = unwrap< double >(in[0]); + double y = unwrap< double >(in[1]); + double z = unwrap< double >(in[2]); + Shared *self = new Shared(new gtsam::Point3(x,y,z)); + collector_gtsamPoint3.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void gtsamPoint3_deconstructor_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_gtsamPoint3",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_gtsamPoint3::iterator item; + item = collector_gtsamPoint3.find(self); + if(item != collector_gtsamPoint3.end()) { + delete self; + collector_gtsamPoint3.erase(item); + } +} + +void gtsamPoint3_norm_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("norm",nargout,nargin-1,0); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint3"); + out[0] = wrap< double >(obj->norm()); +} + +void gtsamPoint3_string_serialize_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("string_serialize",nargout,nargin-1,0); + Shared obj = unwrap_shared_ptr(in[0], "ptr_gtsamPoint3"); + ostringstream out_archive_stream; + boost::archive::text_oarchive out_archive(out_archive_stream); + out_archive << *obj; + out[0] = wrap< string >(out_archive_stream.str()); +} +void gtsamPoint3_StaticFunctionRet_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("gtsamPoint3.StaticFunctionRet",nargout,nargin,1); + double z = unwrap< double >(in[0]); + out[0] = wrap< Point3 >(gtsam::Point3::StaticFunctionRet(z)); +} + +void gtsamPoint3_staticFunction_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("gtsamPoint3.staticFunction",nargout,nargin,0); + out[0] = wrap< double >(gtsam::Point3::staticFunction()); +} + +void gtsamPoint3_string_deserialize_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("gtsamPoint3.string_deserialize",nargout,nargin,1); + string serialized = unwrap< string >(in[0]); + istringstream in_archive_stream(serialized); + boost::archive::text_iarchive in_archive(in_archive_stream); + Shared output(new gtsam::Point3()); + in_archive >> *output; + out[0] = wrap_shared_ptr(output,"gtsam.Point3", false); +} + +void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + _geometry_RTTIRegister(); + + int id = unwrap(in[0]); + + try { + switch(id) { + case 0: + gtsamPoint2_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); + break; + case 1: + gtsamPoint2_constructor_1(nargout, out, nargin-1, in+1); + break; + case 2: + gtsamPoint2_constructor_2(nargout, out, nargin-1, in+1); + break; + case 3: + gtsamPoint2_deconstructor_3(nargout, out, nargin-1, in+1); + break; + case 4: + gtsamPoint2_argChar_4(nargout, out, nargin-1, in+1); + break; + case 5: + gtsamPoint2_argChar_5(nargout, out, nargin-1, in+1); + break; + case 6: + gtsamPoint2_argChar_6(nargout, out, nargin-1, in+1); + break; + case 7: + gtsamPoint2_argChar_7(nargout, out, nargin-1, in+1); + break; + case 8: + gtsamPoint2_argChar_8(nargout, out, nargin-1, in+1); + break; + case 9: + gtsamPoint2_argChar_9(nargout, out, nargin-1, in+1); + break; + case 10: + gtsamPoint2_argChar_10(nargout, out, nargin-1, in+1); + break; + case 11: + gtsamPoint2_argUChar_11(nargout, out, nargin-1, in+1); + break; + case 12: + gtsamPoint2_dim_12(nargout, out, nargin-1, in+1); + break; + case 13: + gtsamPoint2_eigenArguments_13(nargout, out, nargin-1, in+1); + break; + case 14: + gtsamPoint2_returnChar_14(nargout, out, nargin-1, in+1); + break; + case 15: + gtsamPoint2_vectorConfusion_15(nargout, out, nargin-1, in+1); + break; + case 16: + gtsamPoint2_x_16(nargout, out, nargin-1, in+1); + break; + case 17: + gtsamPoint2_y_17(nargout, out, nargin-1, in+1); + break; + case 18: + gtsamPoint3_collectorInsertAndMakeBase_18(nargout, out, nargin-1, in+1); + break; + case 19: + gtsamPoint3_constructor_19(nargout, out, nargin-1, in+1); + break; + case 20: + gtsamPoint3_deconstructor_20(nargout, out, nargin-1, in+1); + break; + case 21: + gtsamPoint3_norm_21(nargout, out, nargin-1, in+1); + break; + case 22: + gtsamPoint3_string_serialize_22(nargout, out, nargin-1, in+1); + break; + case 23: + gtsamPoint3_StaticFunctionRet_23(nargout, out, nargin-1, in+1); + break; + case 24: + gtsamPoint3_staticFunction_24(nargout, out, nargin-1, in+1); + break; + case 25: + gtsamPoint3_string_deserialize_25(nargout, out, nargin-1, in+1); + break; + } + } catch(const std::exception& e) { + mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str()); + } + + std::cout.rdbuf(outbuf); +} diff --git a/tests/expected/matlab/inheritance_wrapper.cpp b/tests/expected/matlab/inheritance_wrapper.cpp new file mode 100644 index 000000000..f12f6ce57 --- /dev/null +++ b/tests/expected/matlab/inheritance_wrapper.cpp @@ -0,0 +1,681 @@ +#include +#include + +#include +#include +#include + +#include +#include +#include + +typedef Fun FunDouble; +typedef PrimitiveRef PrimitiveRefDouble; +typedef MyVector<3> MyVector3; +typedef MyVector<12> MyVector12; +typedef MultipleTemplates MultipleTemplatesIntDouble; +typedef MultipleTemplates MultipleTemplatesIntFloat; +typedef MyFactor MyFactorPosePoint2; +typedef MyTemplate MyTemplatePoint2; +typedef MyTemplate MyTemplateMatrix; + +BOOST_CLASS_EXPORT_GUID(gtsam::Point2, "gtsamPoint2"); +BOOST_CLASS_EXPORT_GUID(gtsam::Point3, "gtsamPoint3"); + +typedef std::set*> Collector_FunRange; +static Collector_FunRange collector_FunRange; +typedef std::set*> Collector_FunDouble; +static Collector_FunDouble collector_FunDouble; +typedef std::set*> Collector_Test; +static Collector_Test collector_Test; +typedef std::set*> Collector_PrimitiveRefDouble; +static Collector_PrimitiveRefDouble collector_PrimitiveRefDouble; +typedef std::set*> Collector_MyVector3; +static Collector_MyVector3 collector_MyVector3; +typedef std::set*> Collector_MyVector12; +static Collector_MyVector12 collector_MyVector12; +typedef std::set*> Collector_MultipleTemplatesIntDouble; +static Collector_MultipleTemplatesIntDouble collector_MultipleTemplatesIntDouble; +typedef std::set*> Collector_MultipleTemplatesIntFloat; +static Collector_MultipleTemplatesIntFloat collector_MultipleTemplatesIntFloat; +typedef std::set*> Collector_MyFactorPosePoint2; +static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2; +typedef std::set*> Collector_gtsamPoint2; +static Collector_gtsamPoint2 collector_gtsamPoint2; +typedef std::set*> Collector_gtsamPoint3; +static Collector_gtsamPoint3 collector_gtsamPoint3; +typedef std::set*> Collector_MyBase; +static Collector_MyBase collector_MyBase; +typedef std::set*> Collector_MyTemplatePoint2; +static Collector_MyTemplatePoint2 collector_MyTemplatePoint2; +typedef std::set*> Collector_MyTemplateMatrix; +static Collector_MyTemplateMatrix collector_MyTemplateMatrix; + +void _deleteAllObjects() +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + bool anyDeleted = false; + { for(Collector_FunRange::iterator iter = collector_FunRange.begin(); + iter != collector_FunRange.end(); ) { + delete *iter; + collector_FunRange.erase(iter++); + anyDeleted = true; + } } + { for(Collector_FunDouble::iterator iter = collector_FunDouble.begin(); + iter != collector_FunDouble.end(); ) { + delete *iter; + collector_FunDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_Test::iterator iter = collector_Test.begin(); + iter != collector_Test.end(); ) { + delete *iter; + collector_Test.erase(iter++); + anyDeleted = true; + } } + { for(Collector_PrimitiveRefDouble::iterator iter = collector_PrimitiveRefDouble.begin(); + iter != collector_PrimitiveRefDouble.end(); ) { + delete *iter; + collector_PrimitiveRefDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyVector3::iterator iter = collector_MyVector3.begin(); + iter != collector_MyVector3.end(); ) { + delete *iter; + collector_MyVector3.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyVector12::iterator iter = collector_MyVector12.begin(); + iter != collector_MyVector12.end(); ) { + delete *iter; + collector_MyVector12.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MultipleTemplatesIntDouble::iterator iter = collector_MultipleTemplatesIntDouble.begin(); + iter != collector_MultipleTemplatesIntDouble.end(); ) { + delete *iter; + collector_MultipleTemplatesIntDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MultipleTemplatesIntFloat::iterator iter = collector_MultipleTemplatesIntFloat.begin(); + iter != collector_MultipleTemplatesIntFloat.end(); ) { + delete *iter; + collector_MultipleTemplatesIntFloat.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyFactorPosePoint2::iterator iter = collector_MyFactorPosePoint2.begin(); + iter != collector_MyFactorPosePoint2.end(); ) { + delete *iter; + collector_MyFactorPosePoint2.erase(iter++); + anyDeleted = true; + } } + { for(Collector_gtsamPoint2::iterator iter = collector_gtsamPoint2.begin(); + iter != collector_gtsamPoint2.end(); ) { + delete *iter; + collector_gtsamPoint2.erase(iter++); + anyDeleted = true; + } } + { for(Collector_gtsamPoint3::iterator iter = collector_gtsamPoint3.begin(); + iter != collector_gtsamPoint3.end(); ) { + delete *iter; + collector_gtsamPoint3.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyBase::iterator iter = collector_MyBase.begin(); + iter != collector_MyBase.end(); ) { + delete *iter; + collector_MyBase.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyTemplatePoint2::iterator iter = collector_MyTemplatePoint2.begin(); + iter != collector_MyTemplatePoint2.end(); ) { + delete *iter; + collector_MyTemplatePoint2.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyTemplateMatrix::iterator iter = collector_MyTemplateMatrix.begin(); + iter != collector_MyTemplateMatrix.end(); ) { + delete *iter; + collector_MyTemplateMatrix.erase(iter++); + anyDeleted = true; + } } + if(anyDeleted) + cout << + "WARNING: Wrap modules with variables in the workspace have been reloaded due to\n" + "calling destructors, call 'clear all' again if you plan to now recompile a wrap\n" + "module, so that your recompiled module is used instead of the old one." << endl; + std::cout.rdbuf(outbuf); +} + +void _inheritance_RTTIRegister() { + const mxArray *alreadyCreated = mexGetVariablePtr("global", "gtsam_inheritance_rttiRegistry_created"); + if(!alreadyCreated) { + std::map types; + types.insert(std::make_pair(typeid(MyBase).name(), "MyBase")); + types.insert(std::make_pair(typeid(MyTemplatePoint2).name(), "MyTemplatePoint2")); + types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix")); + + mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); + if(!registry) + registry = mxCreateStructMatrix(1, 1, 0, NULL); + typedef std::pair StringPair; + for(const StringPair& rtti_matlab: types) { + int fieldId = mxAddField(registry, rtti_matlab.first.c_str()); + if(fieldId < 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str()); + mxSetFieldByNumber(registry, 0, fieldId, matlabName); + } + if(mexPutVariable("global", "gtsamwrap_rttiRegistry", registry) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(registry); + + mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL); + if(mexPutVariable("global", "gtsam_geometry_rttiRegistry_created", newAlreadyCreated) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(newAlreadyCreated); + } +} + +void gtsamPoint2_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_gtsamPoint2.insert(self); +} + +void MyBase_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_MyBase.insert(self); +} + +void MyBase_deconstructor_2(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_MyBase",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_MyBase::iterator item; + item = collector_MyBase.find(self); + if(item != collector_MyBase.end()) { + delete self; + collector_MyBase.erase(item); + } +} + +void gtsamPoint2_deconstructor_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_gtsamPoint2",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_gtsamPoint2::iterator item; + item = collector_gtsamPoint2.find(self); + if(item != collector_gtsamPoint2.end()) { + delete self; + collector_gtsamPoint2.erase(item); + } +} + +void MyTemplatePoint2_collectorInsertAndMakeBase_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_MyTemplatePoint2.insert(self); + + typedef boost::shared_ptr SharedBase; + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast(mxGetData(out[0])) = new SharedBase(*self); +} + +void MyTemplatePoint2_constructor_5(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + Shared *self = new Shared(new MyTemplate()); + collector_MyTemplatePoint2.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; + + typedef boost::shared_ptr SharedBase; + out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast(mxGetData(out[1])) = new SharedBase(*self); +} + +void MyTemplatePoint2_deconstructor_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr> Shared; + checkArguments("delete_MyTemplatePoint2",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_MyTemplatePoint2::iterator item; + item = collector_MyTemplatePoint2.find(self); + if(item != collector_MyTemplatePoint2.end()) { + delete self; + collector_MyTemplatePoint2.erase(item); + } +} + +void MyTemplatePoint2_accept_T_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("accept_T",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); + Point2 value = unwrap< Point2 >(in[1]); + obj->accept_T(value); +} + +void MyTemplatePoint2_accept_Tptr_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("accept_Tptr",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); + Point2 value = unwrap< Point2 >(in[1]); + obj->accept_Tptr(value); +} + +void MyTemplatePoint2_create_MixedPtrs_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("create_MixedPtrs",nargout,nargin-1,0); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); + auto pairResult = obj->create_MixedPtrs(); + out[0] = wrap< Point2 >(pairResult.first); + { + boost::shared_ptr shared(pairResult.second); + out[1] = wrap_shared_ptr(shared,"Point2"); + } +} + +void MyTemplatePoint2_create_ptrs_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("create_ptrs",nargout,nargin-1,0); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); + auto pairResult = obj->create_ptrs(); + { + boost::shared_ptr shared(pairResult.first); + out[0] = wrap_shared_ptr(shared,"Point2"); + } + { + boost::shared_ptr shared(pairResult.second); + out[1] = wrap_shared_ptr(shared,"Point2"); + } +} + +void MyTemplatePoint2_return_T_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_T",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); + Point2 value = unwrap< Point2 >(in[1]); + out[0] = wrap< Point2 >(obj->return_T(value)); +} + +void MyTemplatePoint2_return_Tptr_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_Tptr",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); + Point2 value = unwrap< Point2 >(in[1]); + { + boost::shared_ptr shared(obj->return_Tptr(value)); + out[0] = wrap_shared_ptr(shared,"Point2"); + } +} + +void MyTemplatePoint2_return_ptrs_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_ptrs",nargout,nargin-1,2); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); + Point2 p1 = unwrap< Point2 >(in[1]); + Point2 p2 = unwrap< Point2 >(in[2]); + auto pairResult = obj->return_ptrs(p1,p2); + { + boost::shared_ptr shared(pairResult.first); + out[0] = wrap_shared_ptr(shared,"Point2"); + } + { + boost::shared_ptr shared(pairResult.second); + out[1] = wrap_shared_ptr(shared,"Point2"); + } +} + +void MyTemplatePoint2_templatedMethod_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("templatedMethodMatrix",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); + Matrix t = unwrap< Matrix >(in[1]); + out[0] = wrap< Matrix >(obj->templatedMethod(t)); +} + +void MyTemplatePoint2_templatedMethod_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("templatedMethodPoint2",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); + Point2 t = unwrap< Point2 >(in[1]); + out[0] = wrap< Point2 >(obj->templatedMethod(t)); +} + +void MyTemplatePoint2_templatedMethod_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("templatedMethodPoint3",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); + Point3 t = unwrap< Point3 >(in[1]); + out[0] = wrap< Point3 >(obj->templatedMethod(t)); +} + +void MyTemplatePoint2_templatedMethod_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("templatedMethodVector",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplatePoint2"); + Vector t = unwrap< Vector >(in[1]); + out[0] = wrap< Vector >(obj->templatedMethod(t)); +} + +void MyTemplatePoint2_Level_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("MyTemplatePoint2.Level",nargout,nargin,1); + Point2 K = unwrap< Point2 >(in[0]); + out[0] = wrap_shared_ptr(boost::make_shared>(MyTemplate::Level(K)),"MyTemplatePoint2", false); +} + +void gtsamPoint3_constructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + double x = unwrap< double >(in[0]); + double y = unwrap< double >(in[1]); + double z = unwrap< double >(in[2]); + Shared *self = new Shared(new gtsam::Point3(x,y,z)); + collector_gtsamPoint3.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void MyTemplateMatrix_collectorInsertAndMakeBase_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_MyTemplateMatrix.insert(self); + + typedef boost::shared_ptr SharedBase; + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast(mxGetData(out[0])) = new SharedBase(*self); +} + +void MyTemplateMatrix_constructor_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + Shared *self = new Shared(new MyTemplate()); + collector_MyTemplateMatrix.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; + + typedef boost::shared_ptr SharedBase; + out[1] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast(mxGetData(out[1])) = new SharedBase(*self); +} + +void MyTemplateMatrix_deconstructor_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr> Shared; + checkArguments("delete_MyTemplateMatrix",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_MyTemplateMatrix::iterator item; + item = collector_MyTemplateMatrix.find(self); + if(item != collector_MyTemplateMatrix.end()) { + delete self; + collector_MyTemplateMatrix.erase(item); + } +} + +void MyTemplateMatrix_accept_T_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("accept_T",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); + Matrix value = unwrap< Matrix >(in[1]); + obj->accept_T(value); +} + +void MyTemplateMatrix_accept_Tptr_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("accept_Tptr",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); + Matrix value = unwrap< Matrix >(in[1]); + obj->accept_Tptr(value); +} + +void MyTemplateMatrix_create_MixedPtrs_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("create_MixedPtrs",nargout,nargin-1,0); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); + auto pairResult = obj->create_MixedPtrs(); + out[0] = wrap< Matrix >(pairResult.first); + { + boost::shared_ptr shared(pairResult.second); + out[1] = wrap_shared_ptr(shared,"Matrix"); + } +} + +void MyTemplateMatrix_create_ptrs_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("create_ptrs",nargout,nargin-1,0); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); + auto pairResult = obj->create_ptrs(); + { + boost::shared_ptr shared(pairResult.first); + out[0] = wrap_shared_ptr(shared,"Matrix"); + } + { + boost::shared_ptr shared(pairResult.second); + out[1] = wrap_shared_ptr(shared,"Matrix"); + } +} + +void MyTemplateMatrix_return_T_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_T",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); + Matrix value = unwrap< Matrix >(in[1]); + out[0] = wrap< Matrix >(obj->return_T(value)); +} + +void MyTemplateMatrix_return_Tptr_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_Tptr",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); + Matrix value = unwrap< Matrix >(in[1]); + { + boost::shared_ptr shared(obj->return_Tptr(value)); + out[0] = wrap_shared_ptr(shared,"Matrix"); + } +} + +void MyTemplateMatrix_return_ptrs_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("return_ptrs",nargout,nargin-1,2); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); + Matrix p1 = unwrap< Matrix >(in[1]); + Matrix p2 = unwrap< Matrix >(in[2]); + auto pairResult = obj->return_ptrs(p1,p2); + { + boost::shared_ptr shared(pairResult.first); + out[0] = wrap_shared_ptr(shared,"Matrix"); + } + { + boost::shared_ptr shared(pairResult.second); + out[1] = wrap_shared_ptr(shared,"Matrix"); + } +} + +void MyTemplateMatrix_templatedMethod_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("templatedMethodMatrix",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); + Matrix t = unwrap< Matrix >(in[1]); + out[0] = wrap< Matrix >(obj->templatedMethod(t)); +} + +void MyTemplateMatrix_templatedMethod_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("templatedMethodPoint2",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); + Point2 t = unwrap< Point2 >(in[1]); + out[0] = wrap< Point2 >(obj->templatedMethod(t)); +} + +void MyTemplateMatrix_templatedMethod_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("templatedMethodPoint3",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); + Point3 t = unwrap< Point3 >(in[1]); + out[0] = wrap< Point3 >(obj->templatedMethod(t)); +} + +void MyTemplateMatrix_templatedMethod_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("templatedMethodVector",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr>(in[0], "ptr_MyTemplateMatrix"); + Vector t = unwrap< Vector >(in[1]); + out[0] = wrap< Vector >(obj->templatedMethod(t)); +} + +void MyTemplateMatrix_Level_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("MyTemplateMatrix.Level",nargout,nargin,1); + Matrix K = unwrap< Matrix >(in[0]); + out[0] = wrap_shared_ptr(boost::make_shared>(MyTemplate::Level(K)),"MyTemplateMatrix", false); +} + + +void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + _inheritance_RTTIRegister(); + + int id = unwrap(in[0]); + + try { + switch(id) { + case 0: + gtsamPoint2_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); + break; + case 1: + MyBase_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); + break; + case 2: + MyBase_deconstructor_2(nargout, out, nargin-1, in+1); + break; + case 3: + gtsamPoint2_deconstructor_3(nargout, out, nargin-1, in+1); + break; + case 4: + MyTemplatePoint2_collectorInsertAndMakeBase_3(nargout, out, nargin-1, in+1); + break; + case 5: + MyTemplatePoint2_constructor_5(nargout, out, nargin-1, in+1); + break; + case 6: + MyTemplatePoint2_deconstructor_6(nargout, out, nargin-1, in+1); + break; + case 7: + MyTemplatePoint2_accept_T_7(nargout, out, nargin-1, in+1); + break; + case 8: + MyTemplatePoint2_accept_Tptr_8(nargout, out, nargin-1, in+1); + break; + case 9: + MyTemplatePoint2_create_MixedPtrs_9(nargout, out, nargin-1, in+1); + break; + case 10: + MyTemplatePoint2_create_ptrs_10(nargout, out, nargin-1, in+1); + break; + case 11: + MyTemplatePoint2_return_T_11(nargout, out, nargin-1, in+1); + break; + case 12: + MyTemplatePoint2_return_Tptr_12(nargout, out, nargin-1, in+1); + break; + case 13: + MyTemplatePoint2_return_ptrs_13(nargout, out, nargin-1, in+1); + break; + case 14: + MyTemplatePoint2_templatedMethod_14(nargout, out, nargin-1, in+1); + break; + case 15: + MyTemplatePoint2_templatedMethod_15(nargout, out, nargin-1, in+1); + break; + case 16: + MyTemplatePoint2_templatedMethod_16(nargout, out, nargin-1, in+1); + break; + case 17: + MyTemplatePoint2_templatedMethod_17(nargout, out, nargin-1, in+1); + break; + case 18: + MyTemplatePoint2_Level_18(nargout, out, nargin-1, in+1); + break; + case 19: + gtsamPoint3_constructor_19(nargout, out, nargin-1, in+1); + break; + case 20: + MyTemplateMatrix_collectorInsertAndMakeBase_19(nargout, out, nargin-1, in+1); + break; + case 21: + MyTemplateMatrix_constructor_21(nargout, out, nargin-1, in+1); + break; + case 22: + MyTemplateMatrix_deconstructor_22(nargout, out, nargin-1, in+1); + break; + case 23: + MyTemplateMatrix_accept_T_23(nargout, out, nargin-1, in+1); + break; + case 24: + MyTemplateMatrix_accept_Tptr_24(nargout, out, nargin-1, in+1); + break; + case 25: + MyTemplateMatrix_create_MixedPtrs_25(nargout, out, nargin-1, in+1); + break; + case 26: + MyTemplateMatrix_create_ptrs_26(nargout, out, nargin-1, in+1); + break; + case 27: + MyTemplateMatrix_return_T_27(nargout, out, nargin-1, in+1); + break; + case 28: + MyTemplateMatrix_return_Tptr_28(nargout, out, nargin-1, in+1); + break; + case 29: + MyTemplateMatrix_return_ptrs_29(nargout, out, nargin-1, in+1); + break; + case 30: + MyTemplateMatrix_templatedMethod_30(nargout, out, nargin-1, in+1); + break; + case 31: + MyTemplateMatrix_templatedMethod_31(nargout, out, nargin-1, in+1); + break; + case 32: + MyTemplateMatrix_templatedMethod_32(nargout, out, nargin-1, in+1); + break; + case 33: + MyTemplateMatrix_templatedMethod_33(nargout, out, nargin-1, in+1); + break; + case 34: + MyTemplateMatrix_Level_34(nargout, out, nargin-1, in+1); + break; + } + } catch(const std::exception& e) { + mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str()); + } + + std::cout.rdbuf(outbuf); +} diff --git a/tests/expected-matlab/load2D.m b/tests/expected/matlab/load2D.m similarity index 73% rename from tests/expected-matlab/load2D.m rename to tests/expected/matlab/load2D.m index 323054d3e..eebb4a5bf 100644 --- a/tests/expected-matlab/load2D.m +++ b/tests/expected/matlab/load2D.m @@ -1,10 +1,10 @@ function varargout = load2D(varargin) if length(varargin) == 5 && isa(varargin{1},'char') && isa(varargin{2},'Test') && isa(varargin{3},'numeric') && isa(varargin{4},'logical') && isa(varargin{5},'logical') - [ varargout{1} varargout{2} ] = geometry_wrapper(102, varargin{:}); + [ varargout{1} varargout{2} ] = functions_wrapper(0, varargin{:}); elseif length(varargin) == 5 && isa(varargin{1},'char') && isa(varargin{2},'gtsam.noiseModel.Diagonal') && isa(varargin{3},'numeric') && isa(varargin{4},'logical') && isa(varargin{5},'logical') - [ varargout{1} varargout{2} ] = geometry_wrapper(103, varargin{:}); + [ varargout{1} varargout{2} ] = functions_wrapper(1, varargin{:}); elseif length(varargin) == 2 && isa(varargin{1},'char') && isa(varargin{2},'gtsam.noiseModel.Diagonal') - [ varargout{1} varargout{2} ] = geometry_wrapper(104, varargin{:}); + [ varargout{1} varargout{2} ] = functions_wrapper(2, varargin{:}); else error('Arguments do not match any overload of function load2D'); end diff --git a/tests/expected/matlab/namespaces_wrapper.cpp b/tests/expected/matlab/namespaces_wrapper.cpp new file mode 100644 index 000000000..67bbb00c9 --- /dev/null +++ b/tests/expected/matlab/namespaces_wrapper.cpp @@ -0,0 +1,581 @@ +#include +#include + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include + +typedef Fun FunDouble; +typedef PrimitiveRef PrimitiveRefDouble; +typedef MyVector<3> MyVector3; +typedef MyVector<12> MyVector12; +typedef MultipleTemplates MultipleTemplatesIntDouble; +typedef MultipleTemplates MultipleTemplatesIntFloat; +typedef MyFactor MyFactorPosePoint2; +typedef MyTemplate MyTemplatePoint2; +typedef MyTemplate MyTemplateMatrix; + +BOOST_CLASS_EXPORT_GUID(gtsam::Point2, "gtsamPoint2"); +BOOST_CLASS_EXPORT_GUID(gtsam::Point3, "gtsamPoint3"); + +typedef std::set*> Collector_FunRange; +static Collector_FunRange collector_FunRange; +typedef std::set*> Collector_FunDouble; +static Collector_FunDouble collector_FunDouble; +typedef std::set*> Collector_Test; +static Collector_Test collector_Test; +typedef std::set*> Collector_PrimitiveRefDouble; +static Collector_PrimitiveRefDouble collector_PrimitiveRefDouble; +typedef std::set*> Collector_MyVector3; +static Collector_MyVector3 collector_MyVector3; +typedef std::set*> Collector_MyVector12; +static Collector_MyVector12 collector_MyVector12; +typedef std::set*> Collector_MultipleTemplatesIntDouble; +static Collector_MultipleTemplatesIntDouble collector_MultipleTemplatesIntDouble; +typedef std::set*> Collector_MultipleTemplatesIntFloat; +static Collector_MultipleTemplatesIntFloat collector_MultipleTemplatesIntFloat; +typedef std::set*> Collector_MyFactorPosePoint2; +static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2; +typedef std::set*> Collector_gtsamPoint2; +static Collector_gtsamPoint2 collector_gtsamPoint2; +typedef std::set*> Collector_gtsamPoint3; +static Collector_gtsamPoint3 collector_gtsamPoint3; +typedef std::set*> Collector_MyBase; +static Collector_MyBase collector_MyBase; +typedef std::set*> Collector_MyTemplatePoint2; +static Collector_MyTemplatePoint2 collector_MyTemplatePoint2; +typedef std::set*> Collector_MyTemplateMatrix; +static Collector_MyTemplateMatrix collector_MyTemplateMatrix; +typedef std::set*> Collector_ns1ClassA; +static Collector_ns1ClassA collector_ns1ClassA; +typedef std::set*> Collector_ns1ClassB; +static Collector_ns1ClassB collector_ns1ClassB; +typedef std::set*> Collector_ns2ClassA; +static Collector_ns2ClassA collector_ns2ClassA; +typedef std::set*> Collector_ns2ns3ClassB; +static Collector_ns2ns3ClassB collector_ns2ns3ClassB; +typedef std::set*> Collector_ns2ClassC; +static Collector_ns2ClassC collector_ns2ClassC; +typedef std::set*> Collector_ClassD; +static Collector_ClassD collector_ClassD; + +void _deleteAllObjects() +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + bool anyDeleted = false; + { for(Collector_FunRange::iterator iter = collector_FunRange.begin(); + iter != collector_FunRange.end(); ) { + delete *iter; + collector_FunRange.erase(iter++); + anyDeleted = true; + } } + { for(Collector_FunDouble::iterator iter = collector_FunDouble.begin(); + iter != collector_FunDouble.end(); ) { + delete *iter; + collector_FunDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_Test::iterator iter = collector_Test.begin(); + iter != collector_Test.end(); ) { + delete *iter; + collector_Test.erase(iter++); + anyDeleted = true; + } } + { for(Collector_PrimitiveRefDouble::iterator iter = collector_PrimitiveRefDouble.begin(); + iter != collector_PrimitiveRefDouble.end(); ) { + delete *iter; + collector_PrimitiveRefDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyVector3::iterator iter = collector_MyVector3.begin(); + iter != collector_MyVector3.end(); ) { + delete *iter; + collector_MyVector3.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyVector12::iterator iter = collector_MyVector12.begin(); + iter != collector_MyVector12.end(); ) { + delete *iter; + collector_MyVector12.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MultipleTemplatesIntDouble::iterator iter = collector_MultipleTemplatesIntDouble.begin(); + iter != collector_MultipleTemplatesIntDouble.end(); ) { + delete *iter; + collector_MultipleTemplatesIntDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MultipleTemplatesIntFloat::iterator iter = collector_MultipleTemplatesIntFloat.begin(); + iter != collector_MultipleTemplatesIntFloat.end(); ) { + delete *iter; + collector_MultipleTemplatesIntFloat.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyFactorPosePoint2::iterator iter = collector_MyFactorPosePoint2.begin(); + iter != collector_MyFactorPosePoint2.end(); ) { + delete *iter; + collector_MyFactorPosePoint2.erase(iter++); + anyDeleted = true; + } } + { for(Collector_gtsamPoint2::iterator iter = collector_gtsamPoint2.begin(); + iter != collector_gtsamPoint2.end(); ) { + delete *iter; + collector_gtsamPoint2.erase(iter++); + anyDeleted = true; + } } + { for(Collector_gtsamPoint3::iterator iter = collector_gtsamPoint3.begin(); + iter != collector_gtsamPoint3.end(); ) { + delete *iter; + collector_gtsamPoint3.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyBase::iterator iter = collector_MyBase.begin(); + iter != collector_MyBase.end(); ) { + delete *iter; + collector_MyBase.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyTemplatePoint2::iterator iter = collector_MyTemplatePoint2.begin(); + iter != collector_MyTemplatePoint2.end(); ) { + delete *iter; + collector_MyTemplatePoint2.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyTemplateMatrix::iterator iter = collector_MyTemplateMatrix.begin(); + iter != collector_MyTemplateMatrix.end(); ) { + delete *iter; + collector_MyTemplateMatrix.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ns1ClassA::iterator iter = collector_ns1ClassA.begin(); + iter != collector_ns1ClassA.end(); ) { + delete *iter; + collector_ns1ClassA.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ns1ClassB::iterator iter = collector_ns1ClassB.begin(); + iter != collector_ns1ClassB.end(); ) { + delete *iter; + collector_ns1ClassB.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ns2ClassA::iterator iter = collector_ns2ClassA.begin(); + iter != collector_ns2ClassA.end(); ) { + delete *iter; + collector_ns2ClassA.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ns2ns3ClassB::iterator iter = collector_ns2ns3ClassB.begin(); + iter != collector_ns2ns3ClassB.end(); ) { + delete *iter; + collector_ns2ns3ClassB.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ns2ClassC::iterator iter = collector_ns2ClassC.begin(); + iter != collector_ns2ClassC.end(); ) { + delete *iter; + collector_ns2ClassC.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ClassD::iterator iter = collector_ClassD.begin(); + iter != collector_ClassD.end(); ) { + delete *iter; + collector_ClassD.erase(iter++); + anyDeleted = true; + } } + if(anyDeleted) + cout << + "WARNING: Wrap modules with variables in the workspace have been reloaded due to\n" + "calling destructors, call 'clear all' again if you plan to now recompile a wrap\n" + "module, so that your recompiled module is used instead of the old one." << endl; + std::cout.rdbuf(outbuf); +} + +void _namespaces_RTTIRegister() { + const mxArray *alreadyCreated = mexGetVariablePtr("global", "gtsam_namespaces_rttiRegistry_created"); + if(!alreadyCreated) { + std::map types; + types.insert(std::make_pair(typeid(MyBase).name(), "MyBase")); + types.insert(std::make_pair(typeid(MyTemplatePoint2).name(), "MyTemplatePoint2")); + types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix")); + + mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); + if(!registry) + registry = mxCreateStructMatrix(1, 1, 0, NULL); + typedef std::pair StringPair; + for(const StringPair& rtti_matlab: types) { + int fieldId = mxAddField(registry, rtti_matlab.first.c_str()); + if(fieldId < 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str()); + mxSetFieldByNumber(registry, 0, fieldId, matlabName); + } + if(mexPutVariable("global", "gtsamwrap_rttiRegistry", registry) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(registry); + + mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL); + if(mexPutVariable("global", "gtsam_geometry_rttiRegistry_created", newAlreadyCreated) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(newAlreadyCreated); + } +} + +void ns1ClassA_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ns1ClassA.insert(self); +} + +void ns1ClassA_constructor_1(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ns1::ClassA()); + collector_ns1ClassA.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ns1ClassA_deconstructor_2(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ns1ClassA",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ns1ClassA::iterator item; + item = collector_ns1ClassA.find(self); + if(item != collector_ns1ClassA.end()) { + delete self; + collector_ns1ClassA.erase(item); + } +} + +void ns1ClassB_collectorInsertAndMakeBase_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ns1ClassB.insert(self); +} + +void ns1ClassB_constructor_4(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ns1::ClassB()); + collector_ns1ClassB.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ns1ClassB_deconstructor_5(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ns1ClassB",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ns1ClassB::iterator item; + item = collector_ns1ClassB.find(self); + if(item != collector_ns1ClassB.end()) { + delete self; + collector_ns1ClassB.erase(item); + } +} + +void aGlobalFunction_6(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("aGlobalFunction",nargout,nargin,0); + out[0] = wrap< Vector >(ns1::aGlobalFunction()); +} +void ns2ClassA_collectorInsertAndMakeBase_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ns2ClassA.insert(self); +} + +void ns2ClassA_constructor_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ns2::ClassA()); + collector_ns2ClassA.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ns2ClassA_deconstructor_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ns2ClassA",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ns2ClassA::iterator item; + item = collector_ns2ClassA.find(self); + if(item != collector_ns2ClassA.end()) { + delete self; + collector_ns2ClassA.erase(item); + } +} + +void ns2ClassA_memberFunction_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("memberFunction",nargout,nargin-1,0); + auto obj = unwrap_shared_ptr(in[0], "ptr_ns2ClassA"); + out[0] = wrap< double >(obj->memberFunction()); +} + +void ns2ClassA_nsArg_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("nsArg",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_ns2ClassA"); + ns1::ClassB& arg = *unwrap_shared_ptr< ns1::ClassB >(in[1], "ptr_ns1ClassB"); + out[0] = wrap< int >(obj->nsArg(arg)); +} + +void ns2ClassA_nsReturn_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("nsReturn",nargout,nargin-1,1); + auto obj = unwrap_shared_ptr(in[0], "ptr_ns2ClassA"); + double q = unwrap< double >(in[1]); + out[0] = wrap_shared_ptr(boost::make_shared(obj->nsReturn(q)),"ns2.ns3.ClassB", false); +} + +void ns2ClassA_afunction_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("ns2ClassA.afunction",nargout,nargin,0); + out[0] = wrap< double >(ns2::ClassA::afunction()); +} + +void ns2ns3ClassB_collectorInsertAndMakeBase_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ns2ns3ClassB.insert(self); +} + +void ns2ns3ClassB_constructor_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ns2::ns3::ClassB()); + collector_ns2ns3ClassB.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ns2ns3ClassB_deconstructor_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ns2ns3ClassB",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ns2ns3ClassB::iterator item; + item = collector_ns2ns3ClassB.find(self); + if(item != collector_ns2ns3ClassB.end()) { + delete self; + collector_ns2ns3ClassB.erase(item); + } +} + +void ns2ClassC_collectorInsertAndMakeBase_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ns2ClassC.insert(self); +} + +void ns2ClassC_constructor_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ns2::ClassC()); + collector_ns2ClassC.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ns2ClassC_deconstructor_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ns2ClassC",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ns2ClassC::iterator item; + item = collector_ns2ClassC.find(self); + if(item != collector_ns2ClassC.end()) { + delete self; + collector_ns2ClassC.erase(item); + } +} + +void aGlobalFunction_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("aGlobalFunction",nargout,nargin,0); + out[0] = wrap< Vector >(ns2::aGlobalFunction()); +} +void overloadedGlobalFunction_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("overloadedGlobalFunction",nargout,nargin,1); + ns1::ClassA& a = *unwrap_shared_ptr< ns1::ClassA >(in[0], "ptr_ns1ClassA"); + out[0] = wrap_shared_ptr(boost::make_shared(ns2::overloadedGlobalFunction(a)),"ns1.ClassA", false); +} +void overloadedGlobalFunction_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("overloadedGlobalFunction",nargout,nargin,2); + ns1::ClassA& a = *unwrap_shared_ptr< ns1::ClassA >(in[0], "ptr_ns1ClassA"); + double b = unwrap< double >(in[1]); + out[0] = wrap_shared_ptr(boost::make_shared(ns2::overloadedGlobalFunction(a,b)),"ns1.ClassA", false); +} +void ClassD_collectorInsertAndMakeBase_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_ClassD.insert(self); +} + +void ClassD_constructor_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = new Shared(new ClassD()); + collector_ClassD.insert(self); + out[0] = mxCreateNumericMatrix(1, 1, mxUINT32OR64_CLASS, mxREAL); + *reinterpret_cast (mxGetData(out[0])) = self; +} + +void ClassD_deconstructor_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_ClassD",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_ClassD::iterator item; + item = collector_ClassD.find(self); + if(item != collector_ClassD.end()) { + delete self; + collector_ClassD.erase(item); + } +} + + +void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + _namespaces_RTTIRegister(); + + int id = unwrap(in[0]); + + try { + switch(id) { + case 0: + ns1ClassA_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); + break; + case 1: + ns1ClassA_constructor_1(nargout, out, nargin-1, in+1); + break; + case 2: + ns1ClassA_deconstructor_2(nargout, out, nargin-1, in+1); + break; + case 3: + ns1ClassB_collectorInsertAndMakeBase_3(nargout, out, nargin-1, in+1); + break; + case 4: + ns1ClassB_constructor_4(nargout, out, nargin-1, in+1); + break; + case 5: + ns1ClassB_deconstructor_5(nargout, out, nargin-1, in+1); + break; + case 6: + aGlobalFunction_6(nargout, out, nargin-1, in+1); + break; + case 7: + ns2ClassA_collectorInsertAndMakeBase_7(nargout, out, nargin-1, in+1); + break; + case 8: + ns2ClassA_constructor_8(nargout, out, nargin-1, in+1); + break; + case 9: + ns2ClassA_deconstructor_9(nargout, out, nargin-1, in+1); + break; + case 10: + ns2ClassA_memberFunction_10(nargout, out, nargin-1, in+1); + break; + case 11: + ns2ClassA_nsArg_11(nargout, out, nargin-1, in+1); + break; + case 12: + ns2ClassA_nsReturn_12(nargout, out, nargin-1, in+1); + break; + case 13: + ns2ClassA_afunction_13(nargout, out, nargin-1, in+1); + break; + case 14: + ns2ns3ClassB_collectorInsertAndMakeBase_14(nargout, out, nargin-1, in+1); + break; + case 15: + ns2ns3ClassB_constructor_15(nargout, out, nargin-1, in+1); + break; + case 16: + ns2ns3ClassB_deconstructor_16(nargout, out, nargin-1, in+1); + break; + case 17: + ns2ClassC_collectorInsertAndMakeBase_17(nargout, out, nargin-1, in+1); + break; + case 18: + ns2ClassC_constructor_18(nargout, out, nargin-1, in+1); + break; + case 19: + ns2ClassC_deconstructor_19(nargout, out, nargin-1, in+1); + break; + case 20: + aGlobalFunction_20(nargout, out, nargin-1, in+1); + break; + case 21: + overloadedGlobalFunction_21(nargout, out, nargin-1, in+1); + break; + case 22: + overloadedGlobalFunction_22(nargout, out, nargin-1, in+1); + break; + case 23: + ClassD_collectorInsertAndMakeBase_23(nargout, out, nargin-1, in+1); + break; + case 24: + ClassD_constructor_24(nargout, out, nargin-1, in+1); + break; + case 25: + ClassD_deconstructor_25(nargout, out, nargin-1, in+1); + break; + } + } catch(const std::exception& e) { + mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str()); + } + + std::cout.rdbuf(outbuf); +} diff --git a/tests/expected-matlab/overloadedGlobalFunction.m b/tests/expected/matlab/overloadedGlobalFunction.m similarity index 73% rename from tests/expected-matlab/overloadedGlobalFunction.m rename to tests/expected/matlab/overloadedGlobalFunction.m index 5992abed1..e916c0adb 100644 --- a/tests/expected-matlab/overloadedGlobalFunction.m +++ b/tests/expected/matlab/overloadedGlobalFunction.m @@ -1,8 +1,8 @@ function varargout = overloadedGlobalFunction(varargin) if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = geometry_wrapper(106, varargin{:}); + varargout{1} = functions_wrapper(4, varargin{:}); elseif length(varargin) == 2 && isa(varargin{1},'numeric') && isa(varargin{2},'double') - varargout{1} = geometry_wrapper(107, varargin{:}); + varargout{1} = functions_wrapper(5, varargin{:}); else error('Arguments do not match any overload of function overloadedGlobalFunction'); end diff --git a/tests/expected/python/class_pybind.cpp b/tests/expected/python/class_pybind.cpp new file mode 100644 index 000000000..d6cbd91c5 --- /dev/null +++ b/tests/expected/python/class_pybind.cpp @@ -0,0 +1,86 @@ + + +#include +#include +#include +#include "gtsam/nonlinear/utilities.h" // for RedirectCout. + +#include "folder/path/to/Test.h" + +#include "wrap/serialization.h" +#include + + + + + +using namespace std; + +namespace py = pybind11; + +PYBIND11_MODULE(class_py, m_) { + m_.doc() = "pybind11 wrapper of class_py"; + + + py::class_>(m_, "FunRange") + .def(py::init<>()) + .def("range",[](FunRange* self, double d){return self->range(d);}, py::arg("d")) + .def_static("create",[](){return FunRange::create();}); + + py::class_, std::shared_ptr>>(m_, "FunDouble") + .def("dhamaalString",[](Fun* self, double d, string t){return self->dhamaal(d, t);}, py::arg("d"), py::arg("t")) + .def_static("divertido",[](){return Fun::divertido();}); + + py::class_>(m_, "Test") + .def(py::init<>()) + .def(py::init(), py::arg("a"), py::arg("b")) + .def("return_pair",[](Test* self, const gtsam::Vector& v, const gtsam::Matrix& A){return self->return_pair(v, A);}, py::arg("v"), py::arg("A")) + .def("return_pair",[](Test* self, const gtsam::Vector& v){return self->return_pair(v);}, py::arg("v")) + .def("return_bool",[](Test* self, bool value){return self->return_bool(value);}, py::arg("value")) + .def("return_size_t",[](Test* self, size_t value){return self->return_size_t(value);}, py::arg("value")) + .def("return_int",[](Test* self, int value){return self->return_int(value);}, py::arg("value")) + .def("return_double",[](Test* self, double value){return self->return_double(value);}, py::arg("value")) + .def("return_string",[](Test* self, string value){return self->return_string(value);}, py::arg("value")) + .def("return_vector1",[](Test* self, const gtsam::Vector& value){return self->return_vector1(value);}, py::arg("value")) + .def("return_matrix1",[](Test* self, const gtsam::Matrix& value){return self->return_matrix1(value);}, py::arg("value")) + .def("return_vector2",[](Test* self, const gtsam::Vector& value){return self->return_vector2(value);}, py::arg("value")) + .def("return_matrix2",[](Test* self, const gtsam::Matrix& value){return self->return_matrix2(value);}, py::arg("value")) + .def("arg_EigenConstRef",[](Test* self, const gtsam::Matrix& value){ self->arg_EigenConstRef(value);}, py::arg("value")) + .def("return_field",[](Test* self, const Test& t){return self->return_field(t);}, py::arg("t")) + .def("return_TestPtr",[](Test* self, const std::shared_ptr& value){return self->return_TestPtr(value);}, py::arg("value")) + .def("return_Test",[](Test* self, std::shared_ptr& value){return self->return_Test(value);}, py::arg("value")) + .def("return_Point2Ptr",[](Test* self, bool value){return self->return_Point2Ptr(value);}, py::arg("value")) + .def("create_ptrs",[](Test* self){return self->create_ptrs();}) + .def("create_MixedPtrs",[](Test* self){return self->create_MixedPtrs();}) + .def("return_ptrs",[](Test* self, std::shared_ptr& p1, std::shared_ptr& p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2")) + .def("print_",[](Test* self){ self->print();}) + .def("__repr__", + [](const Test &a) { + gtsam::RedirectCout redirect; + a.print(); + return redirect.str(); + }) + .def_readwrite("model_ptr", &Test::model_ptr); + + py::class_, std::shared_ptr>>(m_, "PrimitiveRefDouble") + .def(py::init<>()) + .def_static("Brutal",[](const double& t){return PrimitiveRef::Brutal(t);}, py::arg("t")); + + py::class_, std::shared_ptr>>(m_, "MyVector3") + .def(py::init<>()); + + py::class_, std::shared_ptr>>(m_, "MyVector12") + .def(py::init<>()); + + py::class_, std::shared_ptr>>(m_, "MultipleTemplatesIntDouble"); + + py::class_, std::shared_ptr>>(m_, "MultipleTemplatesIntFloat"); + + py::class_, std::shared_ptr>>(m_, "MyFactorPosePoint2") + .def(py::init&>(), py::arg("key1"), py::arg("key2"), py::arg("measured"), py::arg("noiseModel")); + + +#include "python/specializations.h" + +} + diff --git a/tests/expected/python/functions_pybind.cpp b/tests/expected/python/functions_pybind.cpp new file mode 100644 index 000000000..ac78563b9 --- /dev/null +++ b/tests/expected/python/functions_pybind.cpp @@ -0,0 +1,37 @@ + + +#include +#include +#include +#include "gtsam/nonlinear/utilities.h" // for RedirectCout. + + +#include "wrap/serialization.h" +#include + + + + + +using namespace std; + +namespace py = pybind11; + +PYBIND11_MODULE(functions_py, m_) { + m_.doc() = "pybind11 wrapper of functions_py"; + + + m_.def("load2D",[](string filename, std::shared_ptr& model, int maxID, bool addNoise, bool smart){return ::load2D(filename, model, maxID, addNoise, smart);}, py::arg("filename"), py::arg("model"), py::arg("maxID"), py::arg("addNoise"), py::arg("smart")); + m_.def("load2D",[](string filename, const std::shared_ptr& model, int maxID, bool addNoise, bool smart){return ::load2D(filename, model, maxID, addNoise, smart);}, py::arg("filename"), py::arg("model"), py::arg("maxID"), py::arg("addNoise"), py::arg("smart")); + m_.def("load2D",[](string filename, gtsam::noiseModel::Diagonal* model){return ::load2D(filename, model);}, py::arg("filename"), py::arg("model")); + m_.def("aGlobalFunction",[](){return ::aGlobalFunction();}); + m_.def("overloadedGlobalFunction",[](int a){return ::overloadedGlobalFunction(a);}, py::arg("a")); + m_.def("overloadedGlobalFunction",[](int a, double b){return ::overloadedGlobalFunction(a, b);}, py::arg("a"), py::arg("b")); + m_.def("MultiTemplatedFunctionStringSize_tDouble",[](const T& x, size_t y){return ::MultiTemplatedFunction(x, y);}, py::arg("x"), py::arg("y")); + m_.def("MultiTemplatedFunctionDoubleSize_tDouble",[](const T& x, size_t y){return ::MultiTemplatedFunction(x, y);}, py::arg("x"), py::arg("y")); + m_.def("TemplatedFunctionRot3",[](const gtsam::Rot3& t){ ::TemplatedFunction(t);}, py::arg("t")); + +#include "python/specializations.h" + +} + diff --git a/tests/expected/python/geometry_pybind.cpp b/tests/expected/python/geometry_pybind.cpp new file mode 100644 index 000000000..22a838215 --- /dev/null +++ b/tests/expected/python/geometry_pybind.cpp @@ -0,0 +1,67 @@ + + +#include +#include +#include +#include "gtsam/nonlinear/utilities.h" // for RedirectCout. + +#include "gtsam/geometry/Point2.h" +#include "gtsam/geometry/Point3.h" + +#include "wrap/serialization.h" +#include + +BOOST_CLASS_EXPORT(gtsam::Point2) +BOOST_CLASS_EXPORT(gtsam::Point3) + + + + +using namespace std; + +namespace py = pybind11; + +PYBIND11_MODULE(geometry_py, m_) { + m_.doc() = "pybind11 wrapper of geometry_py"; + + pybind11::module m_gtsam = m_.def_submodule("gtsam", "gtsam submodule"); + + py::class_>(m_gtsam, "Point2") + .def(py::init<>()) + .def(py::init(), py::arg("x"), py::arg("y")) + .def("x",[](gtsam::Point2* self){return self->x();}) + .def("y",[](gtsam::Point2* self){return self->y();}) + .def("dim",[](gtsam::Point2* self){return self->dim();}) + .def("returnChar",[](gtsam::Point2* self){return self->returnChar();}) + .def("argChar",[](gtsam::Point2* self, char a){ self->argChar(a);}, py::arg("a")) + .def("argChar",[](gtsam::Point2* self, std::shared_ptr& a){ self->argChar(a);}, py::arg("a")) + .def("argChar",[](gtsam::Point2* self, char& a){ self->argChar(a);}, py::arg("a")) + .def("argChar",[](gtsam::Point2* self, char* a){ self->argChar(a);}, py::arg("a")) + .def("argChar",[](gtsam::Point2* self, const std::shared_ptr& a){ self->argChar(a);}, py::arg("a")) + .def("argChar",[](gtsam::Point2* self, const char& a){ self->argChar(a);}, py::arg("a")) + .def("argChar",[](gtsam::Point2* self, const char* a){ self->argChar(a);}, py::arg("a")) + .def("argUChar",[](gtsam::Point2* self, unsigned char a){ self->argUChar(a);}, py::arg("a")) + .def("eigenArguments",[](gtsam::Point2* self, const gtsam::Vector& v, const gtsam::Matrix& m){ self->eigenArguments(v, m);}, py::arg("v"), py::arg("m")) + .def("vectorConfusion",[](gtsam::Point2* self){return self->vectorConfusion();}) + .def("serialize", [](gtsam::Point2* self){ return gtsam::serialize(*self); }) + .def("deserialize", [](gtsam::Point2* self, string serialized){ gtsam::deserialize(serialized, *self); }, py::arg("serialized")) + .def(py::pickle( + [](const gtsam::Point2 &a){ /* __getstate__: Returns a string that encodes the state of the object */ return py::make_tuple(gtsam::serialize(a)); }, + [](py::tuple t){ /* __setstate__ */ gtsam::Point2 obj; gtsam::deserialize(t[0].cast(), obj); return obj; })); + + py::class_>(m_gtsam, "Point3") + .def(py::init(), py::arg("x"), py::arg("y"), py::arg("z")) + .def("norm",[](gtsam::Point3* self){return self->norm();}) + .def("serialize", [](gtsam::Point3* self){ return gtsam::serialize(*self); }) + .def("deserialize", [](gtsam::Point3* self, string serialized){ gtsam::deserialize(serialized, *self); }, py::arg("serialized")) + .def(py::pickle( + [](const gtsam::Point3 &a){ /* __getstate__: Returns a string that encodes the state of the object */ return py::make_tuple(gtsam::serialize(a)); }, + [](py::tuple t){ /* __setstate__ */ gtsam::Point3 obj; gtsam::deserialize(t[0].cast(), obj); return obj; })) + .def_static("staticFunction",[](){return gtsam::Point3::staticFunction();}) + .def_static("StaticFunctionRet",[](double z){return gtsam::Point3::StaticFunctionRet(z);}, py::arg("z")); + + +#include "python/specializations.h" + +} + diff --git a/tests/expected/python/inheritance_pybind.cpp b/tests/expected/python/inheritance_pybind.cpp new file mode 100644 index 000000000..b349df706 --- /dev/null +++ b/tests/expected/python/inheritance_pybind.cpp @@ -0,0 +1,60 @@ + + +#include +#include +#include +#include "gtsam/nonlinear/utilities.h" // for RedirectCout. + + +#include "wrap/serialization.h" +#include + + + + + +using namespace std; + +namespace py = pybind11; + +PYBIND11_MODULE(inheritance_py, m_) { + m_.doc() = "pybind11 wrapper of inheritance_py"; + + + py::class_>(m_, "MyBase"); + + py::class_, MyBase, std::shared_ptr>>(m_, "MyTemplatePoint2") + .def(py::init<>()) + .def("templatedMethodPoint2",[](MyTemplate* self, const gtsam::Point2& t){return self->templatedMethod(t);}, py::arg("t")) + .def("templatedMethodPoint3",[](MyTemplate* self, const gtsam::Point3& t){return self->templatedMethod(t);}, py::arg("t")) + .def("templatedMethodVector",[](MyTemplate* self, const gtsam::Vector& t){return self->templatedMethod(t);}, py::arg("t")) + .def("templatedMethodMatrix",[](MyTemplate* self, const gtsam::Matrix& t){return self->templatedMethod(t);}, py::arg("t")) + .def("accept_T",[](MyTemplate* self, const gtsam::Point2& value){ self->accept_T(value);}, py::arg("value")) + .def("accept_Tptr",[](MyTemplate* self, std::shared_ptr& value){ self->accept_Tptr(value);}, py::arg("value")) + .def("return_Tptr",[](MyTemplate* self, std::shared_ptr& value){return self->return_Tptr(value);}, py::arg("value")) + .def("return_T",[](MyTemplate* self, gtsam::Point2* value){return self->return_T(value);}, py::arg("value")) + .def("create_ptrs",[](MyTemplate* self){return self->create_ptrs();}) + .def("create_MixedPtrs",[](MyTemplate* self){return self->create_MixedPtrs();}) + .def("return_ptrs",[](MyTemplate* self, std::shared_ptr& p1, std::shared_ptr& p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2")) + .def_static("Level",[](const gtsam::Point2& K){return MyTemplate::Level(K);}, py::arg("K")); + + py::class_, MyBase, std::shared_ptr>>(m_, "MyTemplateMatrix") + .def(py::init<>()) + .def("templatedMethodPoint2",[](MyTemplate* self, const gtsam::Point2& t){return self->templatedMethod(t);}, py::arg("t")) + .def("templatedMethodPoint3",[](MyTemplate* self, const gtsam::Point3& t){return self->templatedMethod(t);}, py::arg("t")) + .def("templatedMethodVector",[](MyTemplate* self, const gtsam::Vector& t){return self->templatedMethod(t);}, py::arg("t")) + .def("templatedMethodMatrix",[](MyTemplate* self, const gtsam::Matrix& t){return self->templatedMethod(t);}, py::arg("t")) + .def("accept_T",[](MyTemplate* self, const gtsam::Matrix& value){ self->accept_T(value);}, py::arg("value")) + .def("accept_Tptr",[](MyTemplate* self, const std::shared_ptr& value){ self->accept_Tptr(value);}, py::arg("value")) + .def("return_Tptr",[](MyTemplate* self, const std::shared_ptr& value){return self->return_Tptr(value);}, py::arg("value")) + .def("return_T",[](MyTemplate* self, const gtsam::Matrix* value){return self->return_T(value);}, py::arg("value")) + .def("create_ptrs",[](MyTemplate* self){return self->create_ptrs();}) + .def("create_MixedPtrs",[](MyTemplate* self){return self->create_MixedPtrs();}) + .def("return_ptrs",[](MyTemplate* self, const std::shared_ptr& p1, const std::shared_ptr& p2){return self->return_ptrs(p1, p2);}, py::arg("p1"), py::arg("p2")) + .def_static("Level",[](const gtsam::Matrix& K){return MyTemplate::Level(K);}, py::arg("K")); + + +#include "python/specializations.h" + +} + diff --git a/tests/expected-python/testNamespaces_py.cpp b/tests/expected/python/namespaces_pybind.cpp similarity index 95% rename from tests/expected-python/testNamespaces_py.cpp rename to tests/expected/python/namespaces_pybind.cpp index b115eea66..ee2f41c5d 100644 --- a/tests/expected-python/testNamespaces_py.cpp +++ b/tests/expected/python/namespaces_pybind.cpp @@ -22,8 +22,8 @@ using namespace std; namespace py = pybind11; -PYBIND11_MODULE(testNamespaces_py, m_) { - m_.doc() = "pybind11 wrapper of testNamespaces_py"; +PYBIND11_MODULE(namespaces_py, m_) { + m_.doc() = "pybind11 wrapper of namespaces_py"; pybind11::module m_ns1 = m_.def_submodule("ns1", "ns1 submodule"); diff --git a/tests/expected-xml-generation/xml/JacobianFactorQ_8h.xml b/tests/expected/xml/JacobianFactorQ_8h.xml similarity index 100% rename from tests/expected-xml-generation/xml/JacobianFactorQ_8h.xml rename to tests/expected/xml/JacobianFactorQ_8h.xml diff --git a/tests/expected-xml-generation/xml/NonlinearFactor_8h.xml b/tests/expected/xml/NonlinearFactor_8h.xml similarity index 100% rename from tests/expected-xml-generation/xml/NonlinearFactor_8h.xml rename to tests/expected/xml/NonlinearFactor_8h.xml diff --git a/tests/expected-xml-generation/xml/classgtsam_1_1JacobianFactorQ.xml b/tests/expected/xml/classgtsam_1_1JacobianFactorQ.xml similarity index 100% rename from tests/expected-xml-generation/xml/classgtsam_1_1JacobianFactorQ.xml rename to tests/expected/xml/classgtsam_1_1JacobianFactorQ.xml diff --git a/tests/expected-xml-generation/xml/classgtsam_1_1NoiseModelFactor.xml b/tests/expected/xml/classgtsam_1_1NoiseModelFactor.xml similarity index 100% rename from tests/expected-xml-generation/xml/classgtsam_1_1NoiseModelFactor.xml rename to tests/expected/xml/classgtsam_1_1NoiseModelFactor.xml diff --git a/tests/expected-xml-generation/xml/classgtsam_1_1NoiseModelFactor1.xml b/tests/expected/xml/classgtsam_1_1NoiseModelFactor1.xml similarity index 100% rename from tests/expected-xml-generation/xml/classgtsam_1_1NoiseModelFactor1.xml rename to tests/expected/xml/classgtsam_1_1NoiseModelFactor1.xml diff --git a/tests/expected-xml-generation/xml/classgtsam_1_1NoiseModelFactor2.xml b/tests/expected/xml/classgtsam_1_1NoiseModelFactor2.xml similarity index 100% rename from tests/expected-xml-generation/xml/classgtsam_1_1NoiseModelFactor2.xml rename to tests/expected/xml/classgtsam_1_1NoiseModelFactor2.xml diff --git a/tests/expected-xml-generation/xml/classgtsam_1_1NoiseModelFactor3.xml b/tests/expected/xml/classgtsam_1_1NoiseModelFactor3.xml similarity index 100% rename from tests/expected-xml-generation/xml/classgtsam_1_1NoiseModelFactor3.xml rename to tests/expected/xml/classgtsam_1_1NoiseModelFactor3.xml diff --git a/tests/expected-xml-generation/xml/classgtsam_1_1NoiseModelFactor4.xml b/tests/expected/xml/classgtsam_1_1NoiseModelFactor4.xml similarity index 100% rename from tests/expected-xml-generation/xml/classgtsam_1_1NoiseModelFactor4.xml rename to tests/expected/xml/classgtsam_1_1NoiseModelFactor4.xml diff --git a/tests/expected-xml-generation/xml/classgtsam_1_1NoiseModelFactor5.xml b/tests/expected/xml/classgtsam_1_1NoiseModelFactor5.xml similarity index 100% rename from tests/expected-xml-generation/xml/classgtsam_1_1NoiseModelFactor5.xml rename to tests/expected/xml/classgtsam_1_1NoiseModelFactor5.xml diff --git a/tests/expected-xml-generation/xml/classgtsam_1_1NoiseModelFactor6.xml b/tests/expected/xml/classgtsam_1_1NoiseModelFactor6.xml similarity index 100% rename from tests/expected-xml-generation/xml/classgtsam_1_1NoiseModelFactor6.xml rename to tests/expected/xml/classgtsam_1_1NoiseModelFactor6.xml diff --git a/tests/expected-xml-generation/xml/classgtsam_1_1NonlinearFactor.xml b/tests/expected/xml/classgtsam_1_1NonlinearFactor.xml similarity index 100% rename from tests/expected-xml-generation/xml/classgtsam_1_1NonlinearFactor.xml rename to tests/expected/xml/classgtsam_1_1NonlinearFactor.xml diff --git a/tests/expected-xml-generation/xml/combine.xslt b/tests/expected/xml/combine.xslt similarity index 100% rename from tests/expected-xml-generation/xml/combine.xslt rename to tests/expected/xml/combine.xslt diff --git a/tests/expected-xml-generation/xml/compound.xsd b/tests/expected/xml/compound.xsd similarity index 100% rename from tests/expected-xml-generation/xml/compound.xsd rename to tests/expected/xml/compound.xsd diff --git a/tests/expected-xml-generation/xml/deprecated.xml b/tests/expected/xml/deprecated.xml similarity index 100% rename from tests/expected-xml-generation/xml/deprecated.xml rename to tests/expected/xml/deprecated.xml diff --git a/tests/expected-xml-generation/xml/dir_59425e443f801f1f2fd8bbe4959a3ccf.xml b/tests/expected/xml/dir_59425e443f801f1f2fd8bbe4959a3ccf.xml similarity index 100% rename from tests/expected-xml-generation/xml/dir_59425e443f801f1f2fd8bbe4959a3ccf.xml rename to tests/expected/xml/dir_59425e443f801f1f2fd8bbe4959a3ccf.xml diff --git a/tests/expected-xml-generation/xml/dir_e4787312bc569bb879bb1171628269de.xml b/tests/expected/xml/dir_e4787312bc569bb879bb1171628269de.xml similarity index 100% rename from tests/expected-xml-generation/xml/dir_e4787312bc569bb879bb1171628269de.xml rename to tests/expected/xml/dir_e4787312bc569bb879bb1171628269de.xml diff --git a/tests/expected-xml-generation/xml/index.xml b/tests/expected/xml/index.xml similarity index 100% rename from tests/expected-xml-generation/xml/index.xml rename to tests/expected/xml/index.xml diff --git a/tests/expected-xml-generation/xml/index.xsd b/tests/expected/xml/index.xsd similarity index 100% rename from tests/expected-xml-generation/xml/index.xsd rename to tests/expected/xml/index.xsd diff --git a/tests/expected-xml-generation/xml/namespacegtsam.xml b/tests/expected/xml/namespacegtsam.xml similarity index 100% rename from tests/expected-xml-generation/xml/namespacegtsam.xml rename to tests/expected/xml/namespacegtsam.xml diff --git a/tests/expected-xml-generation/xml/structgtsam_1_1traits_3_01JacobianFactorQ_3_01D_00_01ZDim_01_4_01_4.xml b/tests/expected/xml/structgtsam_1_1traits_3_01JacobianFactorQ_3_01D_00_01ZDim_01_4_01_4.xml similarity index 100% rename from tests/expected-xml-generation/xml/structgtsam_1_1traits_3_01JacobianFactorQ_3_01D_00_01ZDim_01_4_01_4.xml rename to tests/expected/xml/structgtsam_1_1traits_3_01JacobianFactorQ_3_01D_00_01ZDim_01_4_01_4.xml diff --git a/tests/expected-xml-generation/xml/structgtsam_1_1traits_3_01NonlinearFactor_01_4.xml b/tests/expected/xml/structgtsam_1_1traits_3_01NonlinearFactor_01_4.xml similarity index 100% rename from tests/expected-xml-generation/xml/structgtsam_1_1traits_3_01NonlinearFactor_01_4.xml rename to tests/expected/xml/structgtsam_1_1traits_3_01NonlinearFactor_01_4.xml diff --git a/tests/fixtures/class.i b/tests/fixtures/class.i new file mode 100644 index 000000000..aca2567ce --- /dev/null +++ b/tests/fixtures/class.i @@ -0,0 +1,101 @@ +class FunRange { + FunRange(); + This range(double d); + + static This create(); +}; + +template +class Fun { + static This divertido(); + + template + This dhamaal(double d, T t); + + // template + // This pret(double d, T t, U u); +}; + + +// An include! Can go anywhere outside of a class, in any order +#include + +class Test { + + /* a comment! */ + // another comment + Test(); + + // Test a shared ptr property + gtsam::noiseModel::Base* model_ptr; + + pair return_pair (Vector v, Matrix A) const; // intentionally the first method + pair return_pair (Vector v) const; // overload + + bool return_bool (bool value) const; // comment after a line! + size_t return_size_t (size_t value) const; + int return_int (int value) const; + double return_double (double value) const; + + Test(double a, Matrix b); // a constructor in the middle of a class + + // comments in the middle! + + // (more) comments in the middle! + + string return_string (string value) const; + Vector return_vector1(Vector value) const; + Matrix return_matrix1(Matrix value) const; + Vector return_vector2(Vector value) const; + Matrix return_matrix2(Matrix value) const; + void arg_EigenConstRef(const Matrix& value) const; + + bool return_field(const Test& t) const; + + Test* return_TestPtr(const Test* value) const; + Test return_Test(Test* value) const; + + gtsam::Point2* return_Point2Ptr(bool value) const; + + pair create_ptrs () const; + pair create_MixedPtrs () const; + pair return_ptrs (Test* p1, Test* p2) const; + + void print() const; + + // comments at the end! + + // even more comments at the end! +}; + +virtual class ns::OtherClass; + +// A doubly templated class +template +class MyFactor { + MyFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); +}; + +// and a typedef specializing it +typedef MyFactor MyFactorPosePoint2; + +template +class PrimitiveRef { + PrimitiveRef(); + + static This Brutal(const T& t); +}; + +// A class with integer template arguments +template +class MyVector { + MyVector(); +}; + +// comments at the end! + +// even more comments at the end! + +// Class with multiple instantiated templates +template +class MultipleTemplates {}; diff --git a/tests/fixtures/functions.i b/tests/fixtures/functions.i new file mode 100644 index 000000000..d983ac97a --- /dev/null +++ b/tests/fixtures/functions.i @@ -0,0 +1,28 @@ +/** + * A multi-line comment! + */ +// another comment + +class gtsam::NonlinearFactorGraph; +class gtsam::Values; +class gtsam::noiseModel::Diagonal; + +pair load2D(string filename, Test* model, int maxID, bool addNoise, bool smart); +pair load2D(string filename, const gtsam::noiseModel::Diagonal* model, int maxID, bool addNoise, bool smart); +pair load2D(string filename, gtsam::noiseModel::Diagonal@ model); + +Vector aGlobalFunction(); + +// An overloaded global function +Vector overloadedGlobalFunction(int a); +Vector overloadedGlobalFunction(int a, double b); + +// A templated free/global function. Multiple templates supported. +template +R MultiTemplatedFunction(const T& x, T2 y); + +// Check if we can typedef the templated function +template +void TemplatedFunction(const T& t); + +typedef TemplatedFunction TemplatedFunctionRot3; diff --git a/tests/fixtures/geometry.i b/tests/fixtures/geometry.i new file mode 100644 index 000000000..a7b900f80 --- /dev/null +++ b/tests/fixtures/geometry.i @@ -0,0 +1,49 @@ +// comments! + +class VectorNotEigen; + +namespace gtsam { + +#include +class Point2 { + Point2(); + Point2(double x, double y); + double x() const; + double y() const; + int dim() const; + char returnChar() const; + void argChar(char a) const; + void argChar(char* a) const; + void argChar(char& a) const; + void argChar(char@ a) const; + void argChar(const char* a) const; + void argChar(const char& a) const; + void argChar(const char@ a) const; + void argUChar(unsigned char a) const; + void eigenArguments(Vector v, Matrix m) const; + VectorNotEigen vectorConfusion(); + + void serializable() const; // Sets flag and creates export, but does not make serialization functions + + // enable pickling in python + void pickle() const; +}; + +#include +class Point3 { + Point3(double x, double y, double z); + double norm() const; + + // static functions - use static keyword and uppercase + static double staticFunction(); + static gtsam::Point3 StaticFunctionRet(double z); + + // enabling serialization functionality + void serialize() const; // Just triggers a flag internally and removes actual function + + // enable pickling in python + void pickle() const; +}; + +} +// another comment diff --git a/tests/fixtures/inheritance.i b/tests/fixtures/inheritance.i new file mode 100644 index 000000000..e104c5b99 --- /dev/null +++ b/tests/fixtures/inheritance.i @@ -0,0 +1,24 @@ +// A base class +virtual class MyBase { + +}; + +// A templated class +template +virtual class MyTemplate : MyBase { + MyTemplate(); + + template + ARG templatedMethod(const ARG& t); + + // Stress test templates and pointer combinations + void accept_T(const T& value) const; + void accept_Tptr(T* value) const; + T* return_Tptr(T* value) const; + T return_T(T@ value) const; + pair create_ptrs () const; + pair create_MixedPtrs () const; + pair return_ptrs (T* p1, T* p2) const; + + static This Level(const T& K); +}; diff --git a/tests/testNamespaces.h b/tests/fixtures/namespaces.i similarity index 100% rename from tests/testNamespaces.h rename to tests/fixtures/namespaces.i diff --git a/tests/geometry.h b/tests/geometry.h deleted file mode 100644 index 23ec5ff23..000000000 --- a/tests/geometry.h +++ /dev/null @@ -1,185 +0,0 @@ - // comments! - -class VectorNotEigen; -virtual class ns::OtherClass; -class gtsam::NonlinearFactorGraph; -class gtsam::Values; -class gtsam::noiseModel::Diagonal; - -namespace gtsam { - -#include -class Point2 { - Point2(); - Point2(double x, double y); - double x() const; - double y() const; - int dim() const; - char returnChar() const; - void argChar(char a) const; - void argChar(char* a) const; - void argChar(char& a) const; - void argChar(char@ a) const; - void argChar(const char* a) const; - void argChar(const char& a) const; - void argChar(const char@ a) const; - void argUChar(unsigned char a) const; - void eigenArguments(Vector v, Matrix m) const; - VectorNotEigen vectorConfusion(); - - void serializable() const; // Sets flag and creates export, but does not make serialization functions - - // enable pickling in python - void pickle() const; -}; - -#include -class Point3 { - Point3(double x, double y, double z); - double norm() const; - - // static functions - use static keyword and uppercase - static double staticFunction(); - static gtsam::Point3 StaticFunctionRet(double z); - - // enabling serialization functionality - void serialize() const; // Just triggers a flag internally and removes actual function - - // enable pickling in python - void pickle() const; -}; - -} -// another comment - -// another comment - -/** - * A multi-line comment! - */ - -// An include! Can go anywhere outside of a class, in any order -#include - -class Test { - - /* a comment! */ - // another comment - Test(); - - // Test a shared ptr property - gtsam::noiseModel::Base* model_ptr; - - pair return_pair (Vector v, Matrix A) const; // intentionally the first method - pair return_pair (Vector v) const; // overload - - bool return_bool (bool value) const; // comment after a line! - size_t return_size_t (size_t value) const; - int return_int (int value) const; - double return_double (double value) const; - - Test(double a, Matrix b); // a constructor in the middle of a class - - // comments in the middle! - - // (more) comments in the middle! - - string return_string (string value) const; - Vector return_vector1(Vector value) const; - Matrix return_matrix1(Matrix value) const; - Vector return_vector2(Vector value) const; - Matrix return_matrix2(Matrix value) const; - void arg_EigenConstRef(const Matrix& value) const; - - bool return_field(const Test& t) const; - - Test* return_TestPtr(const Test* value) const; - Test return_Test(Test* value) const; - - gtsam::Point2* return_Point2Ptr(bool value) const; - - pair create_ptrs () const; - pair create_MixedPtrs () const; - pair return_ptrs (Test* p1, Test* p2) const; - - void print() const; - - // comments at the end! - - // even more comments at the end! -}; - -pair load2D(string filename, Test* model, int maxID, bool addNoise, bool smart); -pair load2D(string filename, const gtsam::noiseModel::Diagonal* model, int maxID, bool addNoise, bool smart); -pair load2D(string filename, gtsam::noiseModel::Diagonal@ model); - -Vector aGlobalFunction(); - -// An overloaded global function -Vector overloadedGlobalFunction(int a); -Vector overloadedGlobalFunction(int a, double b); - -// A base class -virtual class MyBase { - -}; - -// A templated class -template -virtual class MyTemplate : MyBase { - MyTemplate(); - - template - ARG templatedMethod(const ARG& t); - - // Stress test templates and pointer combinations - void accept_T(const T& value) const; - void accept_Tptr(T* value) const; - T* return_Tptr(T* value) const; - T return_T(T@ value) const; - pair create_ptrs () const; - pair create_MixedPtrs () const; - pair return_ptrs (T* p1, T* p2) const; - - static This Level(const T& K); -}; - -// A doubly templated class -template -class MyFactor { - MyFactor(size_t key1, size_t key2, double measured, const gtsam::noiseModel::Base* noiseModel); -}; - -// and a typedef specializing it -typedef MyFactor MyFactorPosePoint2; - -template -class PrimitiveRef { - PrimitiveRef(); - - static This Brutal(const T& t); -}; - -// A class with integer template arguments -template -class MyVector { - MyVector(); -}; - -// comments at the end! - -// even more comments at the end! - -// Class with multiple instantiated templates -template -class MultipleTemplates {}; - -// A templated free/global function. Multiple templates supported. -template -R MultiTemplatedFunction(const T& x, T2 y); - -// Check if we can typedef the templated function -template -void TemplatedFunction(const T& t); - -typedef TemplatedFunction TemplatedFunctionRot3; diff --git a/tests/test_docs.py b/tests/test_docs.py index f6bec8293..622d6d14f 100644 --- a/tests/test_docs.py +++ b/tests/test_docs.py @@ -5,7 +5,7 @@ Date: May 2019 """ import filecmp import os -import os.path as path +from os import path import shutil import sys import unittest @@ -34,24 +34,26 @@ class TestDocument(unittest.TestCase): DIR_NAME = path.dirname(__file__) DOC_DIR = 'doc-test-files' - OUTPUT_XML_DIR = 'actual-xml-generation' - EXPECTED_XML_DIR = 'expected-xml-generation' + OUTPUT_XML_DIR = 'actual/xml' + EXPECTED_XML_DIR = 'expected/xml' DOC_DIR_PATH = path.abspath(path.join(DIR_NAME, DOC_DIR)) OUTPUT_XML_DIR_PATH = path.abspath(path.join(DIR_NAME, OUTPUT_XML_DIR)) EXPECTED_XML_DIR_PATH = path.abspath(path.join(DIR_NAME, EXPECTED_XML_DIR)) + @unittest.skip("DOC_DIR_PATH doesn't exist") def test_generate_xml(self): """Test parse_xml.generate_xml""" if path.exists(self.OUTPUT_XML_DIR_PATH): shutil.rmtree(self.OUTPUT_XML_DIR_PATH, ignore_errors=True) + parser.generate_xml(self.DOC_DIR_PATH, self.OUTPUT_XML_DIR_PATH, quiet=True) self.assertTrue(os.path.isdir(self.OUTPUT_XML_DIR_PATH)) - xml_path = path.join(self.OUTPUT_XML_DIR_PATH, 'xml') + xml_path = self.OUTPUT_XML_DIR_PATH if path.exists(xml_path): shutil.rmtree(xml_path) parser.generate_xml(self.DOC_DIR_PATH, @@ -63,6 +65,7 @@ class TestDocument(unittest.TestCase): self.assertTrue(not dircmp.diff_files and not dircmp.funny_files) + @unittest.skip("DOC_DIR_PATH doesn't exist") def test_parse(self): """Test the parsing of the XML generated by Doxygen.""" docs = parser.ParseDoxygenXML(self.DOC_DIR_PATH, diff --git a/tests/test_matlab_wrapper.py b/tests/test_matlab_wrapper.py index ade85cb69..83398f72a 100644 --- a/tests/test_matlab_wrapper.py +++ b/tests/test_matlab_wrapper.py @@ -3,16 +3,17 @@ Unit tests for Matlab wrap program Author: Matthew Sklar, Varun Agrawal Date: March 2019 """ -# pylint: disable=import-error, wrong-import-position, too-many-branches +# pylint: disable=import-error, wrong-import-position import filecmp import os +import os.path as osp import sys import unittest from loguru import logger -sys.path.append(os.path.dirname(os.path.dirname(os.path.abspath(__file__)))) +sys.path.append(osp.dirname(osp.dirname(osp.abspath(__file__)))) import gtwrap.interface_parser as parser import gtwrap.template_instantiator as instantiator @@ -23,9 +24,13 @@ class TestWrap(unittest.TestCase): """ Test the Matlab wrapper """ - TEST_DIR = os.path.dirname(os.path.realpath(__file__)) + "/" - MATLAB_TEST_DIR = TEST_DIR + "expected-matlab/" - MATLAB_ACTUAL_DIR = TEST_DIR + "actual-matlab/" + TEST_DIR = osp.dirname(osp.realpath(__file__)) + INTERFACE_DIR = osp.join(TEST_DIR, "fixtures") + MATLAB_TEST_DIR = osp.join(TEST_DIR, "expected", "matlab") + MATLAB_ACTUAL_DIR = osp.join(TEST_DIR, "actual", "matlab") + + # Create the `actual/matlab` directory + os.makedirs(MATLAB_ACTUAL_DIR, exist_ok=True) # set the log level to INFO by default logger.remove() # remove the default sink @@ -48,9 +53,9 @@ class TestWrap(unittest.TestCase): if len(c) == 0: continue logger.debug("c object: {}".format(c[0][0])) - path_to_folder = path + '/' + c[0][0] + path_to_folder = osp.join(path, c[0][0]) - if not os.path.isdir(path_to_folder): + if not osp.isdir(path_to_folder): try: os.makedirs(path_to_folder, exist_ok=True) except OSError: @@ -61,26 +66,27 @@ class TestWrap(unittest.TestCase): self.generate_content(sub_content[1], path_to_folder) elif isinstance(c[1], list): - path_to_folder = path + '/' + c[0] + path_to_folder = osp.join(path, c[0]) - logger.debug("[generate_content_global]: {}".format(path_to_folder)) - if not os.path.isdir(path_to_folder): + logger.debug( + "[generate_content_global]: {}".format(path_to_folder)) + if not osp.isdir(path_to_folder): try: os.makedirs(path_to_folder, exist_ok=True) except OSError: pass for sub_content in c[1]: - path_to_file = path_to_folder + '/' + sub_content[0] + path_to_file = osp.join(path_to_folder, sub_content[0]) logger.debug( "[generate_global_method]: {}".format(path_to_file)) with open(path_to_file, 'w') as f: f.write(sub_content[1]) else: - path_to_file = path + '/' + c[0] + path_to_file = osp.join(path, c[0]) logger.debug("[generate_content]: {}".format(path_to_file)) - if not os.path.isdir(path_to_file): + if not osp.isdir(path_to_file): try: os.mkdir(path) except OSError: @@ -89,16 +95,29 @@ class TestWrap(unittest.TestCase): with open(path_to_file, 'w') as f: f.write(c[1]) - def test_geometry_matlab(self): + def compare_and_diff(self, file): + """ + Compute the comparison between the expected and actual file, + and assert if diff is zero. + """ + output = osp.join(self.MATLAB_ACTUAL_DIR, file) + expected = osp.join(self.MATLAB_TEST_DIR, file) + success = filecmp.cmp(output, expected) + if not success: + print("Differ in file: {}".format(file)) + os.system("diff {} {}".format(output, expected)) + self.assertTrue(success, "Mismatch for file {0}".format(file)) + + def test_geometry(self): """ Check generation of matlab geometry wrapper. python3 wrap/matlab_wrapper.py --src wrap/tests/geometry.h --module_name geometry --out wrap/tests/actual-matlab """ - with open(self.TEST_DIR + 'geometry.h', 'r') as f: + with open(osp.join(self.INTERFACE_DIR, 'geometry.i'), 'r') as f: content = f.read() - if not os.path.exists(self.MATLAB_ACTUAL_DIR): + if not osp.exists(self.MATLAB_ACTUAL_DIR): os.mkdir(self.MATLAB_ACTUAL_DIR) module = parser.Module.parseString(content) @@ -117,27 +136,144 @@ class TestWrap(unittest.TestCase): self.generate_content(cc_content) - def compare_and_diff(file): - output = self.MATLAB_ACTUAL_DIR + file - expected = self.MATLAB_TEST_DIR + file - success = filecmp.cmp(output, expected) - if not success: - print("Differ in file: {}".format(file)) - os.system("diff {} {}".format(output, expected)) - self.assertTrue(success) + self.assertTrue(osp.isdir(osp.join(self.MATLAB_ACTUAL_DIR, '+gtsam'))) - self.assertTrue(os.path.isdir(self.MATLAB_ACTUAL_DIR + '+gtsam')) + files = ['+gtsam/Point2.m', '+gtsam/Point3.m', 'geometry_wrapper.cpp'] + + for file in files: + self.compare_and_diff(file) + + def test_functions(self): + """Test interface file with function info.""" + with open(osp.join(self.INTERFACE_DIR, 'functions.i'), 'r') as f: + content = f.read() + + if not osp.exists(self.MATLAB_ACTUAL_DIR): + os.mkdir(self.MATLAB_ACTUAL_DIR) + + module = parser.Module.parseString(content) + + instantiator.instantiate_namespace_inplace(module) + + wrapper = MatlabWrapper( + module=module, + module_name='functions', + top_module_namespace=['gtsam'], + ignore_classes=[''], + ) + + cc_content = wrapper.wrap() + + self.generate_content(cc_content) files = [ - '+gtsam/Point2.m', '+gtsam/Point3.m', 'Test.m', 'MyBase.m', - 'load2D.m', 'MyTemplatePoint2.m', 'MyTemplateMatrix.m', - 'MyVector3.m', 'MyVector12.m', 'MyFactorPosePoint2.m', - 'aGlobalFunction.m', 'overloadedGlobalFunction.m', - 'geometry_wrapper.cpp' + 'functions_wrapper.cpp', 'aGlobalFunction.m', 'load2D.m', + 'MultiTemplatedFunctionDoubleSize_tDouble.m', + 'MultiTemplatedFunctionStringSize_tDouble.m', + 'overloadedGlobalFunction.m', 'TemplatedFunctionRot3.m' ] for file in files: - compare_and_diff(file) + self.compare_and_diff(file) + + def test_class(self): + """Test interface file with only class info.""" + with open(osp.join(self.INTERFACE_DIR, 'class.i'), 'r') as f: + content = f.read() + + if not osp.exists(self.MATLAB_ACTUAL_DIR): + os.mkdir(self.MATLAB_ACTUAL_DIR) + + module = parser.Module.parseString(content) + + instantiator.instantiate_namespace_inplace(module) + + wrapper = MatlabWrapper( + module=module, + module_name='class', + top_module_namespace=['gtsam'], + ignore_classes=[''], + ) + + cc_content = wrapper.wrap() + + self.generate_content(cc_content) + + files = [ + 'class_wrapper.cpp', 'FunDouble.m', 'FunRange.m', + 'MultipleTemplatesIntDouble.m', 'MultipleTemplatesIntFloat.m', + 'MyFactorPosePoint2.m', 'MyVector3.m', 'MyVector12.m', + 'PrimitiveRefDouble.m', 'Test.m' + ] + + for file in files: + self.compare_and_diff(file) + + def test_inheritance(self): + """Test interface file with class inheritance definitions.""" + with open(osp.join(self.INTERFACE_DIR, 'inheritance.i'), 'r') as f: + content = f.read() + + if not osp.exists(self.MATLAB_ACTUAL_DIR): + os.mkdir(self.MATLAB_ACTUAL_DIR) + + module = parser.Module.parseString(content) + + instantiator.instantiate_namespace_inplace(module) + + wrapper = MatlabWrapper( + module=module, + module_name='inheritance', + top_module_namespace=['gtsam'], + ignore_classes=[''], + ) + + cc_content = wrapper.wrap() + + self.generate_content(cc_content) + + files = [ + 'inheritance_wrapper.cpp', 'MyBase.m', 'MyTemplateMatrix.m', + 'MyTemplatePoint2.m' + ] + + for file in files: + self.compare_and_diff(file) + + def test_namspaces(self): + """ + Test interface file with full namespace definition. + """ + with open(osp.join(self.INTERFACE_DIR, 'namespaces.i'), 'r') as f: + content = f.read() + + if not osp.exists(self.MATLAB_ACTUAL_DIR): + os.mkdir(self.MATLAB_ACTUAL_DIR) + + module = parser.Module.parseString(content) + + instantiator.instantiate_namespace_inplace(module) + + wrapper = MatlabWrapper( + module=module, + module_name='namespaces', + top_module_namespace=['gtsam'], + ignore_classes=[''], + ) + + cc_content = wrapper.wrap() + + self.generate_content(cc_content) + + files = [ + 'namespaces_wrapper.cpp', '+ns1/aGlobalFunction.m', + '+ns1/ClassA.m', '+ns1/ClassB.m', '+ns2/+ns3/ClassB.m', + '+ns2/aGlobalFunction.m', '+ns2/ClassA.m', '+ns2/ClassC.m', + '+ns2/overloadedGlobalFunction.m', 'ClassD.m' + ] + + for file in files: + self.compare_and_diff(file) if __name__ == '__main__': diff --git a/tests/test_pybind_wrapper.py b/tests/test_pybind_wrapper.py index e2fdbe3bb..5f6b82141 100644 --- a/tests/test_pybind_wrapper.py +++ b/tests/test_pybind_wrapper.py @@ -8,25 +8,30 @@ Date: February 2019 import filecmp import os -import os.path as path +import os.path as osp import sys import unittest -sys.path.append(os.path.dirname(os.path.dirname(os.path.abspath(__file__)))) +sys.path.append(osp.dirname(osp.dirname(osp.abspath(__file__)))) sys.path.append( - os.path.normpath( - os.path.abspath(os.path.join(__file__, '../../../build/wrap')))) + osp.normpath(osp.abspath(osp.join(__file__, '../../../build/wrap')))) import gtwrap.interface_parser as parser import gtwrap.template_instantiator as instantiator from gtwrap.pybind_wrapper import PybindWrapper -sys.path.append(os.path.dirname(os.path.dirname(os.path.abspath(__file__)))) +sys.path.append(osp.dirname(osp.dirname(osp.abspath(__file__)))) class TestWrap(unittest.TestCase): """Tests for Python wrapper based on Pybind11.""" - TEST_DIR = os.path.dirname(os.path.realpath(__file__)) + "/" + TEST_DIR = osp.dirname(osp.realpath(__file__)) + INTERFACE_DIR = osp.join(TEST_DIR, 'fixtures') + PYTHON_TEST_DIR = osp.join(TEST_DIR, 'expected', 'python') + PYTHON_ACTUAL_DIR = osp.join(TEST_DIR, "actual", "python") + + # Create the `actual/python` directory + os.makedirs(PYTHON_ACTUAL_DIR, exist_ok=True) def wrap_content(self, content, module_name, output_dir): """ @@ -36,7 +41,8 @@ class TestWrap(unittest.TestCase): instantiator.instantiate_namespace_inplace(module) - with open(self.TEST_DIR + "pybind_wrapper.tpl") as template_file: + with open(osp.join(self.TEST_DIR, + "pybind_wrapper.tpl")) as template_file: module_template = template_file.read() # Create Pybind wrapper instance @@ -49,54 +55,84 @@ class TestWrap(unittest.TestCase): cc_content = wrapper.wrap() - output = path.join(self.TEST_DIR, output_dir, module_name + ".cpp") + output = osp.join(self.TEST_DIR, output_dir, module_name + ".cpp") - if not path.exists(path.join(self.TEST_DIR, output_dir)): - os.mkdir(path.join(self.TEST_DIR, output_dir)) + if not osp.exists(osp.join(self.TEST_DIR, output_dir)): + os.mkdir(osp.join(self.TEST_DIR, output_dir)) with open(output, 'w') as f: f.write(cc_content) return output - def test_geometry_python(self): + def compare_and_diff(self, file, actual): + """ + Compute the comparison between the expected and actual file, + and assert if diff is zero. + """ + expected = osp.join(self.PYTHON_TEST_DIR, file) + success = filecmp.cmp(actual, expected) + + if not success: + os.system("diff {} {}".format(actual, expected)) + self.assertTrue(success, "Mismatch for file {0}".format(file)) + + def test_geometry(self): """ Check generation of python geometry wrapper. python3 ../pybind_wrapper.py --src geometry.h --module_name geometry_py --out output/geometry_py.cc """ - with open(os.path.join(self.TEST_DIR, 'geometry.h'), 'r') as f: + with open(osp.join(self.INTERFACE_DIR, 'geometry.i'), 'r') as f: content = f.read() - output = self.wrap_content(content, 'geometry_py', 'actual-python') + output = self.wrap_content(content, 'geometry_py', + self.PYTHON_ACTUAL_DIR) - expected = path.join(self.TEST_DIR, - 'expected-python/geometry_pybind.cpp') - success = filecmp.cmp(output, expected) + self.compare_and_diff('geometry_pybind.cpp', output) - if not success: - os.system("diff {} {}".format(output, expected)) - self.assertTrue(success) + def test_functions(self): + """Test interface file with function info.""" + with open(osp.join(self.INTERFACE_DIR, 'functions.i'), 'r') as f: + content = f.read() + + output = self.wrap_content(content, 'functions_py', + self.PYTHON_ACTUAL_DIR) + + self.compare_and_diff('functions_pybind.cpp', output) + + def test_class(self): + """Test interface file with only class info.""" + with open(osp.join(self.INTERFACE_DIR, 'class.i'), 'r') as f: + content = f.read() + + output = self.wrap_content(content, 'class_py', self.PYTHON_ACTUAL_DIR) + + self.compare_and_diff('class_pybind.cpp', output) + + def test_inheritance(self): + """Test interface file with class inheritance definitions.""" + with open(osp.join(self.INTERFACE_DIR, 'inheritance.i'), 'r') as f: + content = f.read() + + output = self.wrap_content(content, 'inheritance_py', + self.PYTHON_ACTUAL_DIR) + + self.compare_and_diff('inheritance_pybind.cpp', output) def test_namespaces(self): """ - Check generation of python geometry wrapper. - python3 ../pybind_wrapper.py --src testNamespaces.h --module_name - testNamespaces_py --out output/testNamespaces_py.cc + Check generation of python wrapper for full namespace definition. + python3 ../pybind_wrapper.py --src namespaces.i --module_name + namespaces_py --out output/namespaces_py.cpp """ - with open(os.path.join(self.TEST_DIR, 'testNamespaces.h'), 'r') as f: + with open(osp.join(self.INTERFACE_DIR, 'namespaces.i'), 'r') as f: content = f.read() - output = self.wrap_content(content, 'testNamespaces_py', - 'actual-python') + output = self.wrap_content(content, 'namespaces_py', + self.PYTHON_ACTUAL_DIR) - expected = path.join(self.TEST_DIR, - 'expected-python/testNamespaces_py.cpp') - success = filecmp.cmp(output, expected) - - if not success: - os.system("diff {} {}".format(output, expected)) - self.assertTrue(success) + self.compare_and_diff('namespaces_pybind.cpp', output) if __name__ == '__main__': From 82d6e68e908899c2f4f23485ff7016be260d6708 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 25 Mar 2021 02:09:42 -0400 Subject: [PATCH 12/21] switch back to simple python3 --- .github/workflows/build-python.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/build-python.yml b/.github/workflows/build-python.yml index fa7327faf..089ee3246 100644 --- a/.github/workflows/build-python.yml +++ b/.github/workflows/build-python.yml @@ -29,7 +29,7 @@ jobs: #TODO update wrapper to prevent OOM # build_type: [Debug, Release] build_type: [Release] - python_version: [3.6] + python_version: [3] include: - name: ubuntu-18.04-gcc-5 os: ubuntu-18.04 From b7e19d6033ca397a6f6e6f2b897f0527eedb4c07 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 25 Mar 2021 09:41:42 -0400 Subject: [PATCH 13/21] fix number of arguments to matlab_wrap for unstable --- matlab/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/matlab/CMakeLists.txt b/matlab/CMakeLists.txt index c8d6d197f..3c234d106 100644 --- a/matlab/CMakeLists.txt +++ b/matlab/CMakeLists.txt @@ -77,7 +77,7 @@ if(GTSAM_UNSTABLE_INSTALL_MATLAB_TOOLBOX) # Wrap matlab_wrap(${GTSAM_SOURCE_DIR}/gtsam_unstable/gtsam_unstable.i "gtsam" "" - "${mexFlags}") + "${mexFlags}" "${ignore}") endif(GTSAM_UNSTABLE_INSTALL_MATLAB_TOOLBOX) # Record the root dir for gtsam - needed during external builds, e.g., ROS From 34aae4f72ae20c683b9082a1ad1485af3271090e Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Thu, 25 Mar 2021 13:32:38 -0400 Subject: [PATCH 14/21] Squashed 'wrap/' changes from 29628426d..9a467794e 9a467794e Merge pull request #61 from borglab/fix/python-variables 6bae7af99 added more status messages and set the PYBIND11_PYTHON_VERSION each time 5129cf3b9 set both sets of Python variables and find python version when including PybindWrap 5a67b526c Merge pull request #60 from borglab/fix/multi-template-methods 4a73b29ef better method names for testing templated methods 989fdf946 added unit test for multi-template methods a56908c21 add namespace qualification to instantiations a25d9631e graceful handling of templated method instantiations 0baa5ab5d multiple templates in methods git-subtree-dir: wrap git-subtree-split: 9a467794e8542872b2782cdaec338aaa30a92e33 --- cmake/GtwrapUtils.cmake | 22 +- cmake/PybindWrap.cmake | 10 +- gtwrap/matlab_wrapper.py | 6 +- gtwrap/template_instantiator.py | 79 ++++---- tests/expected/matlab/FunDouble.m | 31 ++- .../matlab/MultipleTemplatesIntDouble.m | 4 +- .../matlab/MultipleTemplatesIntFloat.m | 4 +- tests/expected/matlab/MyFactorPosePoint2.m | 6 +- tests/expected/matlab/MyVector12.m | 6 +- tests/expected/matlab/MyVector3.m | 6 +- tests/expected/matlab/PrimitiveRefDouble.m | 8 +- tests/expected/matlab/Test.m | 48 ++--- tests/expected/matlab/class_wrapper.cpp | 189 ++++++++++-------- tests/expected/python/class_pybind.cpp | 5 +- tests/fixtures/class.i | 8 +- 15 files changed, 240 insertions(+), 192 deletions(-) diff --git a/cmake/GtwrapUtils.cmake b/cmake/GtwrapUtils.cmake index acf075c5b..01cdd32b9 100644 --- a/cmake/GtwrapUtils.cmake +++ b/cmake/GtwrapUtils.cmake @@ -15,16 +15,16 @@ macro(get_python_version) set(Python_VERSION_MAJOR ${PYTHON_VERSION_MAJOR} - PARENT_SCOPE) + CACHE INTERNAL "") set(Python_VERSION_MINOR ${PYTHON_VERSION_MINOR} - PARENT_SCOPE) + CACHE INTERNAL "") set(Python_VERSION_PATCH ${PYTHON_VERSION_PATCH} - PARENT_SCOPE) + CACHE INTERNAL "") set(Python_EXECUTABLE ${PYTHON_EXECUTABLE} - PARENT_SCOPE) + CACHE INTERNAL "") else() # Get info about the Python interpreter @@ -37,6 +37,20 @@ macro(get_python_version) "Cannot find Python interpreter. Please install Python>=3.5.") endif() + # Set both sets of variables + set(PYTHON_VERSION_MAJOR + ${Python_VERSION_MAJOR} + CACHE INTERNAL "") + set(PYTHON_VERSION_MINOR + ${Python_VERSION_MINOR} + CACHE INTERNAL "") + set(PYTHON_VERSION_PATCH + ${Python_VERSION_PATCH} + CACHE INTERNAL "") + set(PYTHON_EXECUTABLE + ${Python_EXECUTABLE} + CACHE INTERNAL "") + endif() endmacro() diff --git a/cmake/PybindWrap.cmake b/cmake/PybindWrap.cmake index c7c47a662..2c07e2b50 100644 --- a/cmake/PybindWrap.cmake +++ b/cmake/PybindWrap.cmake @@ -1,5 +1,3 @@ -set(PYBIND11_PYTHON_VERSION ${WRAP_PYTHON_VERSION}) - if(GTWRAP_PYTHON_PACKAGE_DIR) # packaged set(GTWRAP_PACKAGE_DIR "${GTWRAP_PYTHON_PACKAGE_DIR}") @@ -7,6 +5,14 @@ else() set(GTWRAP_PACKAGE_DIR ${CMAKE_CURRENT_LIST_DIR}/..) endif() +# Get the Python version +include(GtwrapUtils) +message(status "Checking Python Version") +gtwrap_get_python_version(${WRAP_PYTHON_VERSION}) + +message(status "Setting Python version for wrapper") +set(PYBIND11_PYTHON_VERSION ${WRAP_PYTHON_VERSION}) + # User-friendly Pybind11 wrapping and installing function. # Builds a Pybind11 module from the provided interface_header. # For example, for the interface header gtsam.h, this will diff --git a/gtwrap/matlab_wrapper.py b/gtwrap/matlab_wrapper.py index 0c5a6a4bc..1f9f3146f 100755 --- a/gtwrap/matlab_wrapper.py +++ b/gtwrap/matlab_wrapper.py @@ -348,7 +348,7 @@ class MatlabWrapper(object): method += instance_method.parent.name + separator method += instance_method.original.name - method += "<" + instance_method.instantiation.to_cpp() + ">" + method += "<" + instance_method.instantiations.to_cpp() + ">" return method[2 * len(separator):] @@ -1337,9 +1337,9 @@ class MatlabWrapper(object): method_name = method.to_cpp() obj_start = 'obj->' - if method.instantiation: + if method.instantiations: # method_name += '<{}>'.format( - # self._format_type_name(method.instantiation)) + # self._format_type_name(method.instantiations)) # method_name = self._format_instance_method(method, '::') method = method.to_cpp() diff --git a/gtwrap/template_instantiator.py b/gtwrap/template_instantiator.py index 65a1e7227..7ae79e217 100644 --- a/gtwrap/template_instantiator.py +++ b/gtwrap/template_instantiator.py @@ -206,40 +206,35 @@ class InstantiatedMethod(parser.Method): """ We can only instantiate template methods with a single template parameter. """ - def __init__(self, original, instantiation=''): + def __init__(self, original, instantiations=''): self.original = original - self.instantiation = instantiation + self.instantiations = instantiations self.template = '' self.is_const = original.is_const self.parent = original.parent - if not original.template: - self.name = original.name - self.return_type = original.return_type - self.args = original.args - else: - #TODO(Varun) enable multiple templates for methods - if len(self.original.template.typenames) > 1: - raise ValueError("Can only instantiate template method with " - "single template parameter.") - self.name = instantiate_name(original.name, [self.instantiation]) - self.return_type = instantiate_return_type( - original.return_type, - [self.original.template.typenames[0]], - [self.instantiation], - # Keyword type name `This` should already be replaced in the - # previous class template instantiation round. - cpp_typename='', - ) - instantiated_args = instantiate_args_list( - original.args.args_list, - [self.original.template.typenames[0]], - [self.instantiation], - # Keyword type name `This` should already be replaced in the - # previous class template instantiation round. - cpp_typename='', - ) - self.args = parser.ArgumentList(instantiated_args) + # Check for typenames if templated. + # This way, we can gracefully handle bot templated and non-templated methois. + typenames = self.original.template.typenames if self.original.template else [] + self.name = instantiate_name(original.name, self.instantiations) + self.return_type = instantiate_return_type( + original.return_type, + typenames, + self.instantiations, + # Keyword type name `This` should already be replaced in the + # previous class template instantiation round. + cpp_typename='', + ) + + instantiated_args = instantiate_args_list( + original.args.args_list, + typenames, + self.instantiations, + # Keyword type name `This` should already be replaced in the + # previous class template instantiation round. + cpp_typename='', + ) + self.args = parser.ArgumentList(instantiated_args) super().__init__(self.template, self.name, @@ -251,7 +246,13 @@ class InstantiatedMethod(parser.Method): def to_cpp(self): """Generate the C++ code for wrapping.""" if self.original.template: - ret = "{}<{}>".format(self.original.name, self.instantiation) + instantiation_list = [ + # Get the fully qualified name + "::".join(x.namespaces + [x.name]) + for x in self.instantiations + ] + ret = "{}<{}>".format(self.original.name, + ",".join(instantiation_list)) else: ret = self.original.name return ret @@ -293,12 +294,13 @@ class InstantiatedClass(parser.Class): # This will allow the `This` keyword to be used in both templated and non-templated classes. typenames = self.original.template.typenames if self.original.template else [] - # Instantiate the constructors, static methods, properties and instance methods, respectively. + # Instantiate the constructors, static methods, properties + # and instance methods, respectively. self.ctors = self.instantiate_ctors(typenames) self.static_methods = self.instantiate_static_methods(typenames) self.properties = self.instantiate_properties(typenames) - instantiated_methods = self.instantiate_class_templates_in_methods( - typenames) + instantiated_methods = \ + self.instantiate_class_templates_in_methods(typenames) # Second instantiation round to instantiate templated methods. # This is done in case both the class and the method are templated. @@ -307,11 +309,12 @@ class InstantiatedClass(parser.Class): if not method.template: self.methods.append(InstantiatedMethod(method, '')) else: - assert len( - method.template.typenames) == 1, ""\ - "Can only instantiate single template methods" - for inst in method.template.instantiations[0]: - self.methods.append(InstantiatedMethod(method, inst)) + instantiations = [] + # Get all combinations of template parameters + for instantiations in itertools.product( + *method.template.instantiations): + self.methods.append( + InstantiatedMethod(method, instantiations)) super().__init__( self.template, diff --git a/tests/expected/matlab/FunDouble.m b/tests/expected/matlab/FunDouble.m index b6c57cd0c..ca0efcacf 100644 --- a/tests/expected/matlab/FunDouble.m +++ b/tests/expected/matlab/FunDouble.m @@ -2,10 +2,11 @@ %at https://gtsam.org/doxygen/ % %-------Methods------- -%dhamaalString(double d, string t) : returns Fun +%multiTemplatedMethodStringSize_t(double d, string t, size_t u) : returns Fun +%templatedMethodString(double d, string t) : returns Fun % %-------Static Methods------- -%divertido() : returns Fun +%staticMethodWithThis() : returns Fun % %-------Serialization Interface------- %string_serialize() : returns string @@ -34,28 +35,38 @@ classdef FunDouble < handle %DISPLAY Calls print on the object function disp(obj), obj.display; end %DISP Calls print on the object - function varargout = dhamaalString(this, varargin) - % DHAMAALSTRING usage: dhamaalString(double d, string t) : returns Fun + function varargout = multiTemplatedMethodStringSize_t(this, varargin) + % MULTITEMPLATEDMETHODSTRINGSIZE_T usage: multiTemplatedMethodStringSize_t(double d, string t, size_t u) : returns Fun % Doxygen can be found at https://gtsam.org/doxygen/ - if length(varargin) == 2 && isa(varargin{1},'double') && isa(varargin{2},'char') + if length(varargin) == 3 && isa(varargin{1},'double') && isa(varargin{2},'char') && isa(varargin{3},'numeric') varargout{1} = class_wrapper(7, this, varargin{:}); return end - error('Arguments do not match any overload of function FunDouble.dhamaalString'); + error('Arguments do not match any overload of function FunDouble.multiTemplatedMethodStringSize_t'); + end + + function varargout = templatedMethodString(this, varargin) + % TEMPLATEDMETHODSTRING usage: templatedMethodString(double d, string t) : returns Fun + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 2 && isa(varargin{1},'double') && isa(varargin{2},'char') + varargout{1} = class_wrapper(8, this, varargin{:}); + return + end + error('Arguments do not match any overload of function FunDouble.templatedMethodString'); end end methods(Static = true) - function varargout = Divertido(varargin) - % DIVERTIDO usage: divertido() : returns Fundouble + function varargout = StaticMethodWithThis(varargin) + % STATICMETHODWITHTHIS usage: staticMethodWithThis() : returns Fundouble % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - varargout{1} = class_wrapper(8, varargin{:}); + varargout{1} = class_wrapper(9, varargin{:}); return end - error('Arguments do not match any overload of function FunDouble.divertido'); + error('Arguments do not match any overload of function FunDouble.staticMethodWithThis'); end end diff --git a/tests/expected/matlab/MultipleTemplatesIntDouble.m b/tests/expected/matlab/MultipleTemplatesIntDouble.m index bea6a3e6c..9218657d9 100644 --- a/tests/expected/matlab/MultipleTemplatesIntDouble.m +++ b/tests/expected/matlab/MultipleTemplatesIntDouble.m @@ -9,7 +9,7 @@ classdef MultipleTemplatesIntDouble < handle function obj = MultipleTemplatesIntDouble(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - class_wrapper(43, my_ptr); + class_wrapper(44, my_ptr); else error('Arguments do not match any overload of MultipleTemplatesIntDouble constructor'); end @@ -17,7 +17,7 @@ classdef MultipleTemplatesIntDouble < handle end function delete(obj) - class_wrapper(44, obj.ptr_MultipleTemplatesIntDouble); + class_wrapper(45, obj.ptr_MultipleTemplatesIntDouble); end function display(obj), obj.print(''); end diff --git a/tests/expected/matlab/MultipleTemplatesIntFloat.m b/tests/expected/matlab/MultipleTemplatesIntFloat.m index 8c09e1685..6a6c4cb0a 100644 --- a/tests/expected/matlab/MultipleTemplatesIntFloat.m +++ b/tests/expected/matlab/MultipleTemplatesIntFloat.m @@ -9,7 +9,7 @@ classdef MultipleTemplatesIntFloat < handle function obj = MultipleTemplatesIntFloat(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - class_wrapper(45, my_ptr); + class_wrapper(46, my_ptr); else error('Arguments do not match any overload of MultipleTemplatesIntFloat constructor'); end @@ -17,7 +17,7 @@ classdef MultipleTemplatesIntFloat < handle end function delete(obj) - class_wrapper(46, obj.ptr_MultipleTemplatesIntFloat); + class_wrapper(47, obj.ptr_MultipleTemplatesIntFloat); end function display(obj), obj.print(''); end diff --git a/tests/expected/matlab/MyFactorPosePoint2.m b/tests/expected/matlab/MyFactorPosePoint2.m index 22eb3aaa9..50bd775fa 100644 --- a/tests/expected/matlab/MyFactorPosePoint2.m +++ b/tests/expected/matlab/MyFactorPosePoint2.m @@ -12,9 +12,9 @@ classdef MyFactorPosePoint2 < handle function obj = MyFactorPosePoint2(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - class_wrapper(47, my_ptr); + class_wrapper(48, my_ptr); elseif nargin == 4 && isa(varargin{1},'numeric') && isa(varargin{2},'numeric') && isa(varargin{3},'double') && isa(varargin{4},'gtsam.noiseModel.Base') - my_ptr = class_wrapper(48, varargin{1}, varargin{2}, varargin{3}, varargin{4}); + my_ptr = class_wrapper(49, varargin{1}, varargin{2}, varargin{3}, varargin{4}); else error('Arguments do not match any overload of MyFactorPosePoint2 constructor'); end @@ -22,7 +22,7 @@ classdef MyFactorPosePoint2 < handle end function delete(obj) - class_wrapper(49, obj.ptr_MyFactorPosePoint2); + class_wrapper(50, obj.ptr_MyFactorPosePoint2); end function display(obj), obj.print(''); end diff --git a/tests/expected/matlab/MyVector12.m b/tests/expected/matlab/MyVector12.m index df7e73250..7d8dd69e7 100644 --- a/tests/expected/matlab/MyVector12.m +++ b/tests/expected/matlab/MyVector12.m @@ -12,9 +12,9 @@ classdef MyVector12 < handle function obj = MyVector12(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - class_wrapper(40, my_ptr); + class_wrapper(41, my_ptr); elseif nargin == 0 - my_ptr = class_wrapper(41); + my_ptr = class_wrapper(42); else error('Arguments do not match any overload of MyVector12 constructor'); end @@ -22,7 +22,7 @@ classdef MyVector12 < handle end function delete(obj) - class_wrapper(42, obj.ptr_MyVector12); + class_wrapper(43, obj.ptr_MyVector12); end function display(obj), obj.print(''); end diff --git a/tests/expected/matlab/MyVector3.m b/tests/expected/matlab/MyVector3.m index 10c7ad203..6253a7347 100644 --- a/tests/expected/matlab/MyVector3.m +++ b/tests/expected/matlab/MyVector3.m @@ -12,9 +12,9 @@ classdef MyVector3 < handle function obj = MyVector3(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - class_wrapper(37, my_ptr); + class_wrapper(38, my_ptr); elseif nargin == 0 - my_ptr = class_wrapper(38); + my_ptr = class_wrapper(39); else error('Arguments do not match any overload of MyVector3 constructor'); end @@ -22,7 +22,7 @@ classdef MyVector3 < handle end function delete(obj) - class_wrapper(39, obj.ptr_MyVector3); + class_wrapper(40, obj.ptr_MyVector3); end function display(obj), obj.print(''); end diff --git a/tests/expected/matlab/PrimitiveRefDouble.m b/tests/expected/matlab/PrimitiveRefDouble.m index 8a6aca56c..15743b60a 100644 --- a/tests/expected/matlab/PrimitiveRefDouble.m +++ b/tests/expected/matlab/PrimitiveRefDouble.m @@ -19,9 +19,9 @@ classdef PrimitiveRefDouble < handle function obj = PrimitiveRefDouble(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - class_wrapper(33, my_ptr); + class_wrapper(34, my_ptr); elseif nargin == 0 - my_ptr = class_wrapper(34); + my_ptr = class_wrapper(35); else error('Arguments do not match any overload of PrimitiveRefDouble constructor'); end @@ -29,7 +29,7 @@ classdef PrimitiveRefDouble < handle end function delete(obj) - class_wrapper(35, obj.ptr_PrimitiveRefDouble); + class_wrapper(36, obj.ptr_PrimitiveRefDouble); end function display(obj), obj.print(''); end @@ -43,7 +43,7 @@ classdef PrimitiveRefDouble < handle % BRUTAL usage: Brutal(double t) : returns PrimitiveRefdouble % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = class_wrapper(36, varargin{:}); + varargout{1} = class_wrapper(37, varargin{:}); return end diff --git a/tests/expected/matlab/Test.m b/tests/expected/matlab/Test.m index 62a363644..1942fbd2e 100644 --- a/tests/expected/matlab/Test.m +++ b/tests/expected/matlab/Test.m @@ -35,11 +35,11 @@ classdef Test < handle function obj = Test(varargin) if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) my_ptr = varargin{2}; - class_wrapper(9, my_ptr); + class_wrapper(10, my_ptr); elseif nargin == 0 - my_ptr = class_wrapper(10); + my_ptr = class_wrapper(11); elseif nargin == 2 && isa(varargin{1},'double') && isa(varargin{2},'double') - my_ptr = class_wrapper(11, varargin{1}, varargin{2}); + my_ptr = class_wrapper(12, varargin{1}, varargin{2}); else error('Arguments do not match any overload of Test constructor'); end @@ -47,7 +47,7 @@ classdef Test < handle end function delete(obj) - class_wrapper(12, obj.ptr_Test); + class_wrapper(13, obj.ptr_Test); end function display(obj), obj.print(''); end @@ -58,7 +58,7 @@ classdef Test < handle % ARG_EIGENCONSTREF usage: arg_EigenConstRef(Matrix value) : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - class_wrapper(13, this, varargin{:}); + class_wrapper(14, this, varargin{:}); return end error('Arguments do not match any overload of function Test.arg_EigenConstRef'); @@ -68,7 +68,7 @@ classdef Test < handle % CREATE_MIXEDPTRS usage: create_MixedPtrs() : returns pair< Test, Test > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - [ varargout{1} varargout{2} ] = class_wrapper(14, this, varargin{:}); + [ varargout{1} varargout{2} ] = class_wrapper(15, this, varargin{:}); return end error('Arguments do not match any overload of function Test.create_MixedPtrs'); @@ -78,7 +78,7 @@ classdef Test < handle % CREATE_PTRS usage: create_ptrs() : returns pair< Test, Test > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - [ varargout{1} varargout{2} ] = class_wrapper(15, this, varargin{:}); + [ varargout{1} varargout{2} ] = class_wrapper(16, this, varargin{:}); return end error('Arguments do not match any overload of function Test.create_ptrs'); @@ -88,7 +88,7 @@ classdef Test < handle % PRINT usage: print() : returns void % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 0 - class_wrapper(16, this, varargin{:}); + class_wrapper(17, this, varargin{:}); return end error('Arguments do not match any overload of function Test.print'); @@ -98,7 +98,7 @@ classdef Test < handle % RETURN_POINT2PTR usage: return_Point2Ptr(bool value) : returns Point2 % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'logical') - varargout{1} = class_wrapper(17, this, varargin{:}); + varargout{1} = class_wrapper(18, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_Point2Ptr'); @@ -108,7 +108,7 @@ classdef Test < handle % RETURN_TEST usage: return_Test(Test value) : returns Test % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = class_wrapper(18, this, varargin{:}); + varargout{1} = class_wrapper(19, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_Test'); @@ -118,7 +118,7 @@ classdef Test < handle % RETURN_TESTPTR usage: return_TestPtr(Test value) : returns Test % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = class_wrapper(19, this, varargin{:}); + varargout{1} = class_wrapper(20, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_TestPtr'); @@ -128,7 +128,7 @@ classdef Test < handle % RETURN_BOOL usage: return_bool(bool value) : returns bool % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'logical') - varargout{1} = class_wrapper(20, this, varargin{:}); + varargout{1} = class_wrapper(21, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_bool'); @@ -138,7 +138,7 @@ classdef Test < handle % RETURN_DOUBLE usage: return_double(double value) : returns double % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = class_wrapper(21, this, varargin{:}); + varargout{1} = class_wrapper(22, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_double'); @@ -148,7 +148,7 @@ classdef Test < handle % RETURN_FIELD usage: return_field(Test t) : returns bool % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'Test') - varargout{1} = class_wrapper(22, this, varargin{:}); + varargout{1} = class_wrapper(23, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_field'); @@ -158,7 +158,7 @@ classdef Test < handle % RETURN_INT usage: return_int(int value) : returns int % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = class_wrapper(23, this, varargin{:}); + varargout{1} = class_wrapper(24, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_int'); @@ -168,7 +168,7 @@ classdef Test < handle % RETURN_MATRIX1 usage: return_matrix1(Matrix value) : returns Matrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = class_wrapper(24, this, varargin{:}); + varargout{1} = class_wrapper(25, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_matrix1'); @@ -178,7 +178,7 @@ classdef Test < handle % RETURN_MATRIX2 usage: return_matrix2(Matrix value) : returns Matrix % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') - varargout{1} = class_wrapper(25, this, varargin{:}); + varargout{1} = class_wrapper(26, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_matrix2'); @@ -188,13 +188,13 @@ classdef Test < handle % RETURN_PAIR usage: return_pair(Vector v, Matrix A) : returns pair< Vector, Matrix > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 2 && isa(varargin{1},'double') && size(varargin{1},2)==1 && isa(varargin{2},'double') - [ varargout{1} varargout{2} ] = class_wrapper(26, this, varargin{:}); + [ varargout{1} varargout{2} ] = class_wrapper(27, this, varargin{:}); return end % RETURN_PAIR usage: return_pair(Vector v) : returns pair< Vector, Matrix > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 - [ varargout{1} varargout{2} ] = class_wrapper(27, this, varargin{:}); + [ varargout{1} varargout{2} ] = class_wrapper(28, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_pair'); @@ -204,7 +204,7 @@ classdef Test < handle % RETURN_PTRS usage: return_ptrs(Test p1, Test p2) : returns pair< Test, Test > % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 2 && isa(varargin{1},'Test') && isa(varargin{2},'Test') - [ varargout{1} varargout{2} ] = class_wrapper(28, this, varargin{:}); + [ varargout{1} varargout{2} ] = class_wrapper(29, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_ptrs'); @@ -214,7 +214,7 @@ classdef Test < handle % RETURN_SIZE_T usage: return_size_t(size_t value) : returns size_t % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'numeric') - varargout{1} = class_wrapper(29, this, varargin{:}); + varargout{1} = class_wrapper(30, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_size_t'); @@ -224,7 +224,7 @@ classdef Test < handle % RETURN_STRING usage: return_string(string value) : returns string % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'char') - varargout{1} = class_wrapper(30, this, varargin{:}); + varargout{1} = class_wrapper(31, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_string'); @@ -234,7 +234,7 @@ classdef Test < handle % RETURN_VECTOR1 usage: return_vector1(Vector value) : returns Vector % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 - varargout{1} = class_wrapper(31, this, varargin{:}); + varargout{1} = class_wrapper(32, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_vector1'); @@ -244,7 +244,7 @@ classdef Test < handle % RETURN_VECTOR2 usage: return_vector2(Vector value) : returns Vector % Doxygen can be found at https://gtsam.org/doxygen/ if length(varargin) == 1 && isa(varargin{1},'double') && size(varargin{1},2)==1 - varargout{1} = class_wrapper(32, this, varargin{:}); + varargout{1} = class_wrapper(33, this, varargin{:}); return end error('Arguments do not match any overload of function Test.return_vector2'); diff --git a/tests/expected/matlab/class_wrapper.cpp b/tests/expected/matlab/class_wrapper.cpp index a74306675..f4c7c6af0 100644 --- a/tests/expected/matlab/class_wrapper.cpp +++ b/tests/expected/matlab/class_wrapper.cpp @@ -200,22 +200,32 @@ void FunDouble_deconstructor_6(int nargout, mxArray *out[], int nargin, const mx } } -void FunDouble_dhamaal_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void FunDouble_multiTemplatedMethod_7(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - checkArguments("dhamaalString",nargout,nargin-1,2); + checkArguments("multiTemplatedMethodStringSize_t",nargout,nargin-1,3); auto obj = unwrap_shared_ptr>(in[0], "ptr_FunDouble"); double d = unwrap< double >(in[1]); string t = unwrap< string >(in[2]); - out[0] = wrap_shared_ptr(boost::make_shared>(obj->dhamaal(d,t)),"Fun", false); + size_t u = unwrap< size_t >(in[3]); + out[0] = wrap_shared_ptr(boost::make_shared>(obj->multiTemplatedMethod(d,t,u)),"Fun", false); } -void FunDouble_divertido_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void FunDouble_templatedMethod_8(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { - checkArguments("FunDouble.divertido",nargout,nargin,0); - out[0] = wrap_shared_ptr(boost::make_shared>(Fun::divertido()),"Fundouble", false); + checkArguments("templatedMethodString",nargout,nargin-1,2); + auto obj = unwrap_shared_ptr>(in[0], "ptr_FunDouble"); + double d = unwrap< double >(in[1]); + string t = unwrap< string >(in[2]); + out[0] = wrap_shared_ptr(boost::make_shared>(obj->templatedMethod(d,t)),"Fun", false); } -void Test_collectorInsertAndMakeBase_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void FunDouble_staticMethodWithThis_9(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("FunDouble.staticMethodWithThis",nargout,nargin,0); + out[0] = wrap_shared_ptr(boost::make_shared>(Fun::staticMethodWithThis()),"Fundouble", false); +} + +void Test_collectorInsertAndMakeBase_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -224,7 +234,7 @@ void Test_collectorInsertAndMakeBase_9(int nargout, mxArray *out[], int nargin, collector_Test.insert(self); } -void Test_constructor_10(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_constructor_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -235,7 +245,7 @@ void Test_constructor_10(int nargout, mxArray *out[], int nargin, const mxArray *reinterpret_cast (mxGetData(out[0])) = self; } -void Test_constructor_11(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_constructor_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr Shared; @@ -248,7 +258,7 @@ void Test_constructor_11(int nargout, mxArray *out[], int nargin, const mxArray *reinterpret_cast (mxGetData(out[0])) = self; } -void Test_deconstructor_12(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_deconstructor_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr Shared; checkArguments("delete_Test",nargout,nargin,1); @@ -261,7 +271,7 @@ void Test_deconstructor_12(int nargout, mxArray *out[], int nargin, const mxArra } } -void Test_arg_EigenConstRef_13(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_arg_EigenConstRef_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("arg_EigenConstRef",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -269,7 +279,7 @@ void Test_arg_EigenConstRef_13(int nargout, mxArray *out[], int nargin, const mx obj->arg_EigenConstRef(value); } -void Test_create_MixedPtrs_14(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_create_MixedPtrs_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("create_MixedPtrs",nargout,nargin-1,0); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -278,7 +288,7 @@ void Test_create_MixedPtrs_14(int nargout, mxArray *out[], int nargin, const mxA out[1] = wrap_shared_ptr(pairResult.second,"Test", false); } -void Test_create_ptrs_15(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_create_ptrs_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("create_ptrs",nargout,nargin-1,0); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -287,14 +297,14 @@ void Test_create_ptrs_15(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap_shared_ptr(pairResult.second,"Test", false); } -void Test_print_16(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_print_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("print",nargout,nargin-1,0); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); obj->print(); } -void Test_return_Point2Ptr_17(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_Point2Ptr_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_Point2Ptr",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -305,7 +315,7 @@ void Test_return_Point2Ptr_17(int nargout, mxArray *out[], int nargin, const mxA } } -void Test_return_Test_18(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_Test_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_Test",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -313,7 +323,7 @@ void Test_return_Test_18(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap_shared_ptr(boost::make_shared(obj->return_Test(value)),"Test", false); } -void Test_return_TestPtr_19(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_TestPtr_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_TestPtr",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -321,7 +331,7 @@ void Test_return_TestPtr_19(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap_shared_ptr(obj->return_TestPtr(value),"Test", false); } -void Test_return_bool_20(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_bool_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_bool",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -329,7 +339,7 @@ void Test_return_bool_20(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap< bool >(obj->return_bool(value)); } -void Test_return_double_21(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_double_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_double",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -337,7 +347,7 @@ void Test_return_double_21(int nargout, mxArray *out[], int nargin, const mxArra out[0] = wrap< double >(obj->return_double(value)); } -void Test_return_field_22(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_field_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_field",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -345,7 +355,7 @@ void Test_return_field_22(int nargout, mxArray *out[], int nargin, const mxArray out[0] = wrap< bool >(obj->return_field(t)); } -void Test_return_int_23(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_int_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_int",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -353,7 +363,7 @@ void Test_return_int_23(int nargout, mxArray *out[], int nargin, const mxArray * out[0] = wrap< int >(obj->return_int(value)); } -void Test_return_matrix1_24(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_matrix1_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_matrix1",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -361,7 +371,7 @@ void Test_return_matrix1_24(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Matrix >(obj->return_matrix1(value)); } -void Test_return_matrix2_25(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_matrix2_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_matrix2",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -369,7 +379,7 @@ void Test_return_matrix2_25(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Matrix >(obj->return_matrix2(value)); } -void Test_return_pair_26(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_pair_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_pair",nargout,nargin-1,2); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -380,7 +390,7 @@ void Test_return_pair_26(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap< Matrix >(pairResult.second); } -void Test_return_pair_27(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_pair_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_pair",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -390,7 +400,7 @@ void Test_return_pair_27(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap< Matrix >(pairResult.second); } -void Test_return_ptrs_28(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_ptrs_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_ptrs",nargout,nargin-1,2); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -401,7 +411,7 @@ void Test_return_ptrs_28(int nargout, mxArray *out[], int nargin, const mxArray out[1] = wrap_shared_ptr(pairResult.second,"Test", false); } -void Test_return_size_t_29(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_size_t_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_size_t",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -409,7 +419,7 @@ void Test_return_size_t_29(int nargout, mxArray *out[], int nargin, const mxArra out[0] = wrap< size_t >(obj->return_size_t(value)); } -void Test_return_string_30(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_string_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_string",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -417,7 +427,7 @@ void Test_return_string_30(int nargout, mxArray *out[], int nargin, const mxArra out[0] = wrap< string >(obj->return_string(value)); } -void Test_return_vector1_31(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_vector1_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_vector1",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -425,7 +435,7 @@ void Test_return_vector1_31(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Vector >(obj->return_vector1(value)); } -void Test_return_vector2_32(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void Test_return_vector2_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("return_vector2",nargout,nargin-1,1); auto obj = unwrap_shared_ptr(in[0], "ptr_Test"); @@ -433,7 +443,7 @@ void Test_return_vector2_32(int nargout, mxArray *out[], int nargin, const mxArr out[0] = wrap< Vector >(obj->return_vector2(value)); } -void PrimitiveRefDouble_collectorInsertAndMakeBase_33(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void PrimitiveRefDouble_collectorInsertAndMakeBase_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -442,7 +452,7 @@ void PrimitiveRefDouble_collectorInsertAndMakeBase_33(int nargout, mxArray *out[ collector_PrimitiveRefDouble.insert(self); } -void PrimitiveRefDouble_constructor_34(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void PrimitiveRefDouble_constructor_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -453,7 +463,7 @@ void PrimitiveRefDouble_constructor_34(int nargout, mxArray *out[], int nargin, *reinterpret_cast (mxGetData(out[0])) = self; } -void PrimitiveRefDouble_deconstructor_35(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void PrimitiveRefDouble_deconstructor_36(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr> Shared; checkArguments("delete_PrimitiveRefDouble",nargout,nargin,1); @@ -466,14 +476,14 @@ void PrimitiveRefDouble_deconstructor_35(int nargout, mxArray *out[], int nargin } } -void PrimitiveRefDouble_Brutal_36(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void PrimitiveRefDouble_Brutal_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { checkArguments("PrimitiveRefDouble.Brutal",nargout,nargin,1); double t = unwrap< double >(in[0]); out[0] = wrap_shared_ptr(boost::make_shared>(PrimitiveRef::Brutal(t)),"PrimitiveRefdouble", false); } -void MyVector3_collectorInsertAndMakeBase_37(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyVector3_collectorInsertAndMakeBase_38(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -482,7 +492,7 @@ void MyVector3_collectorInsertAndMakeBase_37(int nargout, mxArray *out[], int na collector_MyVector3.insert(self); } -void MyVector3_constructor_38(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyVector3_constructor_39(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -493,7 +503,7 @@ void MyVector3_constructor_38(int nargout, mxArray *out[], int nargin, const mxA *reinterpret_cast (mxGetData(out[0])) = self; } -void MyVector3_deconstructor_39(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyVector3_deconstructor_40(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr> Shared; checkArguments("delete_MyVector3",nargout,nargin,1); @@ -506,7 +516,7 @@ void MyVector3_deconstructor_39(int nargout, mxArray *out[], int nargin, const m } } -void MyVector12_collectorInsertAndMakeBase_40(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyVector12_collectorInsertAndMakeBase_41(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -515,7 +525,7 @@ void MyVector12_collectorInsertAndMakeBase_40(int nargout, mxArray *out[], int n collector_MyVector12.insert(self); } -void MyVector12_constructor_41(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyVector12_constructor_42(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -526,7 +536,7 @@ void MyVector12_constructor_41(int nargout, mxArray *out[], int nargin, const mx *reinterpret_cast (mxGetData(out[0])) = self; } -void MyVector12_deconstructor_42(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyVector12_deconstructor_43(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr> Shared; checkArguments("delete_MyVector12",nargout,nargin,1); @@ -539,7 +549,7 @@ void MyVector12_deconstructor_42(int nargout, mxArray *out[], int nargin, const } } -void MultipleTemplatesIntDouble_collectorInsertAndMakeBase_43(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MultipleTemplatesIntDouble_collectorInsertAndMakeBase_44(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -548,7 +558,7 @@ void MultipleTemplatesIntDouble_collectorInsertAndMakeBase_43(int nargout, mxArr collector_MultipleTemplatesIntDouble.insert(self); } -void MultipleTemplatesIntDouble_deconstructor_44(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MultipleTemplatesIntDouble_deconstructor_45(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr> Shared; checkArguments("delete_MultipleTemplatesIntDouble",nargout,nargin,1); @@ -561,7 +571,7 @@ void MultipleTemplatesIntDouble_deconstructor_44(int nargout, mxArray *out[], in } } -void MultipleTemplatesIntFloat_collectorInsertAndMakeBase_45(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MultipleTemplatesIntFloat_collectorInsertAndMakeBase_46(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -570,7 +580,7 @@ void MultipleTemplatesIntFloat_collectorInsertAndMakeBase_45(int nargout, mxArra collector_MultipleTemplatesIntFloat.insert(self); } -void MultipleTemplatesIntFloat_deconstructor_46(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MultipleTemplatesIntFloat_deconstructor_47(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr> Shared; checkArguments("delete_MultipleTemplatesIntFloat",nargout,nargin,1); @@ -583,7 +593,7 @@ void MultipleTemplatesIntFloat_deconstructor_46(int nargout, mxArray *out[], int } } -void MyFactorPosePoint2_collectorInsertAndMakeBase_47(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_collectorInsertAndMakeBase_48(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -592,7 +602,7 @@ void MyFactorPosePoint2_collectorInsertAndMakeBase_47(int nargout, mxArray *out[ collector_MyFactorPosePoint2.insert(self); } -void MyFactorPosePoint2_constructor_48(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_constructor_49(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { mexAtExit(&_deleteAllObjects); typedef boost::shared_ptr> Shared; @@ -607,7 +617,7 @@ void MyFactorPosePoint2_constructor_48(int nargout, mxArray *out[], int nargin, *reinterpret_cast (mxGetData(out[0])) = self; } -void MyFactorPosePoint2_deconstructor_49(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +void MyFactorPosePoint2_deconstructor_50(int nargout, mxArray *out[], int nargin, const mxArray *in[]) { typedef boost::shared_ptr> Shared; checkArguments("delete_MyFactorPosePoint2",nargout,nargin,1); @@ -654,133 +664,136 @@ void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) FunDouble_deconstructor_6(nargout, out, nargin-1, in+1); break; case 7: - FunDouble_dhamaal_7(nargout, out, nargin-1, in+1); + FunDouble_multiTemplatedMethod_7(nargout, out, nargin-1, in+1); break; case 8: - FunDouble_divertido_8(nargout, out, nargin-1, in+1); + FunDouble_templatedMethod_8(nargout, out, nargin-1, in+1); break; case 9: - Test_collectorInsertAndMakeBase_9(nargout, out, nargin-1, in+1); + FunDouble_staticMethodWithThis_9(nargout, out, nargin-1, in+1); break; case 10: - Test_constructor_10(nargout, out, nargin-1, in+1); + Test_collectorInsertAndMakeBase_10(nargout, out, nargin-1, in+1); break; case 11: Test_constructor_11(nargout, out, nargin-1, in+1); break; case 12: - Test_deconstructor_12(nargout, out, nargin-1, in+1); + Test_constructor_12(nargout, out, nargin-1, in+1); break; case 13: - Test_arg_EigenConstRef_13(nargout, out, nargin-1, in+1); + Test_deconstructor_13(nargout, out, nargin-1, in+1); break; case 14: - Test_create_MixedPtrs_14(nargout, out, nargin-1, in+1); + Test_arg_EigenConstRef_14(nargout, out, nargin-1, in+1); break; case 15: - Test_create_ptrs_15(nargout, out, nargin-1, in+1); + Test_create_MixedPtrs_15(nargout, out, nargin-1, in+1); break; case 16: - Test_print_16(nargout, out, nargin-1, in+1); + Test_create_ptrs_16(nargout, out, nargin-1, in+1); break; case 17: - Test_return_Point2Ptr_17(nargout, out, nargin-1, in+1); + Test_print_17(nargout, out, nargin-1, in+1); break; case 18: - Test_return_Test_18(nargout, out, nargin-1, in+1); + Test_return_Point2Ptr_18(nargout, out, nargin-1, in+1); break; case 19: - Test_return_TestPtr_19(nargout, out, nargin-1, in+1); + Test_return_Test_19(nargout, out, nargin-1, in+1); break; case 20: - Test_return_bool_20(nargout, out, nargin-1, in+1); + Test_return_TestPtr_20(nargout, out, nargin-1, in+1); break; case 21: - Test_return_double_21(nargout, out, nargin-1, in+1); + Test_return_bool_21(nargout, out, nargin-1, in+1); break; case 22: - Test_return_field_22(nargout, out, nargin-1, in+1); + Test_return_double_22(nargout, out, nargin-1, in+1); break; case 23: - Test_return_int_23(nargout, out, nargin-1, in+1); + Test_return_field_23(nargout, out, nargin-1, in+1); break; case 24: - Test_return_matrix1_24(nargout, out, nargin-1, in+1); + Test_return_int_24(nargout, out, nargin-1, in+1); break; case 25: - Test_return_matrix2_25(nargout, out, nargin-1, in+1); + Test_return_matrix1_25(nargout, out, nargin-1, in+1); break; case 26: - Test_return_pair_26(nargout, out, nargin-1, in+1); + Test_return_matrix2_26(nargout, out, nargin-1, in+1); break; case 27: Test_return_pair_27(nargout, out, nargin-1, in+1); break; case 28: - Test_return_ptrs_28(nargout, out, nargin-1, in+1); + Test_return_pair_28(nargout, out, nargin-1, in+1); break; case 29: - Test_return_size_t_29(nargout, out, nargin-1, in+1); + Test_return_ptrs_29(nargout, out, nargin-1, in+1); break; case 30: - Test_return_string_30(nargout, out, nargin-1, in+1); + Test_return_size_t_30(nargout, out, nargin-1, in+1); break; case 31: - Test_return_vector1_31(nargout, out, nargin-1, in+1); + Test_return_string_31(nargout, out, nargin-1, in+1); break; case 32: - Test_return_vector2_32(nargout, out, nargin-1, in+1); + Test_return_vector1_32(nargout, out, nargin-1, in+1); break; case 33: - PrimitiveRefDouble_collectorInsertAndMakeBase_33(nargout, out, nargin-1, in+1); + Test_return_vector2_33(nargout, out, nargin-1, in+1); break; case 34: - PrimitiveRefDouble_constructor_34(nargout, out, nargin-1, in+1); + PrimitiveRefDouble_collectorInsertAndMakeBase_34(nargout, out, nargin-1, in+1); break; case 35: - PrimitiveRefDouble_deconstructor_35(nargout, out, nargin-1, in+1); + PrimitiveRefDouble_constructor_35(nargout, out, nargin-1, in+1); break; case 36: - PrimitiveRefDouble_Brutal_36(nargout, out, nargin-1, in+1); + PrimitiveRefDouble_deconstructor_36(nargout, out, nargin-1, in+1); break; case 37: - MyVector3_collectorInsertAndMakeBase_37(nargout, out, nargin-1, in+1); + PrimitiveRefDouble_Brutal_37(nargout, out, nargin-1, in+1); break; case 38: - MyVector3_constructor_38(nargout, out, nargin-1, in+1); + MyVector3_collectorInsertAndMakeBase_38(nargout, out, nargin-1, in+1); break; case 39: - MyVector3_deconstructor_39(nargout, out, nargin-1, in+1); + MyVector3_constructor_39(nargout, out, nargin-1, in+1); break; case 40: - MyVector12_collectorInsertAndMakeBase_40(nargout, out, nargin-1, in+1); + MyVector3_deconstructor_40(nargout, out, nargin-1, in+1); break; case 41: - MyVector12_constructor_41(nargout, out, nargin-1, in+1); + MyVector12_collectorInsertAndMakeBase_41(nargout, out, nargin-1, in+1); break; case 42: - MyVector12_deconstructor_42(nargout, out, nargin-1, in+1); + MyVector12_constructor_42(nargout, out, nargin-1, in+1); break; case 43: - MultipleTemplatesIntDouble_collectorInsertAndMakeBase_43(nargout, out, nargin-1, in+1); + MyVector12_deconstructor_43(nargout, out, nargin-1, in+1); break; case 44: - MultipleTemplatesIntDouble_deconstructor_44(nargout, out, nargin-1, in+1); + MultipleTemplatesIntDouble_collectorInsertAndMakeBase_44(nargout, out, nargin-1, in+1); break; case 45: - MultipleTemplatesIntFloat_collectorInsertAndMakeBase_45(nargout, out, nargin-1, in+1); + MultipleTemplatesIntDouble_deconstructor_45(nargout, out, nargin-1, in+1); break; case 46: - MultipleTemplatesIntFloat_deconstructor_46(nargout, out, nargin-1, in+1); + MultipleTemplatesIntFloat_collectorInsertAndMakeBase_46(nargout, out, nargin-1, in+1); break; case 47: - MyFactorPosePoint2_collectorInsertAndMakeBase_47(nargout, out, nargin-1, in+1); + MultipleTemplatesIntFloat_deconstructor_47(nargout, out, nargin-1, in+1); break; case 48: - MyFactorPosePoint2_constructor_48(nargout, out, nargin-1, in+1); + MyFactorPosePoint2_collectorInsertAndMakeBase_48(nargout, out, nargin-1, in+1); break; case 49: - MyFactorPosePoint2_deconstructor_49(nargout, out, nargin-1, in+1); + MyFactorPosePoint2_constructor_49(nargout, out, nargin-1, in+1); + break; + case 50: + MyFactorPosePoint2_deconstructor_50(nargout, out, nargin-1, in+1); break; } } catch(const std::exception& e) { diff --git a/tests/expected/python/class_pybind.cpp b/tests/expected/python/class_pybind.cpp index d6cbd91c5..a996f35ae 100644 --- a/tests/expected/python/class_pybind.cpp +++ b/tests/expected/python/class_pybind.cpp @@ -28,8 +28,9 @@ PYBIND11_MODULE(class_py, m_) { .def_static("create",[](){return FunRange::create();}); py::class_, std::shared_ptr>>(m_, "FunDouble") - .def("dhamaalString",[](Fun* self, double d, string t){return self->dhamaal(d, t);}, py::arg("d"), py::arg("t")) - .def_static("divertido",[](){return Fun::divertido();}); + .def("templatedMethodString",[](Fun* self, double d, string t){return self->templatedMethod(d, t);}, py::arg("d"), py::arg("t")) + .def("multiTemplatedMethodStringSize_t",[](Fun* self, double d, string t, size_t u){return self->multiTemplatedMethod(d, t, u);}, py::arg("d"), py::arg("t"), py::arg("u")) + .def_static("staticMethodWithThis",[](){return Fun::staticMethodWithThis();}); py::class_>(m_, "Test") .def(py::init<>()) diff --git a/tests/fixtures/class.i b/tests/fixtures/class.i index aca2567ce..1e2fce338 100644 --- a/tests/fixtures/class.i +++ b/tests/fixtures/class.i @@ -7,13 +7,13 @@ class FunRange { template class Fun { - static This divertido(); + static This staticMethodWithThis(); template - This dhamaal(double d, T t); + This templatedMethod(double d, T t); - // template - // This pret(double d, T t, U u); + template + This multiTemplatedMethod(double d, T t, U u); }; From c78ca4bd02e94c87a233e307533afb34241a6138 Mon Sep 17 00:00:00 2001 From: Varun Agrawal Date: Fri, 26 Mar 2021 00:54:01 -0400 Subject: [PATCH 15/21] Squashed 'wrap/' changes from 9a467794e..96ccdfd0b 96ccdfd0b Merge pull request #65 from borglab/fix/special-cases 04c06b7e6 Merge pull request #63 from borglab/fix/cmake bf2c91bd2 fix issue in template instantiation generator 152dbcb12 test for special cases d03004b24 fixed the cmake to discover the correct python version and set all corresponding variables 4cf66e0da Merge pull request #61 from borglab/fix/python-variables 80558e35b added more status messages and set the PYBIND11_PYTHON_VERSION each time 73afd1b0a set both sets of Python variables and find python version when including PybindWrap REVERT: 9a467794e Merge pull request #61 from borglab/fix/python-variables REVERT: 6bae7af99 added more status messages and set the PYBIND11_PYTHON_VERSION each time REVERT: 5129cf3b9 set both sets of Python variables and find python version when including PybindWrap git-subtree-dir: wrap git-subtree-split: 96ccdfd0b84a4dbf1b3e9ed31b95ebc2758be9cc --- cmake/GtwrapUtils.cmake | 39 +- cmake/PybindWrap.cmake | 4 +- gtwrap/template_instantiator.py | 10 +- .../matlab/+gtsam/NonlinearFactorGraph.m | 44 +++ .../matlab/+gtsam/PinholeCameraCal3Bundler.m | 31 ++ .../expected/matlab/special_cases_wrapper.cpp | 340 ++++++++++++++++++ .../expected/python/special_cases_pybind.cpp | 35 ++ tests/fixtures/special_cases.i | 17 + tests/test_matlab_wrapper.py | 38 +- tests/test_pybind_wrapper.py | 12 + 10 files changed, 544 insertions(+), 26 deletions(-) create mode 100644 tests/expected/matlab/+gtsam/NonlinearFactorGraph.m create mode 100644 tests/expected/matlab/+gtsam/PinholeCameraCal3Bundler.m create mode 100644 tests/expected/matlab/special_cases_wrapper.cpp create mode 100644 tests/expected/python/special_cases_pybind.cpp create mode 100644 tests/fixtures/special_cases.i diff --git a/cmake/GtwrapUtils.cmake b/cmake/GtwrapUtils.cmake index 01cdd32b9..a3a77708c 100644 --- a/cmake/GtwrapUtils.cmake +++ b/cmake/GtwrapUtils.cmake @@ -1,5 +1,6 @@ # Utilities to help with wrapping. +# Use CMake's find_package to find the version of Python installed. macro(get_python_version) if(${CMAKE_VERSION} VERSION_LESS "3.12.0") # Use older version of cmake's find_python @@ -13,19 +14,6 @@ macro(get_python_version) find_package(PythonLibs ${PYTHON_VERSION_STRING}) - set(Python_VERSION_MAJOR - ${PYTHON_VERSION_MAJOR} - CACHE INTERNAL "") - set(Python_VERSION_MINOR - ${PYTHON_VERSION_MINOR} - CACHE INTERNAL "") - set(Python_VERSION_PATCH - ${PYTHON_VERSION_PATCH} - CACHE INTERNAL "") - set(Python_EXECUTABLE - ${PYTHON_EXECUTABLE} - CACHE INTERNAL "") - else() # Get info about the Python interpreter # https://cmake.org/cmake/help/latest/module/FindPython.html#module:FindPython @@ -37,6 +25,26 @@ macro(get_python_version) "Cannot find Python interpreter. Please install Python>=3.5.") endif() + endif() +endmacro() + +# Depending on the version of CMake, ensure all the appropriate variables are set. +macro(configure_python_variables) + if(${CMAKE_VERSION} VERSION_LESS "3.12.0") + set(Python_VERSION_MAJOR + ${PYTHON_VERSION_MAJOR} + CACHE INTERNAL "") + set(Python_VERSION_MINOR + ${PYTHON_VERSION_MINOR} + CACHE INTERNAL "") + set(Python_VERSION_PATCH + ${PYTHON_VERSION_PATCH} + CACHE INTERNAL "") + set(Python_EXECUTABLE + ${PYTHON_EXECUTABLE} + CACHE PATH "") + + else() # Set both sets of variables set(PYTHON_VERSION_MAJOR ${Python_VERSION_MAJOR} @@ -49,7 +57,7 @@ macro(get_python_version) CACHE INTERNAL "") set(PYTHON_EXECUTABLE ${Python_EXECUTABLE} - CACHE INTERNAL "") + CACHE PATH "") endif() endmacro() @@ -85,4 +93,7 @@ macro(gtwrap_get_python_version WRAP_PYTHON_VERSION) EXACT) endif() + # (Always) Configure the variables once we find the python package + configure_python_variables() + endmacro() diff --git a/cmake/PybindWrap.cmake b/cmake/PybindWrap.cmake index 2c07e2b50..dc581be49 100644 --- a/cmake/PybindWrap.cmake +++ b/cmake/PybindWrap.cmake @@ -7,10 +7,10 @@ endif() # Get the Python version include(GtwrapUtils) -message(status "Checking Python Version") +message(STATUS "Checking Python Version") gtwrap_get_python_version(${WRAP_PYTHON_VERSION}) -message(status "Setting Python version for wrapper") +message(STATUS "Setting Python version for wrapper") set(PYBIND11_PYTHON_VERSION ${WRAP_PYTHON_VERSION}) # User-friendly Pybind11 wrapping and installing function. diff --git a/gtwrap/template_instantiator.py b/gtwrap/template_instantiator.py index 7ae79e217..5651a2a6f 100644 --- a/gtwrap/template_instantiator.py +++ b/gtwrap/template_instantiator.py @@ -206,7 +206,7 @@ class InstantiatedMethod(parser.Method): """ We can only instantiate template methods with a single template parameter. """ - def __init__(self, original, instantiations=''): + def __init__(self, original, instantiations: List[parser.Typename]=''): self.original = original self.instantiations = instantiations self.template = '' @@ -246,11 +246,9 @@ class InstantiatedMethod(parser.Method): def to_cpp(self): """Generate the C++ code for wrapping.""" if self.original.template: - instantiation_list = [ - # Get the fully qualified name - "::".join(x.namespaces + [x.name]) - for x in self.instantiations - ] + # to_cpp will handle all the namespacing and templating + instantiation_list = [x.to_cpp() for x in self.instantiations] + # now can simply combine the instantiations, separated by commas ret = "{}<{}>".format(self.original.name, ",".join(instantiation_list)) else: diff --git a/tests/expected/matlab/+gtsam/NonlinearFactorGraph.m b/tests/expected/matlab/+gtsam/NonlinearFactorGraph.m new file mode 100644 index 000000000..4b4704e87 --- /dev/null +++ b/tests/expected/matlab/+gtsam/NonlinearFactorGraph.m @@ -0,0 +1,44 @@ +%class NonlinearFactorGraph, see Doxygen page for details +%at https://gtsam.org/doxygen/ +% +%-------Methods------- +%addPriorPinholeCameraCal3Bundler(size_t key, PinholeCamera prior, Base noiseModel) : returns void +% +classdef NonlinearFactorGraph < handle + properties + ptr_gtsamNonlinearFactorGraph = 0 + end + methods + function obj = NonlinearFactorGraph(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + special_cases_wrapper(0, my_ptr); + else + error('Arguments do not match any overload of gtsam.NonlinearFactorGraph constructor'); + end + obj.ptr_gtsamNonlinearFactorGraph = my_ptr; + end + + function delete(obj) + special_cases_wrapper(1, obj.ptr_gtsamNonlinearFactorGraph); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + function varargout = addPriorPinholeCameraCal3Bundler(this, varargin) + % ADDPRIORPINHOLECAMERACAL3BUNDLER usage: addPriorPinholeCameraCal3Bundler(size_t key, PinholeCamera prior, Base noiseModel) : returns void + % Doxygen can be found at https://gtsam.org/doxygen/ + if length(varargin) == 3 && isa(varargin{1},'numeric') && isa(varargin{2},'gtsam.PinholeCameraCal3Bundler') && isa(varargin{3},'gtsam.noiseModel.Base') + special_cases_wrapper(2, this, varargin{:}); + return + end + error('Arguments do not match any overload of function gtsam.NonlinearFactorGraph.addPriorPinholeCameraCal3Bundler'); + end + + end + + methods(Static = true) + end +end diff --git a/tests/expected/matlab/+gtsam/PinholeCameraCal3Bundler.m b/tests/expected/matlab/+gtsam/PinholeCameraCal3Bundler.m new file mode 100644 index 000000000..3e8451e96 --- /dev/null +++ b/tests/expected/matlab/+gtsam/PinholeCameraCal3Bundler.m @@ -0,0 +1,31 @@ +%class PinholeCameraCal3Bundler, see Doxygen page for details +%at https://gtsam.org/doxygen/ +% +classdef PinholeCameraCal3Bundler < handle + properties + ptr_gtsamPinholeCameraCal3Bundler = 0 + end + methods + function obj = PinholeCameraCal3Bundler(varargin) + if nargin == 2 && isa(varargin{1}, 'uint64') && varargin{1} == uint64(5139824614673773682) + my_ptr = varargin{2}; + special_cases_wrapper(3, my_ptr); + else + error('Arguments do not match any overload of gtsam.PinholeCameraCal3Bundler constructor'); + end + obj.ptr_gtsamPinholeCameraCal3Bundler = my_ptr; + end + + function delete(obj) + special_cases_wrapper(4, obj.ptr_gtsamPinholeCameraCal3Bundler); + end + + function display(obj), obj.print(''); end + %DISPLAY Calls print on the object + function disp(obj), obj.display; end + %DISP Calls print on the object + end + + methods(Static = true) + end +end diff --git a/tests/expected/matlab/special_cases_wrapper.cpp b/tests/expected/matlab/special_cases_wrapper.cpp new file mode 100644 index 000000000..f1c03e9a1 --- /dev/null +++ b/tests/expected/matlab/special_cases_wrapper.cpp @@ -0,0 +1,340 @@ +#include +#include + +#include +#include +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +typedef Fun FunDouble; +typedef PrimitiveRef PrimitiveRefDouble; +typedef MyVector<3> MyVector3; +typedef MyVector<12> MyVector12; +typedef MultipleTemplates MultipleTemplatesIntDouble; +typedef MultipleTemplates MultipleTemplatesIntFloat; +typedef MyFactor MyFactorPosePoint2; +typedef MyTemplate MyTemplatePoint2; +typedef MyTemplate MyTemplateMatrix; +typedef gtsam::PinholeCamera PinholeCameraCal3Bundler; + +BOOST_CLASS_EXPORT_GUID(gtsam::Point2, "gtsamPoint2"); +BOOST_CLASS_EXPORT_GUID(gtsam::Point3, "gtsamPoint3"); + +typedef std::set*> Collector_FunRange; +static Collector_FunRange collector_FunRange; +typedef std::set*> Collector_FunDouble; +static Collector_FunDouble collector_FunDouble; +typedef std::set*> Collector_Test; +static Collector_Test collector_Test; +typedef std::set*> Collector_PrimitiveRefDouble; +static Collector_PrimitiveRefDouble collector_PrimitiveRefDouble; +typedef std::set*> Collector_MyVector3; +static Collector_MyVector3 collector_MyVector3; +typedef std::set*> Collector_MyVector12; +static Collector_MyVector12 collector_MyVector12; +typedef std::set*> Collector_MultipleTemplatesIntDouble; +static Collector_MultipleTemplatesIntDouble collector_MultipleTemplatesIntDouble; +typedef std::set*> Collector_MultipleTemplatesIntFloat; +static Collector_MultipleTemplatesIntFloat collector_MultipleTemplatesIntFloat; +typedef std::set*> Collector_MyFactorPosePoint2; +static Collector_MyFactorPosePoint2 collector_MyFactorPosePoint2; +typedef std::set*> Collector_gtsamPoint2; +static Collector_gtsamPoint2 collector_gtsamPoint2; +typedef std::set*> Collector_gtsamPoint3; +static Collector_gtsamPoint3 collector_gtsamPoint3; +typedef std::set*> Collector_MyBase; +static Collector_MyBase collector_MyBase; +typedef std::set*> Collector_MyTemplatePoint2; +static Collector_MyTemplatePoint2 collector_MyTemplatePoint2; +typedef std::set*> Collector_MyTemplateMatrix; +static Collector_MyTemplateMatrix collector_MyTemplateMatrix; +typedef std::set*> Collector_ns1ClassA; +static Collector_ns1ClassA collector_ns1ClassA; +typedef std::set*> Collector_ns1ClassB; +static Collector_ns1ClassB collector_ns1ClassB; +typedef std::set*> Collector_ns2ClassA; +static Collector_ns2ClassA collector_ns2ClassA; +typedef std::set*> Collector_ns2ns3ClassB; +static Collector_ns2ns3ClassB collector_ns2ns3ClassB; +typedef std::set*> Collector_ns2ClassC; +static Collector_ns2ClassC collector_ns2ClassC; +typedef std::set*> Collector_ClassD; +static Collector_ClassD collector_ClassD; +typedef std::set*> Collector_gtsamNonlinearFactorGraph; +static Collector_gtsamNonlinearFactorGraph collector_gtsamNonlinearFactorGraph; +typedef std::set*> Collector_gtsamPinholeCameraCal3Bundler; +static Collector_gtsamPinholeCameraCal3Bundler collector_gtsamPinholeCameraCal3Bundler; + +void _deleteAllObjects() +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + bool anyDeleted = false; + { for(Collector_FunRange::iterator iter = collector_FunRange.begin(); + iter != collector_FunRange.end(); ) { + delete *iter; + collector_FunRange.erase(iter++); + anyDeleted = true; + } } + { for(Collector_FunDouble::iterator iter = collector_FunDouble.begin(); + iter != collector_FunDouble.end(); ) { + delete *iter; + collector_FunDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_Test::iterator iter = collector_Test.begin(); + iter != collector_Test.end(); ) { + delete *iter; + collector_Test.erase(iter++); + anyDeleted = true; + } } + { for(Collector_PrimitiveRefDouble::iterator iter = collector_PrimitiveRefDouble.begin(); + iter != collector_PrimitiveRefDouble.end(); ) { + delete *iter; + collector_PrimitiveRefDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyVector3::iterator iter = collector_MyVector3.begin(); + iter != collector_MyVector3.end(); ) { + delete *iter; + collector_MyVector3.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyVector12::iterator iter = collector_MyVector12.begin(); + iter != collector_MyVector12.end(); ) { + delete *iter; + collector_MyVector12.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MultipleTemplatesIntDouble::iterator iter = collector_MultipleTemplatesIntDouble.begin(); + iter != collector_MultipleTemplatesIntDouble.end(); ) { + delete *iter; + collector_MultipleTemplatesIntDouble.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MultipleTemplatesIntFloat::iterator iter = collector_MultipleTemplatesIntFloat.begin(); + iter != collector_MultipleTemplatesIntFloat.end(); ) { + delete *iter; + collector_MultipleTemplatesIntFloat.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyFactorPosePoint2::iterator iter = collector_MyFactorPosePoint2.begin(); + iter != collector_MyFactorPosePoint2.end(); ) { + delete *iter; + collector_MyFactorPosePoint2.erase(iter++); + anyDeleted = true; + } } + { for(Collector_gtsamPoint2::iterator iter = collector_gtsamPoint2.begin(); + iter != collector_gtsamPoint2.end(); ) { + delete *iter; + collector_gtsamPoint2.erase(iter++); + anyDeleted = true; + } } + { for(Collector_gtsamPoint3::iterator iter = collector_gtsamPoint3.begin(); + iter != collector_gtsamPoint3.end(); ) { + delete *iter; + collector_gtsamPoint3.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyBase::iterator iter = collector_MyBase.begin(); + iter != collector_MyBase.end(); ) { + delete *iter; + collector_MyBase.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyTemplatePoint2::iterator iter = collector_MyTemplatePoint2.begin(); + iter != collector_MyTemplatePoint2.end(); ) { + delete *iter; + collector_MyTemplatePoint2.erase(iter++); + anyDeleted = true; + } } + { for(Collector_MyTemplateMatrix::iterator iter = collector_MyTemplateMatrix.begin(); + iter != collector_MyTemplateMatrix.end(); ) { + delete *iter; + collector_MyTemplateMatrix.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ns1ClassA::iterator iter = collector_ns1ClassA.begin(); + iter != collector_ns1ClassA.end(); ) { + delete *iter; + collector_ns1ClassA.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ns1ClassB::iterator iter = collector_ns1ClassB.begin(); + iter != collector_ns1ClassB.end(); ) { + delete *iter; + collector_ns1ClassB.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ns2ClassA::iterator iter = collector_ns2ClassA.begin(); + iter != collector_ns2ClassA.end(); ) { + delete *iter; + collector_ns2ClassA.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ns2ns3ClassB::iterator iter = collector_ns2ns3ClassB.begin(); + iter != collector_ns2ns3ClassB.end(); ) { + delete *iter; + collector_ns2ns3ClassB.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ns2ClassC::iterator iter = collector_ns2ClassC.begin(); + iter != collector_ns2ClassC.end(); ) { + delete *iter; + collector_ns2ClassC.erase(iter++); + anyDeleted = true; + } } + { for(Collector_ClassD::iterator iter = collector_ClassD.begin(); + iter != collector_ClassD.end(); ) { + delete *iter; + collector_ClassD.erase(iter++); + anyDeleted = true; + } } + { for(Collector_gtsamNonlinearFactorGraph::iterator iter = collector_gtsamNonlinearFactorGraph.begin(); + iter != collector_gtsamNonlinearFactorGraph.end(); ) { + delete *iter; + collector_gtsamNonlinearFactorGraph.erase(iter++); + anyDeleted = true; + } } + { for(Collector_gtsamPinholeCameraCal3Bundler::iterator iter = collector_gtsamPinholeCameraCal3Bundler.begin(); + iter != collector_gtsamPinholeCameraCal3Bundler.end(); ) { + delete *iter; + collector_gtsamPinholeCameraCal3Bundler.erase(iter++); + anyDeleted = true; + } } + if(anyDeleted) + cout << + "WARNING: Wrap modules with variables in the workspace have been reloaded due to\n" + "calling destructors, call 'clear all' again if you plan to now recompile a wrap\n" + "module, so that your recompiled module is used instead of the old one." << endl; + std::cout.rdbuf(outbuf); +} + +void _special_cases_RTTIRegister() { + const mxArray *alreadyCreated = mexGetVariablePtr("global", "gtsam_special_cases_rttiRegistry_created"); + if(!alreadyCreated) { + std::map types; + types.insert(std::make_pair(typeid(MyBase).name(), "MyBase")); + types.insert(std::make_pair(typeid(MyTemplatePoint2).name(), "MyTemplatePoint2")); + types.insert(std::make_pair(typeid(MyTemplateMatrix).name(), "MyTemplateMatrix")); + + mxArray *registry = mexGetVariable("global", "gtsamwrap_rttiRegistry"); + if(!registry) + registry = mxCreateStructMatrix(1, 1, 0, NULL); + typedef std::pair StringPair; + for(const StringPair& rtti_matlab: types) { + int fieldId = mxAddField(registry, rtti_matlab.first.c_str()); + if(fieldId < 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxArray *matlabName = mxCreateString(rtti_matlab.second.c_str()); + mxSetFieldByNumber(registry, 0, fieldId, matlabName); + } + if(mexPutVariable("global", "gtsamwrap_rttiRegistry", registry) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(registry); + + mxArray *newAlreadyCreated = mxCreateNumericMatrix(0, 0, mxINT8_CLASS, mxREAL); + if(mexPutVariable("global", "gtsam_geometry_rttiRegistry_created", newAlreadyCreated) != 0) + mexErrMsgTxt("gtsam wrap: Error indexing RTTI types, inheritance will not work correctly"); + mxDestroyArray(newAlreadyCreated); + } +} + +void gtsamNonlinearFactorGraph_collectorInsertAndMakeBase_0(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_gtsamNonlinearFactorGraph.insert(self); +} + +void gtsamNonlinearFactorGraph_deconstructor_1(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr Shared; + checkArguments("delete_gtsamNonlinearFactorGraph",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_gtsamNonlinearFactorGraph::iterator item; + item = collector_gtsamNonlinearFactorGraph.find(self); + if(item != collector_gtsamNonlinearFactorGraph.end()) { + delete self; + collector_gtsamNonlinearFactorGraph.erase(item); + } +} + +void gtsamNonlinearFactorGraph_addPrior_2(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + checkArguments("addPriorPinholeCameraCal3Bundler",nargout,nargin-1,3); + auto obj = unwrap_shared_ptr(in[0], "ptr_gtsamNonlinearFactorGraph"); + size_t key = unwrap< size_t >(in[1]); + gtsam::PinholeCamera& prior = *unwrap_shared_ptr< gtsam::PinholeCamera >(in[2], "ptr_gtsamPinholeCameraCal3Bundler"); + boost::shared_ptr noiseModel = unwrap_shared_ptr< gtsam::noiseModel::Base >(in[3], "ptr_gtsamnoiseModelBase"); + obj->addPrior>(key,prior,noiseModel); +} + +void gtsamPinholeCameraCal3Bundler_collectorInsertAndMakeBase_3(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mexAtExit(&_deleteAllObjects); + typedef boost::shared_ptr> Shared; + + Shared *self = *reinterpret_cast (mxGetData(in[0])); + collector_gtsamPinholeCameraCal3Bundler.insert(self); +} + +void gtsamPinholeCameraCal3Bundler_deconstructor_4(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + typedef boost::shared_ptr> Shared; + checkArguments("delete_gtsamPinholeCameraCal3Bundler",nargout,nargin,1); + Shared *self = *reinterpret_cast(mxGetData(in[0])); + Collector_gtsamPinholeCameraCal3Bundler::iterator item; + item = collector_gtsamPinholeCameraCal3Bundler.find(self); + if(item != collector_gtsamPinholeCameraCal3Bundler.end()) { + delete self; + collector_gtsamPinholeCameraCal3Bundler.erase(item); + } +} + + +void mexFunction(int nargout, mxArray *out[], int nargin, const mxArray *in[]) +{ + mstream mout; + std::streambuf *outbuf = std::cout.rdbuf(&mout); + + _special_cases_RTTIRegister(); + + int id = unwrap(in[0]); + + try { + switch(id) { + case 0: + gtsamNonlinearFactorGraph_collectorInsertAndMakeBase_0(nargout, out, nargin-1, in+1); + break; + case 1: + gtsamNonlinearFactorGraph_deconstructor_1(nargout, out, nargin-1, in+1); + break; + case 2: + gtsamNonlinearFactorGraph_addPrior_2(nargout, out, nargin-1, in+1); + break; + case 3: + gtsamPinholeCameraCal3Bundler_collectorInsertAndMakeBase_3(nargout, out, nargin-1, in+1); + break; + case 4: + gtsamPinholeCameraCal3Bundler_deconstructor_4(nargout, out, nargin-1, in+1); + break; + } + } catch(const std::exception& e) { + mexErrMsgTxt(("Exception from gtsam:\n" + std::string(e.what()) + "\n").c_str()); + } + + std::cout.rdbuf(outbuf); +} diff --git a/tests/expected/python/special_cases_pybind.cpp b/tests/expected/python/special_cases_pybind.cpp new file mode 100644 index 000000000..fb15a004d --- /dev/null +++ b/tests/expected/python/special_cases_pybind.cpp @@ -0,0 +1,35 @@ + + +#include +#include +#include +#include "gtsam/nonlinear/utilities.h" // for RedirectCout. + +#include "gtsam/geometry/Cal3Bundler.h" + +#include "wrap/serialization.h" +#include + + + + + +using namespace std; + +namespace py = pybind11; + +PYBIND11_MODULE(special_cases_py, m_) { + m_.doc() = "pybind11 wrapper of special_cases_py"; + + pybind11::module m_gtsam = m_.def_submodule("gtsam", "gtsam submodule"); + + py::class_>(m_gtsam, "NonlinearFactorGraph") + .def("addPriorPinholeCameraCal3Bundler",[](gtsam::NonlinearFactorGraph* self, size_t key, const gtsam::PinholeCamera& prior, const std::shared_ptr& noiseModel){ self->addPrior>(key, prior, noiseModel);}, py::arg("key"), py::arg("prior"), py::arg("noiseModel")); + + py::class_, std::shared_ptr>>(m_gtsam, "PinholeCameraCal3Bundler"); + + +#include "python/specializations.h" + +} + diff --git a/tests/fixtures/special_cases.i b/tests/fixtures/special_cases.i new file mode 100644 index 000000000..9451eed24 --- /dev/null +++ b/tests/fixtures/special_cases.i @@ -0,0 +1,17 @@ +// Check for templated class as template argument for method! +namespace gtsam { + +#include + +class Cal3Bundler; + +template +class PinholeCamera {}; +typedef gtsam::PinholeCamera PinholeCameraCal3Bundler; + +class NonlinearFactorGraph { + template}> + void addPrior(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); +}; + +} \ No newline at end of file diff --git a/tests/test_matlab_wrapper.py b/tests/test_matlab_wrapper.py index 83398f72a..02d40cb45 100644 --- a/tests/test_matlab_wrapper.py +++ b/tests/test_matlab_wrapper.py @@ -36,7 +36,7 @@ class TestWrap(unittest.TestCase): logger.remove() # remove the default sink logger.add(sys.stderr, format="{time} {level} {message}", level="INFO") - def generate_content(self, cc_content, path=''): + def generate_content(self, cc_content, path=MATLAB_ACTUAL_DIR): """Generate files and folders from matlab wrapper content. Keyword arguments: @@ -45,9 +45,6 @@ class TestWrap(unittest.TestCase): (folder_name, [(file_name, file_content)]) path -- the path to the files parent folder within the main folder """ - if path == '': - path = self.MATLAB_ACTUAL_DIR - for c in cc_content: if isinstance(c, list): if len(c) == 0: @@ -275,6 +272,39 @@ class TestWrap(unittest.TestCase): for file in files: self.compare_and_diff(file) + def test_special_cases(self): + """ + Tests for some unique, non-trivial features. + """ + with open(osp.join(self.INTERFACE_DIR, 'special_cases.i'), 'r') as f: + content = f.read() + + if not osp.exists(self.MATLAB_ACTUAL_DIR): + os.mkdir(self.MATLAB_ACTUAL_DIR) + + module = parser.Module.parseString(content) + + instantiator.instantiate_namespace_inplace(module) + + wrapper = MatlabWrapper( + module=module, + module_name='special_cases', + top_module_namespace=['gtsam'], + ignore_classes=[''], + ) + + cc_content = wrapper.wrap() + + self.generate_content(cc_content) + + files = [ + 'special_cases_wrapper.cpp', + '+gtsam/PinholeCameraCal3Bundler.m', + '+gtsam/NonlinearFactorGraph.m', + ] + + for file in files: + self.compare_and_diff(file) if __name__ == '__main__': unittest.main() diff --git a/tests/test_pybind_wrapper.py b/tests/test_pybind_wrapper.py index 5f6b82141..c5df5deb5 100644 --- a/tests/test_pybind_wrapper.py +++ b/tests/test_pybind_wrapper.py @@ -134,6 +134,18 @@ class TestWrap(unittest.TestCase): self.compare_and_diff('namespaces_pybind.cpp', output) + def test_special_cases(self): + """ + Tests for some unique, non-trivial features. + """ + with open(osp.join(self.INTERFACE_DIR, 'special_cases.i'), 'r') as f: + content = f.read() + + output = self.wrap_content(content, 'special_cases_py', + self.PYTHON_ACTUAL_DIR) + + self.compare_and_diff('special_cases_pybind.cpp', output) + if __name__ == '__main__': unittest.main() From ef2cd5dab54e87ef864b7fda2e29de47f6896c3a Mon Sep 17 00:00:00 2001 From: Milo Knowles Date: Fri, 26 Mar 2021 08:59:44 -0400 Subject: [PATCH 16/21] Fix x/y mismatch in unit tests --- gtsam_unstable/slam/tests/testPartialPriorFactor.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp b/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp index 8a77bc5b9..55be97d9d 100644 --- a/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp +++ b/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp @@ -38,7 +38,6 @@ struct traits : public Testable }; } - /* ************************************************************************* */ TEST(PartialPriorFactor, JacobianAtIdentity) { @@ -46,7 +45,7 @@ TEST(PartialPriorFactor, JacobianAtIdentity) Pose3 measurement = Pose3::identity(); SharedNoiseModel model = noiseModel::Isotropic::Sigma(1, 0.25); - TestPartialPriorFactor factor(poseKey, kIndexTy, measurement.translation().x(), model); + TestPartialPriorFactor factor(poseKey, kIndexTy, measurement.translation().y(), model); // Create a linearization point at the zero-error point Pose3 pose = Pose3::identity(); @@ -63,14 +62,13 @@ TEST(PartialPriorFactor, JacobianAtIdentity) CHECK(assert_equal(expectedH1, actualH1, 1e-5)); } - /* ************************************************************************* */ TEST(PartialPriorFactor, JacobianPartialTranslation) { Key poseKey(1); Pose3 measurement(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); SharedNoiseModel model = noiseModel::Isotropic::Sigma(1, 0.25); - TestPartialPriorFactor factor(poseKey, kIndexTy, measurement.translation().x(), model); + TestPartialPriorFactor factor(poseKey, kIndexTy, measurement.translation().y(), model); // Create a linearization point at the zero-error point Pose3 pose(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); From 74b92efd89655659c34f89749c11e861deefc10c Mon Sep 17 00:00:00 2001 From: Milo Knowles Date: Fri, 26 Mar 2021 09:55:25 -0400 Subject: [PATCH 17/21] Add constructor tests and extend tests to Pose2 --- .../slam/tests/testPartialPriorFactor.cpp | 206 +++++++++++++++--- 1 file changed, 176 insertions(+), 30 deletions(-) diff --git a/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp b/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp index 55be97d9d..8a3a2a63b 100644 --- a/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp +++ b/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp @@ -11,6 +11,7 @@ #include #include +#include #include #include #include @@ -19,8 +20,9 @@ using namespace std; using namespace gtsam; +namespace NM = gtsam::noiseModel; -// Pose representation is [ Rx Ry Rz Tx Ty Tz ]. +// Pose3 tangent representation is [ Rx Ry Rz Tx Ty Tz ]. static const int kIndexRx = 0; static const int kIndexRy = 1; static const int kIndexRz = 2; @@ -29,30 +31,152 @@ static const int kIndexTy = 4; static const int kIndexTz = 5; -typedef PartialPriorFactor TestPartialPriorFactor; +typedef PartialPriorFactor TestPartialPriorFactor2; +typedef PartialPriorFactor TestPartialPriorFactor3; +typedef std::vector Indices; /// traits namespace gtsam { template<> -struct traits : public Testable { -}; +struct traits : public Testable {}; + +template<> +struct traits : public Testable {}; } /* ************************************************************************* */ -TEST(PartialPriorFactor, JacobianAtIdentity) -{ +TEST(PartialPriorFactor, Constructors2) { + Key poseKey(1); + Pose2 measurement(-13.1, 3.14, -0.73); + + // Prior on x component of translation. + TestPartialPriorFactor2 factor1(poseKey, 0, measurement.x(), NM::Isotropic::Sigma(1, 0.25)); + CHECK(assert_equal(1, factor1.prior().rows())); + CHECK(assert_equal(measurement.x(), factor1.prior()(0))); + CHECK(assert_container_equality({ 0 }, factor1.indices())); + + // Prior on full translation vector. + const Indices t_indices = { 0, 1 }; + TestPartialPriorFactor2 factor2(poseKey, t_indices, measurement.translation(), NM::Isotropic::Sigma(2, 0.25)); + CHECK(assert_equal(2, factor2.prior().rows())); + CHECK(assert_equal(measurement.translation(), factor2.prior())); + CHECK(assert_container_equality(t_indices, factor2.indices())); + + // Prior on theta. + TestPartialPriorFactor2 factor3(poseKey, 2, measurement.theta(), NM::Isotropic::Sigma(1, 0.1)); + CHECK(assert_equal(1, factor3.prior().rows())); + CHECK(assert_equal(measurement.theta(), factor3.prior()(0))); + CHECK(assert_container_equality({ 2 }, factor3.indices())); +} + +/* ************************************************************************* */ +TEST(PartialPriorFactor, JacobianPartialTranslation2) { + Key poseKey(1); + Pose2 measurement(-13.1, 3.14, -0.73); + + // Prior on x component of translation. + TestPartialPriorFactor2 factor(poseKey, 0, measurement.x(), NM::Isotropic::Sigma(1, 0.25)); + + Pose2 pose = measurement; // Zero-error linearization point. + + // Calculate numerical derivatives. + Matrix expectedH1 = numericalDerivative11( + boost::bind(&TestPartialPriorFactor2::evaluateError, &factor, _1, boost::none), pose); + + // Use the factor to calculate the derivative. + Matrix actualH1; + factor.evaluateError(pose, actualH1); + + // Verify we get the expected error. + CHECK(assert_equal(expectedH1, actualH1, 1e-5)); +} + +/* ************************************************************************* */ +TEST(PartialPriorFactor, JacobianFullTranslation2) { + Key poseKey(1); + Pose2 measurement(-6.0, 3.5, 0.123); + + // Prior on x component of translation. + TestPartialPriorFactor2 factor(poseKey, { 0, 1 }, measurement.translation(), NM::Isotropic::Sigma(2, 0.25)); + + Pose2 pose = measurement; // Zero-error linearization point. + + // Calculate numerical derivatives. + Matrix expectedH1 = numericalDerivative11( + boost::bind(&TestPartialPriorFactor2::evaluateError, &factor, _1, boost::none), pose); + + // Use the factor to calculate the derivative. + Matrix actualH1; + factor.evaluateError(pose, actualH1); + + // Verify we get the expected error. + CHECK(assert_equal(expectedH1, actualH1, 1e-5)); +} + +/* ************************************************************************* */ +TEST(PartialPriorFactor, JacobianTheta) { + Key poseKey(1); + Pose2 measurement(-1.0, 0.4, -2.5); + + // Prior on x component of translation. + TestPartialPriorFactor2 factor(poseKey, 2, measurement.theta(), NM::Isotropic::Sigma(1, 0.25)); + + Pose2 pose = measurement; // Zero-error linearization point. + + // Calculate numerical derivatives. + Matrix expectedH1 = numericalDerivative11( + boost::bind(&TestPartialPriorFactor2::evaluateError, &factor, _1, boost::none), pose); + + // Use the factor to calculate the derivative. + Matrix actualH1; + factor.evaluateError(pose, actualH1); + + // Verify we get the expected error. + CHECK(assert_equal(expectedH1, actualH1, 1e-5)); +} + +/* ************************************************************************* */ +TEST(PartialPriorFactor, Constructors3) { + Key poseKey(1); + Pose3 measurement(Rot3::RzRyRx(-0.17, 0.567, M_PI), Point3(10.0, -2.3, 3.14)); + + // Single component of translation. + TestPartialPriorFactor3 factor1(poseKey, kIndexTy, measurement.y(), + NM::Isotropic::Sigma(1, 0.25)); + CHECK(assert_equal(1, factor1.prior().rows())); + CHECK(assert_equal(measurement.y(), factor1.prior()(0))); + CHECK(assert_container_equality({ kIndexTy }, factor1.indices())); + + // Full translation vector. + const Indices t_indices = { kIndexTx, kIndexTy, kIndexTz }; + TestPartialPriorFactor3 factor2(poseKey, t_indices, measurement.translation(), + NM::Isotropic::Sigma(3, 0.25)); + CHECK(assert_equal(3, factor2.prior().rows())); + CHECK(assert_equal(measurement.translation(), factor2.prior())); + CHECK(assert_container_equality(t_indices, factor2.indices())); + + // Full tangent vector of rotation. + const Indices r_indices = { kIndexRx, kIndexRy, kIndexRz }; + TestPartialPriorFactor3 factor3(poseKey, r_indices, Rot3::Logmap(measurement.rotation()), + NM::Isotropic::Sigma(3, 0.1)); + CHECK(assert_equal(3, factor3.prior().rows())); + CHECK(assert_equal(Rot3::Logmap(measurement.rotation()), factor3.prior())); + CHECK(assert_container_equality(r_indices, factor3.indices())); +} + +/* ************************************************************************* */ +TEST(PartialPriorFactor, JacobianAtIdentity3) { Key poseKey(1); Pose3 measurement = Pose3::identity(); - SharedNoiseModel model = noiseModel::Isotropic::Sigma(1, 0.25); + SharedNoiseModel model = NM::Isotropic::Sigma(1, 0.25); - TestPartialPriorFactor factor(poseKey, kIndexTy, measurement.translation().y(), model); + TestPartialPriorFactor3 factor(poseKey, kIndexTy, measurement.translation().y(), model); - // Create a linearization point at the zero-error point - Pose3 pose = Pose3::identity(); + Pose3 pose = measurement; // Zero-error linearization point. // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - boost::bind(&TestPartialPriorFactor::evaluateError, &factor, _1, boost::none), pose); + boost::bind(&TestPartialPriorFactor3::evaluateError, &factor, _1, boost::none), pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -63,19 +187,18 @@ TEST(PartialPriorFactor, JacobianAtIdentity) } /* ************************************************************************* */ -TEST(PartialPriorFactor, JacobianPartialTranslation) { +TEST(PartialPriorFactor, JacobianPartialTranslation3) { Key poseKey(1); Pose3 measurement(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); - SharedNoiseModel model = noiseModel::Isotropic::Sigma(1, 0.25); + SharedNoiseModel model = NM::Isotropic::Sigma(1, 0.25); - TestPartialPriorFactor factor(poseKey, kIndexTy, measurement.translation().y(), model); + TestPartialPriorFactor3 factor(poseKey, kIndexTy, measurement.translation().y(), model); - // Create a linearization point at the zero-error point - Pose3 pose(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); + Pose3 pose = measurement; // Zero-error linearization point. // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - boost::bind(&TestPartialPriorFactor::evaluateError, &factor, _1, boost::none), pose); + boost::bind(&TestPartialPriorFactor3::evaluateError, &factor, _1, boost::none), pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -86,20 +209,20 @@ TEST(PartialPriorFactor, JacobianPartialTranslation) { } /* ************************************************************************* */ -TEST(PartialPriorFactor, JacobianFullTranslation) { +TEST(PartialPriorFactor, JacobianFullTranslation3) { Key poseKey(1); Pose3 measurement(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); - SharedNoiseModel model = noiseModel::Isotropic::Sigma(3, 0.25); + SharedNoiseModel model = NM::Isotropic::Sigma(3, 0.25); std::vector translationIndices = { kIndexTx, kIndexTy, kIndexTz }; - TestPartialPriorFactor factor(poseKey, translationIndices, measurement.translation(), model); + TestPartialPriorFactor3 factor(poseKey, translationIndices, measurement.translation(), model); // Create a linearization point at the zero-error point - Pose3 pose(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); + Pose3 pose = measurement; // Zero-error linearization point. // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - boost::bind(&TestPartialPriorFactor::evaluateError, &factor, _1, boost::none), pose); + boost::bind(&TestPartialPriorFactor3::evaluateError, &factor, _1, boost::none), pose); // Use the factor to calculate the derivative. Matrix actualH1; @@ -110,20 +233,43 @@ TEST(PartialPriorFactor, JacobianFullTranslation) { } /* ************************************************************************* */ -TEST(PartialPriorFactor, JacobianFullRotation) { +TEST(PartialPriorFactor, JacobianTxTz3) { Key poseKey(1); - Pose3 measurement(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); - SharedNoiseModel model = noiseModel::Isotropic::Sigma(3, 0.25); + Pose3 measurement(Rot3::RzRyRx(-0.17, 0.567, M_PI), Point3(10.0, -2.3, 3.14)); + SharedNoiseModel model = NM::Isotropic::Sigma(2, 0.25); - std::vector rotationIndices = { kIndexRx, kIndexRy, kIndexRz }; - TestPartialPriorFactor factor(poseKey, rotationIndices, Rot3::Logmap(measurement.rotation()), model); + std::vector translationIndices = { kIndexTx, kIndexTz }; + TestPartialPriorFactor3 factor(poseKey, translationIndices, + (Vector(2) << measurement.x(), measurement.z()).finished(), model); - // Create a linearization point at the zero-error point - Pose3 pose(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); + Pose3 pose = measurement; // Zero-error linearization point. // Calculate numerical derivatives. Matrix expectedH1 = numericalDerivative11( - boost::bind(&TestPartialPriorFactor::evaluateError, &factor, _1, boost::none), pose); + boost::bind(&TestPartialPriorFactor3::evaluateError, &factor, _1, boost::none), pose); + + // Use the factor to calculate the derivative. + Matrix actualH1; + factor.evaluateError(pose, actualH1); + + // Verify we get the expected error. + CHECK(assert_equal(expectedH1, actualH1, 1e-5)); +} + +/* ************************************************************************* */ +TEST(PartialPriorFactor, JacobianFullRotation3) { + Key poseKey(1); + Pose3 measurement(Rot3::RzRyRx(0.15, -0.30, 0.45), Point3(-5.0, 8.0, -11.0)); + SharedNoiseModel model = NM::Isotropic::Sigma(3, 0.25); + + std::vector rotationIndices = { kIndexRx, kIndexRy, kIndexRz }; + TestPartialPriorFactor3 factor(poseKey, rotationIndices, Rot3::Logmap(measurement.rotation()), model); + + Pose3 pose = measurement; // Zero-error linearization point. + + // Calculate numerical derivatives. + Matrix expectedH1 = numericalDerivative11( + boost::bind(&TestPartialPriorFactor3::evaluateError, &factor, _1, boost::none), pose); // Use the factor to calculate the derivative. Matrix actualH1; From 05fad78ce917a4024d6a1c48b4ba35b3bd997be7 Mon Sep 17 00:00:00 2001 From: Milo Knowles Date: Fri, 26 Mar 2021 10:09:05 -0400 Subject: [PATCH 18/21] Switch to cleaner T::Logmap --- gtsam_unstable/slam/PartialPriorFactor.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index bc28a6830..7568a222f 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -111,14 +111,14 @@ namespace gtsam { Vector evaluateError(const T& p, boost::optional H = boost::none) const override { if (H) { Matrix H_logmap; - p.localCoordinates(T::identity(), H_logmap); + T::Logmap(p, H_logmap); (*H) = Matrix::Zero(indices_.size(), T::dimension); for (size_t i = 0; i < indices_.size(); ++i) { (*H).row(i) = H_logmap.row(indices_.at(i)); } } // Compute the tangent vector representation of T and select relevant parameters. - const Vector& full_logmap = p.localCoordinates(T::identity()); + const Vector& full_logmap = T::Logmap(p); Vector partial_logmap = Vector::Zero(T::dimension); for (size_t i = 0; i < indices_.size(); ++i) { partial_logmap(i) = full_logmap(indices_.at(i)); From 909b5500f8a43e4aa07c15086fd586069cd869c8 Mon Sep 17 00:00:00 2001 From: Milo Knowles Date: Fri, 26 Mar 2021 11:26:27 -0400 Subject: [PATCH 19/21] Fix incorrect Vector dimension that was causing CI failures --- gtsam_unstable/slam/PartialPriorFactor.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index 7568a222f..e92c23cb8 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -119,7 +119,7 @@ namespace gtsam { } // Compute the tangent vector representation of T and select relevant parameters. const Vector& full_logmap = T::Logmap(p); - Vector partial_logmap = Vector::Zero(T::dimension); + Vector partial_logmap = Vector::Zero(indices_.size()); for (size_t i = 0; i < indices_.size(); ++i) { partial_logmap(i) = full_logmap(indices_.at(i)); } From a0ff5e3886f751b6d2093e8f6d94efa869816510 Mon Sep 17 00:00:00 2001 From: Milo Knowles Date: Fri, 26 Mar 2021 14:36:43 -0400 Subject: [PATCH 20/21] Add LocalCoordinates() to ProductLieGroup and remove unnecessary include to reduce compile memory --- gtsam/base/ProductLieGroup.h | 3 ++ gtsam_unstable/dynamics/DynamicsPriors.h | 28 +++++++++++++------ gtsam_unstable/dynamics/PoseRTV.h | 1 + gtsam_unstable/slam/PartialPriorFactor.h | 16 +++++------ .../slam/tests/testPartialPriorFactor.cpp | 1 - 5 files changed, 30 insertions(+), 19 deletions(-) diff --git a/gtsam/base/ProductLieGroup.h b/gtsam/base/ProductLieGroup.h index 458538003..a2dcf738e 100644 --- a/gtsam/base/ProductLieGroup.h +++ b/gtsam/base/ProductLieGroup.h @@ -161,6 +161,9 @@ public: } return v; } + static TangentVector LocalCoordinates(const ProductLieGroup& p, ChartJacobian Hp = boost::none) { + return Logmap(p, Hp); + } ProductLieGroup expmap(const TangentVector& v) const { return compose(ProductLieGroup::Expmap(v)); } diff --git a/gtsam_unstable/dynamics/DynamicsPriors.h b/gtsam_unstable/dynamics/DynamicsPriors.h index e286b5fdc..d4ebcba19 100644 --- a/gtsam_unstable/dynamics/DynamicsPriors.h +++ b/gtsam_unstable/dynamics/DynamicsPriors.h @@ -9,20 +9,28 @@ #pragma once -#include - #include +#include namespace gtsam { +// Indices of relevant variables in the PoseRTV tangent vector: +// [ rx ry rz tx ty tz vx vy vz ] +static const size_t kRollIndex = 0; +static const size_t kPitchIndex = 1; +static const size_t kHeightIndex = 5; +static const size_t kVelocityZIndex = 8; +static const std::vector kVelocityIndices = { 6, 7, 8 }; + /** - * Forces the value of the height in a PoseRTV to a specific value + * Forces the value of the height (z) in a PoseRTV to a specific value. * Dim: 1 */ struct DHeightPrior : public gtsam::PartialPriorFactor { typedef gtsam::PartialPriorFactor Base; + DHeightPrior(Key key, double height, const gtsam::SharedNoiseModel& model) - : Base(key, 5, height, model) { } + : Base(key, kHeightIndex, height, model) {} }; /** @@ -35,11 +43,11 @@ struct DRollPrior : public gtsam::PartialPriorFactor { /** allows for explicit roll parameterization - uses canonical coordinate */ DRollPrior(Key key, double wx, const gtsam::SharedNoiseModel& model) - : Base(key, 0, wx, model) { } + : Base(key, kRollIndex, wx, model) { } /** Forces roll to zero */ DRollPrior(Key key, const gtsam::SharedNoiseModel& model) - : Base(key, 0, 0.0, model) { } + : Base(key, kRollIndex, 0.0, model) { } }; /** @@ -49,8 +57,9 @@ struct DRollPrior : public gtsam::PartialPriorFactor { */ struct VelocityPrior : public gtsam::PartialPriorFactor { typedef gtsam::PartialPriorFactor Base; + VelocityPrior(Key key, const gtsam::Vector& vel, const gtsam::SharedNoiseModel& model) - : Base(key, {6, 7, 8}, vel, model) {} + : Base(key, kVelocityIndices, vel, model) {} }; /** @@ -65,13 +74,14 @@ struct DGroundConstraint : public gtsam::PartialPriorFactor { * Primary constructor allows for variable height of the "floor" */ DGroundConstraint(Key key, double height, const gtsam::SharedNoiseModel& model) - : Base(key, {5, 8, 0, 1}, Vector::Unit(4,0)*height, model) {} + : Base(key, { kHeightIndex, kVelocityZIndex, kRollIndex, kPitchIndex }, + Vector::Unit(4, 0)*height, model) {} /** * Fully specify vector - use only for debugging */ DGroundConstraint(Key key, const Vector& constraint, const gtsam::SharedNoiseModel& model) - : Base(key, {5, 8, 0, 1}, constraint, model) { + : Base(key, { kHeightIndex, kVelocityZIndex, kRollIndex, kPitchIndex }, constraint, model) { assert(constraint.size() == 4); } }; diff --git a/gtsam_unstable/dynamics/PoseRTV.h b/gtsam_unstable/dynamics/PoseRTV.h index b1cfb6f30..c573de2b6 100644 --- a/gtsam_unstable/dynamics/PoseRTV.h +++ b/gtsam_unstable/dynamics/PoseRTV.h @@ -80,6 +80,7 @@ public: using Base::Dim; using Base::retract; using Base::localCoordinates; + using Base::LocalCoordinates; /// @} /// @name measurement functions diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index e92c23cb8..910ee7bbd 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -17,8 +17,6 @@ #pragma once -#include - #include #include @@ -110,21 +108,21 @@ namespace gtsam { /** Returns a vector of errors for the measured tangent parameters. */ Vector evaluateError(const T& p, boost::optional H = boost::none) const override { if (H) { - Matrix H_logmap; - T::Logmap(p, H_logmap); + Matrix H_local; + T::LocalCoordinates(p, H_local); (*H) = Matrix::Zero(indices_.size(), T::dimension); for (size_t i = 0; i < indices_.size(); ++i) { - (*H).row(i) = H_logmap.row(indices_.at(i)); + (*H).row(i) = H_local.row(indices_.at(i)); } } // Compute the tangent vector representation of T and select relevant parameters. - const Vector& full_logmap = T::Logmap(p); - Vector partial_logmap = Vector::Zero(indices_.size()); + const Vector& full_tangent = T::LocalCoordinates(p); + Vector partial_tangent = Vector::Zero(indices_.size()); for (size_t i = 0; i < indices_.size(); ++i) { - partial_logmap(i) = full_logmap(indices_.at(i)); + partial_tangent(i) = full_tangent(indices_.at(i)); } - return partial_logmap - prior_; + return partial_tangent - prior_; } // access diff --git a/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp b/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp index 8a3a2a63b..ae8074f43 100644 --- a/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp +++ b/gtsam_unstable/slam/tests/testPartialPriorFactor.cpp @@ -30,7 +30,6 @@ static const int kIndexTx = 3; static const int kIndexTy = 4; static const int kIndexTz = 5; - typedef PartialPriorFactor TestPartialPriorFactor2; typedef PartialPriorFactor TestPartialPriorFactor3; typedef std::vector Indices; From 1f12f82e01506b4596c06b97292d405707aa5a66 Mon Sep 17 00:00:00 2001 From: Milo Knowles Date: Fri, 26 Mar 2021 17:29:47 -0400 Subject: [PATCH 21/21] Fix Rot3::LocalCoordinates runtime error when using Cayley map --- gtsam_unstable/slam/PartialPriorFactor.h | 15 +++++++++++---- 1 file changed, 11 insertions(+), 4 deletions(-) diff --git a/gtsam_unstable/slam/PartialPriorFactor.h b/gtsam_unstable/slam/PartialPriorFactor.h index 910ee7bbd..52a57b945 100644 --- a/gtsam_unstable/slam/PartialPriorFactor.h +++ b/gtsam_unstable/slam/PartialPriorFactor.h @@ -107,16 +107,23 @@ namespace gtsam { /** Returns a vector of errors for the measured tangent parameters. */ Vector evaluateError(const T& p, boost::optional H = boost::none) const override { + Eigen::Matrix H_local; + + // If the Rot3 Cayley map is used, Rot3::LocalCoordinates will throw a runtime error + // when asked to compute the Jacobian matrix (see Rot3M.cpp). + #ifdef GTSAM_ROT3_EXPMAP + const Vector full_tangent = T::LocalCoordinates(p, H ? &H_local : nullptr); + #else + const Vector full_tangent = T::Logmap(p, H ? &H_local : nullptr); + #endif + if (H) { - Matrix H_local; - T::LocalCoordinates(p, H_local); (*H) = Matrix::Zero(indices_.size(), T::dimension); for (size_t i = 0; i < indices_.size(); ++i) { (*H).row(i) = H_local.row(indices_.at(i)); } } - // Compute the tangent vector representation of T and select relevant parameters. - const Vector& full_tangent = T::LocalCoordinates(p); + // Select relevant parameters from the tangent vector. Vector partial_tangent = Vector::Zero(indices_.size()); for (size_t i = 0; i < indices_.size(); ++i) { partial_tangent(i) = full_tangent(indices_.at(i));